QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
StructureScanComplexItem.cc
Go to the documentation of this file.
2#include "JsonParsing.h"
3#include "MissionController.h"
4#include "QGCApplication.h"
5#include "SettingsManager.h"
6#include "AppSettings.h"
8#include "FlightPathSegment.h"
9#include "QGCMath.h"
10#include "QGCLoggingCategory.h"
11
12#include <QtCore/QJsonArray>
13
14QGC_LOGGING_CATEGORY(StructureScanComplexItemLog, "Plan.StructureScanComplexItem")
15
16StructureScanComplexItem::StructureScanComplexItem(PlanMasterController* masterController, bool flyView, const QString& kmlOrShpFile)
17 : ComplexMissionItem (masterController, flyView)
18 , _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/StructureScan.SettingsGroup.json"), this /* QObject parent */))
19 , _sequenceNumber (0)
20 , _entryVertex (0)
21, _ignoreRecalc (false)
22 , _scanDistance (0.0)
23 , _cameraShots (0)
24 , _cameraCalc (masterController, settingsGroup)
25 , _scanBottomAltFact (settingsGroup, _metaDataMap[scanBottomAltName])
26 , _structureHeightFact (settingsGroup, _metaDataMap[structureHeightName])
27 , _layersFact (settingsGroup, _metaDataMap[layersName])
28 , _gimbalPitchFact (settingsGroup, _metaDataMap[gimbalPitchName])
29 , _startFromTopFact (settingsGroup, _metaDataMap[startFromTopName])
30 , _entranceAltFact (settingsGroup, _metaDataMap[_entranceAltName])
31{
32 _editorQml = "qrc:/qml/QGroundControl/PlanView/StructureScanEditor.qml";
33
34 _entranceAltFact.setRawValue(SettingsManager::instance()->appSettings()->defaultMissionItemAltitude()->rawValue());
35
36 connect(&_entranceAltFact, &Fact::valueChanged, this, &StructureScanComplexItem::_setDirty);
37 connect(&_scanBottomAltFact, &Fact::valueChanged, this, &StructureScanComplexItem::_setDirty);
38 connect(&_layersFact, &Fact::valueChanged, this, &StructureScanComplexItem::_setDirty);
39 connect(&_gimbalPitchFact, &Fact::valueChanged, this, &StructureScanComplexItem::_setDirty);
40 connect(&_startFromTopFact, &Fact::valueChanged, this, &StructureScanComplexItem::_setDirty);
41
42 connect(&_startFromTopFact, &Fact::valueChanged, this, &StructureScanComplexItem::_signalTopBottomAltChanged);
43 connect(&_layersFact, &Fact::valueChanged, this, &StructureScanComplexItem::_signalTopBottomAltChanged);
44
45 connect(&_structureHeightFact, &Fact::valueChanged, this, &StructureScanComplexItem::_recalcLayerInfo);
46 connect(&_scanBottomAltFact, &Fact::valueChanged, this, &StructureScanComplexItem::_recalcLayerInfo);
47 connect(_cameraCalc.adjustedFootprintFrontal(), &Fact::valueChanged, this, &StructureScanComplexItem::_recalcLayerInfo);
48
49 connect(&_entranceAltFact, &Fact::valueChanged, this, &StructureScanComplexItem::_updateCoordinateAltitudes);
50
51 connect(&_structurePolygon, &QGCMapPolygon::dirtyChanged, this, &StructureScanComplexItem::_polygonDirtyChanged);
52 connect(&_structurePolygon, &QGCMapPolygon::pathChanged, this, &StructureScanComplexItem::_rebuildFlightPolygon);
54 connect(&_structurePolygon, &QGCMapPolygon::isValidChanged, this, &StructureScanComplexItem::_updateWizardMode);
55 connect(&_structurePolygon, &QGCMapPolygon::traceModeChanged, this, &StructureScanComplexItem::_updateWizardMode);
56
57 connect(&_structurePolygon, &QGCMapPolygon::countChanged, this, &StructureScanComplexItem::_updateLastSequenceNumber);
58 connect(&_layersFact, &Fact::valueChanged, this, &StructureScanComplexItem::_updateLastSequenceNumber);
59
60 connect(&_flightPolygon, &QGCMapPolygon::pathChanged, this, &StructureScanComplexItem::_flightPathChanged);
61
62 connect(_cameraCalc.distanceToSurface(), &Fact::valueChanged, this, &StructureScanComplexItem::_rebuildFlightPolygon);
63
64 connect(&_flightPolygon, &QGCMapPolygon::pathChanged, this, &StructureScanComplexItem::_recalcCameraShots);
65 connect(_cameraCalc.adjustedFootprintSide(), &Fact::valueChanged, this, &StructureScanComplexItem::_recalcCameraShots);
66 connect(&_layersFact, &Fact::valueChanged, this, &StructureScanComplexItem::_recalcCameraShots);
67
68 connect(&_cameraCalc, &CameraCalc::isManualCameraChanged, this, &StructureScanComplexItem::_updateGimbalPitch);
69
70 connect(&_layersFact, &Fact::valueChanged, this, &StructureScanComplexItem::_recalcScanDistance);
71 connect(&_flightPolygon, &QGCMapPolygon::pathChanged, this, &StructureScanComplexItem::_recalcScanDistance);
72
74
77
78 connect(&_entranceAltFact, &Fact::valueChanged, this, &StructureScanComplexItem::_amslEntryAltChanged);
80
87
92 connect(_cameraCalc.adjustedFootprintFrontal(), &Fact::valueChanged, this, &StructureScanComplexItem::_updateFlightPathSegmentsSignal);
96
97 // The follow is used to compress multiple recalc calls in a row to into a single call.
98 connect(this, &StructureScanComplexItem::_updateFlightPathSegmentsSignal, this, &StructureScanComplexItem::_updateFlightPathSegmentsDontCallDirectly, Qt::QueuedConnection);
99 qgcApp()->addCompressedSignal(QMetaMethod::fromSignal(&StructureScanComplexItem::_updateFlightPathSegmentsSignal));
100
101 _recalcLayerInfo();
102
103 if (!kmlOrShpFile.isEmpty()) {
104 _structurePolygon.loadKMLOrSHPFile(kmlOrShpFile);
105 _structurePolygon.setDirty(false);
106 }
107
108 setDirty(false);
109}
110
111void StructureScanComplexItem::_setCameraShots(int cameraShots)
112{
113 if (_cameraShots != cameraShots) {
114 _cameraShots = cameraShots;
115 emit cameraShotsChanged(this->cameraShots());
116 }
117}
118
119void StructureScanComplexItem::_clearInternal(void)
120{
121 setDirty(true);
122
125}
126
127void StructureScanComplexItem::_updateLastSequenceNumber(void)
128{
130}
131
133{
134 // Each structure layer contains:
135 // 1 waypoint for each polygon vertex + 1 to go back to first polygon vertex for each layer
136 // Two commands for camera trigger start/stop
137 int layerItemCount = _flightPolygon.count() + 1 + 2;
138
139 // Take into account the number of layers
140 int multiLayerItemCount = layerItemCount * _layersFact.rawValue().toInt();
141
142 // +2 for ROI_WPNEXT_OFFSET and ROI_NONE commands
143 // +2 for entrance/exit waypoints
144 int itemCount = multiLayerItemCount + 2 + 2;
145
146 return _sequenceNumber + itemCount - 1;
147}
148
150{
151 if (_dirty != dirty) {
152 _dirty = dirty;
153 emit dirtyChanged(_dirty);
154 }
155}
156
157void StructureScanComplexItem::save(QJsonArray& missionItems)
158{
159 QJsonObject saveObject;
160
161 // Header
162 saveObject[JsonParsing::jsonVersionKey] = 3;
165
166 saveObject[_entranceAltName] = _entranceAltFact.rawValue().toDouble();
167 saveObject[scanBottomAltName] = _scanBottomAltFact.rawValue().toDouble();
168 saveObject[structureHeightName] = _structureHeightFact.rawValue().toDouble();
169 saveObject[layersName] = _layersFact.rawValue().toDouble();
170 saveObject[gimbalPitchName] = _gimbalPitchFact.rawValue().toDouble();
171 saveObject[startFromTopName] = _startFromTopFact.rawValue().toBool();
172
173 QJsonObject cameraCalcObject;
174 _cameraCalc.save(cameraCalcObject);
175 saveObject[_jsonCameraCalcKey] = cameraCalcObject;
176
177 _structurePolygon.saveToJson(saveObject);
178
179 missionItems.append(saveObject);
180}
181
183{
184 if (_sequenceNumber != sequenceNumber) {
185 _sequenceNumber = sequenceNumber;
188 }
189}
190
191bool StructureScanComplexItem::load(const QJsonObject& complexObject, int sequenceNumber, QString& errorString)
192{
193 QList<JsonParsing::KeyValidateInfo> keyInfoList = {
194 { JsonParsing::jsonVersionKey, QJsonValue::Double, true },
195 { VisualMissionItem::jsonTypeKey, QJsonValue::String, true },
196 { ComplexMissionItem::jsonComplexItemTypeKey, QJsonValue::String, true },
197 { QGCMapPolygon::jsonPolygonKey, QJsonValue::Array, true },
198 { scanBottomAltName, QJsonValue::Double, true },
199 { structureHeightName, QJsonValue::Double, true },
200 { layersName, QJsonValue::Double, true },
201 { _jsonCameraCalcKey, QJsonValue::Object, true },
202 { _entranceAltName, QJsonValue::Double, true },
203 { gimbalPitchName, QJsonValue::Double, true },
204 { startFromTopName, QJsonValue::Bool, true },
205 };
206 if (!JsonParsing::validateKeys(complexObject, keyInfoList, errorString)) {
207 return false;
208 }
209
210 _structurePolygon.clear();
211
212 QString itemType = complexObject[VisualMissionItem::jsonTypeKey].toString();
213 QString complexType = complexObject[ComplexMissionItem::jsonComplexItemTypeKey].toString();
215 errorString = tr("%1 does not support loading this complex mission item type: %2:%3").arg(qgcApp()->applicationName()).arg(itemType).arg(complexType);
216 return false;
217 }
218
219 int version = complexObject[JsonParsing::jsonVersionKey].toInt();
220 if (version != 3) {
221 errorString = tr("%1 version %2 not supported").arg(jsonComplexItemTypeValue).arg(version);
222 return false;
223 }
224
226
227 // Load CameraCalc first since it will trigger camera name change which will trounce gimbal angles
228 if (!_cameraCalc.load(complexObject[_jsonCameraCalcKey].toObject(), false /* v1FollowTerrain */, errorString, false /* forPresets */)) {
229 return false;
230 }
231
232 _scanBottomAltFact.setRawValue (complexObject[scanBottomAltName].toDouble());
233 _layersFact.setRawValue (complexObject[layersName].toDouble());
234 _structureHeightFact.setRawValue (complexObject[structureHeightName].toDouble());
235 _startFromTopFact.setRawValue (complexObject[startFromTopName].toBool());
236 _entranceAltFact.setRawValue (complexObject[_entranceAltName].toDouble());
237 _gimbalPitchFact.setRawValue (complexObject[gimbalPitchName].toDouble());
238
239 if (!_structurePolygon.loadFromJson(complexObject, true /* required */, errorString)) {
240 _structurePolygon.clear();
241 return false;
242 }
243
244 return true;
245}
246
247void StructureScanComplexItem::_flightPathChanged(void)
248{
249 // Calc bounding cubetopFlightAlt
250 double north = 0.0;
251 double south = 180.0;
252 double east = 0.0;
253 double west = 360.0;
254 double bottom = 100000.;
255 double top = 0.;
256 QList<QGeoCoordinate> vertices = _flightPolygon.coordinateList();
257 for (int i = 0; i < vertices.count(); i++) {
258 QGeoCoordinate vertex = vertices[i];
259 double lat = vertex.latitude() + 90.0;
260 double lon = vertex.longitude() + 180.0;
261 north = fmax(north, lat);
262 south = fmin(south, lat);
263 east = fmax(east, lon);
264 west = fmin(west, lon);
265 bottom = fmin(bottom, vertex.altitude());
266 top = fmax(top, vertex.altitude());
267 }
268 //-- Update bounding cube for airspace management control
270 QGeoCoordinate(north - 90.0, west - 180.0, bottom),
271 QGeoCoordinate(south - 90.0, east - 180.0, top)));
272
275
276 if (_isIncomplete) {
277 _isIncomplete = false;
278 emit isIncompleteChanged();
279 }
280}
281
282double StructureScanComplexItem::greatestDistanceTo(const QGeoCoordinate &other) const
283{
284 double greatestDistance = 0.0;
285 QList<QGeoCoordinate> vertices = _flightPolygon.coordinateList();
286
287 for (int i=0; i<vertices.count(); i++) {
288 QGeoCoordinate vertex = vertices[i];
289 double distance = vertex.distanceTo(other);
290 if (distance > greatestDistance) {
291 greatestDistance = distance;
292 }
293 }
294
295 return greatestDistance;
296}
297
298void StructureScanComplexItem::appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
299{
300 int seqNum = _sequenceNumber;
301 bool startFromTop = _startFromTopFact.rawValue().toBool();
302 double startAltitude = (startFromTop ? _structureHeightFact.rawValue().toDouble() : _scanBottomAltFact.rawValue().toDouble());
303
304 MissionItem* item = nullptr;
305
306 // Entrance waypoint
307 QGeoCoordinate entranceExitCoord = _flightPolygon.vertexCoordinate(_entryVertex);
308 item = new MissionItem(seqNum++,
309 MAV_CMD_NAV_WAYPOINT,
310 MAV_FRAME_GLOBAL_RELATIVE_ALT,
311 0, // No hold time
312 0.0, // No acceptance radius specified
313 0.0, // Pass through waypoint
314 std::numeric_limits<double>::quiet_NaN(), // Yaw unchanged
315 entranceExitCoord.latitude(),
316 entranceExitCoord.longitude(),
317 _entranceAltFact.rawValue().toDouble(),
318 true, // autoContinue
319 false, // isCurrentItem
320 missionItemParent);
321 items.append(item);
322
323 // Point camera at structure
324 item = new MissionItem(seqNum++,
325 MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET,
326 MAV_FRAME_MISSION,
327 0, 0, 0, 0, // param 1-4 not used
328 _gimbalPitchFact.rawValue().toDouble(),
329 0, // Roll stays in standard orientation
330 90, // 90 degreee yaw offset to point to structure
331 true, // autoContinue
332 false, // isCurrentItem
333 missionItemParent);
334 items.append(item);
335
336 // Set up for the first layer
337 double layerAltitude = startAltitude;
338 double halfLayerHeight = _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble() / 2.0;
339 if (startFromTop) {
340 layerAltitude -= halfLayerHeight;
341 } else {
342 layerAltitude += halfLayerHeight;
343 }
344
345 for (int layer=0; layer<_layersFact.rawValue().toInt(); layer++) {
346 bool addTriggerStart = true;
347
348 bool done = false;
349 int currentVertex = _entryVertex;
350 int processedVertices = 0;
351 do {
352 QGeoCoordinate vertexCoord = _flightPolygon.vertexCoordinate(currentVertex);
353
354 item = new MissionItem(seqNum++,
355 MAV_CMD_NAV_WAYPOINT,
356 MAV_FRAME_GLOBAL_RELATIVE_ALT,
357 0, // No hold time
358 0.0, // No acceptance radius specified
359 0.0, // Pass through waypoint
360 std::numeric_limits<double>::quiet_NaN(), // Yaw unchanged
361 vertexCoord.latitude(),
362 vertexCoord.longitude(),
363 layerAltitude,
364 true, // autoContinue
365 false, // isCurrentItem
366 missionItemParent);
367 items.append(item);
368
369 // Start camera triggering after first waypoint in layer
370 if (addTriggerStart) {
371 addTriggerStart = false;
372 item = new MissionItem(seqNum++,
373 MAV_CMD_DO_SET_CAM_TRIGG_DIST,
374 MAV_FRAME_MISSION,
375 _cameraCalc.adjustedFootprintSide()->rawValue().toDouble(), // trigger distance
376 0, // shutter integration (ignore)
377 1, // trigger immediately when starting
378 0, 0, 0, 0, // param 4-7 unused
379 true, // autoContinue
380 false, // isCurrentItem
381 missionItemParent);
382 items.append(item);
383 }
384
385 // Move to next vertext
386 currentVertex++;
387 if (currentVertex >= _flightPolygon.count()) {
388 currentVertex = 0;
389 }
390
391 // Have we processed all the vertices
392 processedVertices++;
393 done = processedVertices == _flightPolygon.count() + 1;
394 } while (!done);
395
396 // Stop camera triggering after last waypoint in layer
397 item = new MissionItem(seqNum++,
398 MAV_CMD_DO_SET_CAM_TRIGG_DIST,
399 MAV_FRAME_MISSION,
400 0, // stop triggering
401 0, // shutter integration (ignore)
402 0, // trigger immediately when starting
403 0, 0, 0, 0, // param 4-7 unused
404 true, // autoContinue
405 false, // isCurrentItem
406 missionItemParent);
407 items.append(item);
408
409 // Move to next layer altitude
410 if (startFromTop) {
411 layerAltitude -= halfLayerHeight * 2;
412 } else {
413 layerAltitude += halfLayerHeight * 2;
414 }
415 }
416
417 // Return camera to neutral position
418 item = new MissionItem(seqNum++,
419 MAV_CMD_DO_SET_ROI_NONE,
420 MAV_FRAME_MISSION,
421 0, 0, 0,0, 0, 0, 0, // param 1-7 not used
422 true, // autoContinue
423 false, // isCurrentItem
424 missionItemParent);
425 items.append(item);
426
427 // Exit waypoint
428 item = new MissionItem(seqNum++,
429 MAV_CMD_NAV_WAYPOINT,
430 MAV_FRAME_GLOBAL_RELATIVE_ALT,
431 0, // No hold time
432 0.0, // No acceptance radius specified
433 0.0, // Pass through waypoint
434 std::numeric_limits<double>::quiet_NaN(), // Yaw unchanged
435 entranceExitCoord.latitude(),
436 entranceExitCoord.longitude(),
437 _entranceAltFact.rawValue().toDouble(),
438 true, // autoContinue
439 false, // isCurrentItem
440 missionItemParent);
441 items.append(item);
442
443}
444
446{
447 return _cameraShots;
448}
449
451{
453 if (!QGC::fuzzyCompare(_vehicleSpeed, missionFlightStatus.vehicleSpeed)) {
454 _vehicleSpeed = missionFlightStatus.vehicleSpeed;
456 }
457}
458
459void StructureScanComplexItem::_setDirty(void)
460{
461 setDirty(true);
462}
463
465{
466 _entranceAltFact.setRawValue(newAltitude);
467}
468
469void StructureScanComplexItem::setCoordinate(const QGeoCoordinate& coordinate)
470{
471 const QGeoCoordinate oldCoordinate = this->coordinate();
472 if (!oldCoordinate.isValid() || !coordinate.isValid() || _structurePolygon.count() < 3) {
473 return;
474 }
475
476 const double distanceMeters = oldCoordinate.distanceTo(coordinate);
477 const double azimuthDegrees = oldCoordinate.azimuthTo(coordinate);
478 const QList<QGeoCoordinate> vertices = _structurePolygon.coordinateList();
479
480 QList<QGeoCoordinate> translatedVertices;
481 translatedVertices.reserve(vertices.count());
482 for (const QGeoCoordinate& vertex: vertices) {
483 translatedVertices.append(vertex.atDistanceAndAzimuth(distanceMeters, azimuthDegrees));
484 }
485
486 _structurePolygon.setPath(translatedVertices);
487}
488
489void StructureScanComplexItem::_polygonDirtyChanged(bool dirty)
490{
491 if (dirty) {
492 setDirty(true);
493 }
494}
495
497{
498 return _vehicleSpeed == 0 ? 0 : _cameraCalc.adjustedFootprintSide()->rawValue().toDouble() / _vehicleSpeed;
499}
500
501QGeoCoordinate StructureScanComplexItem::coordinate(void) const
502{
503 if (_flightPolygon.count() > 0) {
504 QGeoCoordinate coord = _flightPolygon.vertexCoordinate(_entryVertex);
505 return coord;
506 } else {
507 return QGeoCoordinate();
508 }
509}
510
511void StructureScanComplexItem::_updateCoordinateAltitudes(void)
512{
514}
515
517{
518 _entryVertex++;
519 if (_entryVertex >= _flightPolygon.count()) {
520 _entryVertex = 0;
521 }
523}
524
525void StructureScanComplexItem::_rebuildFlightPolygon(void)
526{
527 // While this is happening all hell breaks loose signal-wise which can cause a bad vertex reference.
528 // So we reset to a safe value first and then double check validity when putting it back
529 int savedEntryVertex = _entryVertex;
530 _entryVertex = 0;
531
532 _flightPolygon = _structurePolygon;
533 _flightPolygon.offset(_cameraCalc.distanceToSurface()->rawValue().toDouble());
534
535 if (savedEntryVertex >= _flightPolygon.count()) {
536 _entryVertex = 0;
537 } else {
538 _entryVertex = savedEntryVertex;
539 }
540
542}
543
544void StructureScanComplexItem::_recalcCameraShots(void)
545{
546 double triggerDistance = _cameraCalc.adjustedFootprintSide()->rawValue().toDouble();
547 if (triggerDistance == 0) {
548 _setCameraShots(0);
549 return;
550 }
551
552 if (_flightPolygon.count() < 3) {
553 _setCameraShots(0);
554 return;
555 }
556
557 // Determine the distance for each polygon traverse
558 double distance = 0;
559 for (int i=0; i<_flightPolygon.count(); i++) {
560 QGeoCoordinate coord1 = _flightPolygon.vertexCoordinate(i);
561 QGeoCoordinate coord2 = _flightPolygon.vertexCoordinate(i + 1 == _flightPolygon.count() ? 0 : i + 1);
562 distance += coord1.distanceTo(coord2);
563 }
564 if (distance == 0.0) {
565 _setCameraShots(0);
566 return;
567 }
568
569 int cameraShots = static_cast<int>(distance / triggerDistance);
570 _setCameraShots(cameraShots * _layersFact.rawValue().toInt());
571}
572
573void StructureScanComplexItem::_recalcLayerInfo(void)
574{
575 double surfaceHeight = qMax(_structureHeightFact.rawValue().toDouble() - _scanBottomAltFact.rawValue().toDouble(), 0.0);
576
577 // Layer count is calculated from surface and layer heights
578 _layersFact.setRawValue(qMax(qCeil(surfaceHeight / _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble()), 1));
579}
580
581void StructureScanComplexItem::_updateGimbalPitch(void)
582{
583 if (!_cameraCalc.isManualCamera()) {
584 _gimbalPitchFact.setRawValue(0);
585 }
586}
587
589{
590 if (_startFromTopFact.rawValue().toBool()) {
591 // Structure Height minus the topmost layers
592 double layerIncrement = (_cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble() / 2.0) + ((_layersFact.rawValue().toInt() - 1) * _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble());
593 return _structureHeightFact.rawValue().toDouble() - layerIncrement;
594 } else {
595 // Bottom alt plus half the height of a layer
596 double layerIncrement = _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble() / 2.0;
597 return _scanBottomAltFact.rawValue().toDouble() + layerIncrement;
598 }
599}
600
602{
603 if (_startFromTopFact.rawValue().toBool()) {
604 // Structure Height minus half the layer height
605 double layerIncrement = _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble() / 2.0;
606 return _structureHeightFact.rawValue().toDouble() - layerIncrement;
607 } else {
608 // Bottom alt plus all layers
609 double layerIncrement = (_cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble() / 2.0) + ((_layersFact.rawValue().toInt() - 1) * _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble());
610 return _scanBottomAltFact.rawValue().toDouble() + layerIncrement;
611 }
612}
613
614void StructureScanComplexItem::_signalTopBottomAltChanged(void)
615{
616 emit topFlightAltChanged();
618}
619
620void StructureScanComplexItem::_recalcScanDistance()
621{
622 double scanDistance = 0;
623
624 if (_flightPolygon.count() > 2) {
625 QList<QGeoCoordinate> vertices = _flightPolygon.coordinateList();
626 for (int i=0; i<vertices.count() - 1; i++) {
627 scanDistance += vertices[i].distanceTo(vertices[i+1]);
628 }
629 scanDistance += vertices.last().distanceTo(vertices.first());
630
631 scanDistance *= _layersFact.rawValue().toInt();
632
633 double surfaceHeight = qMax(_structureHeightFact.rawValue().toDouble() - _scanBottomAltFact.rawValue().toDouble(), 0.0);
634 scanDistance += surfaceHeight;
635
636 qCDebug(StructureScanComplexItemLog) << "StructureScanComplexItem--_recalcScanDistance layers: "
637 << _layersFact.rawValue().toInt() << " structure height: " << surfaceHeight
638 << " scanDistance: " << _scanDistance;
639 }
640
641 if (!QGC::fuzzyCompare(_scanDistance, scanDistance)) {
642 _scanDistance = scanDistance;
644 }
645
646}
647
652
653void StructureScanComplexItem::_updateWizardMode(void)
654{
655 if (_structurePolygon.isValid() && !_structurePolygon.traceMode()) {
656 setWizardMode(false);
657 }
658}
659
661{
662 return _entranceAltFact.rawValue().toDouble();
663}
664
666{
667 return _entranceAltFact.rawValue().toDouble() + _missionController->plannedHomePosition().altitude();
668}
669
670// Never call this method directly. If you want to update the flight segments you emit _updateFlightPathSegmentsSignal()
671void StructureScanComplexItem::_updateFlightPathSegmentsDontCallDirectly(void)
672{
673 // Generation of flight segments depends on the following values:
674 // _flightPolygon,
675 // _startFromTopFact
676 // _structureHeightFact,
677 // _scanBottomAltFact
678 // _cameraCalc.adjustedFootprintFrontal()
679 // _missionController->plannedHomePosition().altitude()
680 // _entranceAltFact
681 // _layersFact
682 // Any changes to these values must rebuild the segments
683
686 emit terrainCollisionChanged(false);
687 _structurePolygon.setShowAltColor(false);
688 }
689
692
693 if (_flightPolygon.count() > 2) {
694
695 bool startFromTop = _startFromTopFact.rawValue().toBool();
696 double startAltitude = (startFromTop ? _structureHeightFact.rawValue().toDouble() : _scanBottomAltFact.rawValue().toDouble());
697
698 // Set up for the first layer
699 double prevLayerAltitude = 0;
700 double layerAltitude = startAltitude;
701 double halfLayerHeight = _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble() / 2.0;
702 if (startFromTop) {
703 layerAltitude -= halfLayerHeight;
704 } else {
705 layerAltitude += halfLayerHeight;
706 }
707 layerAltitude += _missionController->plannedHomePosition().altitude();
708
709 QGeoCoordinate layerEntranceCoord = _flightPolygon.vertexCoordinate(_entryVertex);
710
711 // Entrance to first layer entrance
712 double entranceAlt = _entranceAltFact.rawValue().toDouble() + _missionController->plannedHomePosition().altitude();
713 _appendFlightPathSegment(FlightPathSegment::SegmentTypeGeneric, layerEntranceCoord, entranceAlt, layerEntranceCoord, layerAltitude);
714
715 // Segments for each layer
716 for (int layerIndex=0; layerIndex<_layersFact.rawValue().toInt(); layerIndex++) {
717 // Move from one layer to the next
718 if (layerIndex != 0) {
719 _appendFlightPathSegment(FlightPathSegment::SegmentTypeGeneric, layerEntranceCoord, prevLayerAltitude, layerEntranceCoord, layerAltitude);
720 }
721
722 QGeoCoordinate prevCoord = QGeoCoordinate();
723 for (const QGeoCoordinate& coord: _flightPolygon.coordinateList()) {
724 if (prevCoord.isValid()) {
725 _appendFlightPathSegment(FlightPathSegment::SegmentTypeGeneric, prevCoord, layerAltitude, coord, layerAltitude);
726 }
727 prevCoord = coord;
728 }
729 _appendFlightPathSegment(FlightPathSegment::SegmentTypeGeneric, _flightPolygon.coordinateList().last(), layerAltitude, _flightPolygon.coordinateList().first(), layerAltitude);
730
731 // Move to next layer altitude
732 prevLayerAltitude = layerAltitude;
733 if (startFromTop) {
734 layerAltitude -= halfLayerHeight * 2;
735 } else {
736 layerAltitude += halfLayerHeight * 2;
737 }
738 }
739
740 // Last layer exit back to entrance
741 _appendFlightPathSegment(FlightPathSegment::SegmentTypeGeneric, layerEntranceCoord, prevLayerAltitude, layerEntranceCoord, entranceAlt);
742 }
743
745
747 emit terrainCollisionChanged(true);
748 }
749
751}
752
754{
755 double minAlt = qMin(bottomFlightAlt(), _entranceAltFact.rawValue().toDouble());
756 return minAlt + _missionController->plannedHomePosition().altitude();
757}
758
760{
761 double maxAlt = qMax(topFlightAlt(), _entranceAltFact.rawValue().toDouble());
762 return maxAlt + _missionController->plannedHomePosition().altitude();
763}
764
765void StructureScanComplexItem::_segmentTerrainCollisionChanged(bool terrainCollision)
766{
768 _structurePolygon.setShowAltColor(_cTerrainCollisionSegments != 0);
769}
#define qgcApp()
QString errorString
#define QGC_LOGGING_CATEGORY(name, categoryStr)
void save(QJsonObject &json) const
Fact * adjustedFootprintSide(void)
Definition CameraCalc.h:57
bool isManualCamera(void) const
Definition CameraCalc.h:68
Fact * distanceToSurface(void)
Definition CameraCalc.h:53
Fact * adjustedFootprintFrontal(void)
Definition CameraCalc.h:58
bool load(const QJsonObject &json, bool deprecatedFollowTerrain, QString &errorString, bool forPresets)
void isManualCameraChanged(void)
void isIncompleteChanged(void)
static constexpr const char * jsonComplexItemTypeKey
This mission item attribute specifies the type of the complex item.
void _appendFlightPathSegment(FlightPathSegment::SegmentType segmentType, const QGeoCoordinate &coord1, double coord1AMSLAlt, const QGeoCoordinate &coord2, double coord2AMSLAlt)
QmlObjectListModel _flightPathSegments
void greatestDistanceToChanged(void)
void maxAMSLAltitudeChanged(void)
virtual bool terrainCollision(void) const
void minAMSLAltitudeChanged(void)
void complexDistanceChanged(void)
void terrainCollisionChanged(bool terrainCollision)
virtual void _segmentTerrainCollisionChanged(bool terrainCollision)
Holds the meta data associated with a Fact.
void setRawValue(const QVariant &value)
Definition Fact.cc:128
QVariant rawValue() const
Value after translation.
Definition Fact.h:85
void valueChanged(const QVariant &value)
This signal is only meant for use by the QT property system. It should not be connected to by client ...
void recalcTerrainProfile(void)
void plannedHomePositionChanged(QGeoCoordinate plannedHomePosition)
QGeoCoordinate plannedHomePosition(void) const
void endResetModel()
Depth-counted endResetModel — only the outermost call has effect.
void beginResetModel()
Depth-counted beginResetModel — only the outermost call has effect.
Master controller for mission, fence, rally.
MissionController * missionController(void)
void dirtyChanged(bool dirty)
bool isValid(void) const
bool traceMode(void) const
QList< QGeoCoordinate > coordinateList(void) const
Returns the path in a list of QGeoCoordinate's format.
Q_INVOKABLE void offset(double distance)
Offsets the current polygon edges by the specified distance in meters.
void traceModeChanged(bool traceMode)
Q_INVOKABLE QGeoCoordinate vertexCoordinate(int vertex) const
Returns the QGeoCoordinate for the vertex specified.
void setPath(const QList< QGeoCoordinate > &path)
void saveToJson(QJsonObject &json)
static constexpr const char * jsonPolygonKey
Q_INVOKABLE void clear(void)
bool isValidChanged(void)
void setShowAltColor(bool showAltColor)
void pathChanged(void)
void countChanged(int count)
int count(void) const
bool loadFromJson(const QJsonObject &json, bool required, QString &errorString)
void clearAndDeleteContents() override final
Clears the list and calls deleteLater on each entry.
Provides access to group of settings.
static SettingsManager * instance()
int lastSequenceNumber(void) const final
void setCoordinate(const QGeoCoordinate &coordinate) final
void bottomFlightAltChanged(void)
void setMissionFlightStatus(MissionFlightStatus_t &missionFlightStatus) final
void applyNewAltitude(double newAltitude) final
Adjust the altitude of the item if appropriate to the new altitude.
bool load(const QJsonObject &complexObject, int sequenceNumber, QString &errorString) final
QGeoCoordinate coordinate(void) const final
Q_INVOKABLE void rotateEntryPoint(void)
void save(QJsonArray &missionItems) final
static constexpr const char * structureHeightName
void timeBetweenShotsChanged(void)
void cameraShotsChanged(int cameraShots)
static constexpr const char * layersName
static constexpr const char * jsonComplexItemTypeValue
void topFlightAltChanged(void)
void setSequenceNumber(int sequenceNumber) final
static constexpr const char * scanBottomAltName
ReadyForSaveState readyForSaveState(void) const final
double editableAlt(void) const final
static constexpr const char * gimbalPitchName
double minAMSLAltitude(void) const final
void _updateFlightPathSegmentsSignal(void)
double greatestDistanceTo(const QGeoCoordinate &other) const final
double amslEntryAlt(void) const final
double maxAMSLAltitude(void) const final
void appendMissionItems(QList< MissionItem * > &items, QObject *missionItemParent) final
static constexpr const char * startFromTopName
int sequenceNumber(void) const final
PlanMasterController * _masterController
void _setBoundingCube(QGCGeoBoundingCube bc)
static constexpr const char * jsonTypeComplexItemValue
Item type is Complex Item.
void amslExitAltChanged(double alt)
void setWizardMode(bool wizardMode)
void lastSequenceNumberChanged(int sequenceNumber)
void entryCoordinateChanged(const QGeoCoordinate &entryCoordinate)
void specifiesCoordinateChanged(void)
void coordinateChanged(const QGeoCoordinate &coordinate)
void readyForSaveStateChanged(void)
MissionController * _missionController
double distance(void) const
void amslEntryAltChanged(double alt)
bool _wizardMode
true: Item editor is showing wizard completion panel
static constexpr const char * jsonTypeKey
Json file attribute which specifies the item type.
void _amslEntryAltChanged(void)
void dirtyChanged(bool dirty)
void sequenceNumberChanged(int sequenceNumber)
void exitCoordinateChanged(const QGeoCoordinate &exitCoordinate)
void wizardModeChanged(bool wizardMode)
virtual void setMissionFlightStatus(MissionFlightStatus_t &missionFlightStatus)
bool validateKeys(const QJsonObject &jsonObject, const QList< KeyValidateInfo > &keyInfo, QString &errorString)
Validates that all required keys are present and that listed keys have the expected type.
constexpr const char * jsonVersionKey
Definition JsonParsing.h:12
bool fuzzyCompare(double value1, double value2)
Returns true if the two values are equal or close. Correctly handles 0 and NaN values.
Definition QGCMath.cc:109
double vehicleSpeed
Either cruise or hover speed based on vehicle type and vtol state.