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