QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MissionSettingsItem.cc
Go to the documentation of this file.
3#include "MissionItem.h"
4#include "QGC.h"
5#include "Vehicle.h"
7
8#include <QtCore/QJsonArray>
9
10QGC_LOGGING_CATEGORY(MissionSettingsItemLog, "Plan.MissionSettingsItem")
11
12QMap<QString, FactMetaData*> MissionSettingsItem::_metaDataMap;
13
15 : ComplexMissionItem (masterController, flyView)
16 , _managerVehicle (masterController->managerVehicle())
17 , _plannedHomePositionAltitudeFact (0, _plannedHomePositionAltitudeName, FactMetaData::valueTypeDouble)
18 , _cameraSection (masterController)
19 , _speedSection (masterController)
20{
21 _isIncomplete = false;
22 _editorQml = "qrc:/qml/QGroundControl/Controls/MissionSettingsEditor.qml";
23
24 if (_metaDataMap.isEmpty()) {
25 _metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/MissionSettings.FactMetaData.json"), nullptr /* metaDataParent */);
26 }
27
28 _plannedHomePositionAltitudeFact.setMetaData (_metaDataMap[_plannedHomePositionAltitudeName]);
29 _plannedHomePositionAltitudeFact.setRawValue (_plannedHomePositionAltitudeFact.rawDefaultValue());
30 setHomePositionSpecialCase(true);
31
32 _cameraSection.setAvailable(true);
33 _speedSection.setAvailable(true);
34
35 connect(this, &MissionSettingsItem::specifyMissionFlightSpeedChanged, this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber);
36 connect(&_cameraSection, &CameraSection::itemCountChanged, this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber);
37 connect(&_speedSection, &CameraSection::itemCountChanged, this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber);
38 connect(this, &MissionSettingsItem::terrainAltitudeChanged, this, &MissionSettingsItem::_setHomeAltFromTerrain);
39 connect(&_cameraSection, &CameraSection::dirtyChanged, this, &MissionSettingsItem::_sectionDirtyChanged);
40 connect(&_speedSection, &SpeedSection::dirtyChanged, this, &MissionSettingsItem::_sectionDirtyChanged);
50
51 connect(&_plannedHomePositionAltitudeFact, &Fact::rawValueChanged, this, &MissionSettingsItem::_updateAltitudeInCoordinate);
52
53 connect(_managerVehicle, &Vehicle::homePositionChanged, this, &MissionSettingsItem::_updateHomePosition);
54 _updateHomePosition(_managerVehicle->homePosition());
55}
56
58{
59 int lastSequenceNumber = _sequenceNumber;
60
61 lastSequenceNumber += _cameraSection.itemCount();
62 lastSequenceNumber += _speedSection.itemCount();
63
64 return lastSequenceNumber;
65}
66
68{
69 if (_dirty != dirty) {
70 _dirty = dirty;
71 if (!dirty) {
72 _cameraSection.setDirty(false);
73 _speedSection.setDirty(false);
74 }
75 emit dirtyChanged(_dirty);
76 }
77}
78
79void MissionSettingsItem::save(QJsonArray& missionItems)
80{
81 QList<MissionItem*> items;
82
83 appendMissionItems(items, this);
84
85 // First item should be planned home position, we are not responsible for save/load
86 // Remaining items we just output as is
87 for (int i=1; i<items.count(); i++) {
88 MissionItem* item = items[i];
89 QJsonObject saveObject;
90 item->save(saveObject);
91 missionItems.append(saveObject);
92 item->deleteLater();
93 }
94}
95
97{
98 if (_sequenceNumber != sequenceNumber) {
99 _sequenceNumber = sequenceNumber;
102 }
103}
104
105bool MissionSettingsItem::load(const QJsonObject& /*complexObject*/, int /*sequenceNumber*/, QString& /*errorString*/)
106{
107 return true;
108}
109
110double MissionSettingsItem::greatestDistanceTo(const QGeoCoordinate &other) const
111{
112 Q_UNUSED(other);
113 return 0;
114}
115
117{
118 return true;
119}
120
121void MissionSettingsItem::appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
122{
123 int seqNum = _sequenceNumber;
124
125 // IMPORTANT NOTE: If anything changes here you must also change MissionSettingsItem::scanForMissionSettings
126
127 // Planned home position
128 MissionItem* item = new MissionItem(seqNum++,
129 MAV_CMD_NAV_WAYPOINT,
130 MAV_FRAME_GLOBAL,
131 0, // Hold time
132 0, // Acceptance radius
133 0, // Not sure?
134 0, // Yaw
135 coordinate().latitude(),
136 coordinate().longitude(),
137 _plannedHomePositionAltitudeFact.rawValue().toDouble(),
138 true, // autoContinue
139 false, // isCurrentItem
140 missionItemParent);
141 items.append(item);
142
143 _cameraSection.appendSectionItems(items, missionItemParent, seqNum);
144 _speedSection.appendSectionItems(items, missionItemParent, seqNum);
145}
146
147bool MissionSettingsItem::addMissionEndAction(QList<MissionItem*>& /*items*/, int /*seqNum*/, QObject* /*missionItemParent*/)
148{
149 return false;
150}
151
153{
154 bool foundSpeedSection = false;
155 bool foundCameraSection = false;
156
157 qCDebug(MissionSettingsItemLog) << "MissionSettingsItem::scanForMissionSettings count:scanIndex" << visualItems->count() << scanIndex;
158
159 // Scan through the initial mission items for possible mission settings
160 foundCameraSection = _cameraSection.scanForSection(visualItems, scanIndex);
161 foundSpeedSection = _speedSection.scanForSection(visualItems, scanIndex);
162
163 return foundSpeedSection || foundCameraSection;
164}
165
167{
168 return 0;
169}
170
171void MissionSettingsItem::_setDirty(void)
172{
173 setDirty(true);
174}
175
176void MissionSettingsItem::_setCoordinateWorker(const QGeoCoordinate& coordinate)
177{
178 if (_plannedHomePositionCoordinate != coordinate) {
179 _plannedHomePositionCoordinate = coordinate;
181 if (_plannedHomePositionFromVehicle) {
182 _plannedHomePositionAltitudeFact.setRawValue(coordinate.altitude());
183 }
184 }
185}
186
188{
189 // If the user hasn't moved the planned home position manually we use the value from the vehicle
190 if (!_plannedHomePositionMovedByUser) {
191 QGeoCoordinate coordinate = vehicle->homePosition();
192 // ArduPilot tends to send crap home positions at initial vehicle boot, discard them
193 if (coordinate.isValid() && (coordinate.latitude() != 0 || coordinate.longitude() != 0)) {
194 _plannedHomePositionFromVehicle = true;
195 _setCoordinateWorker(coordinate);
196 }
197 }
198}
199
200void MissionSettingsItem::setInitialHomePosition(const QGeoCoordinate& coordinate)
201{
202 _plannedHomePositionMovedByUser = false;
203 _plannedHomePositionFromVehicle = false;
204 _setCoordinateWorker(coordinate);
205}
206
207void MissionSettingsItem::setInitialHomePositionFromUser(const QGeoCoordinate& coordinate)
208{
209 _plannedHomePositionMovedByUser = true;
210 _plannedHomePositionFromVehicle = false;
211 _setCoordinateWorker(coordinate);
212}
213
214
215void MissionSettingsItem::setCoordinate(const QGeoCoordinate& coordinate)
216{
217 if (coordinate != this->coordinate()) {
218 // The user is moving the planned home position manually. Stop tracking vehicle home position.
219 _plannedHomePositionMovedByUser = true;
220 _plannedHomePositionFromVehicle = false;
221 _setCoordinateWorker(coordinate);
222 }
223}
224
225void MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber(void)
226{
228 setDirty(true);
229}
230
231void MissionSettingsItem::_sectionDirtyChanged(bool dirty)
232{
233 if (dirty) {
234 setDirty(true);
235 }
236}
237
239{
240 return _cameraSection.specifyGimbal() ? _cameraSection.gimbalYaw()->rawValue().toDouble() : std::numeric_limits<double>::quiet_NaN();
241}
242
244{
245 return _cameraSection.specifyGimbal() ? _cameraSection.gimbalPitch()->rawValue().toDouble() : std::numeric_limits<double>::quiet_NaN();
246}
247
248void MissionSettingsItem::_updateAltitudeInCoordinate(QVariant value)
249{
250 double newAltitude = value.toDouble();
251
252 if (!QGC::fuzzyCompare(_plannedHomePositionCoordinate.altitude(), newAltitude)) {
253 qCDebug(MissionSettingsItemLog) << "MissionSettingsItem::_updateAltitudeInCoordinate" << newAltitude;
254 _plannedHomePositionCoordinate.setAltitude(newAltitude);
255 emit coordinateChanged(_plannedHomePositionCoordinate);
256 }
257}
258
260{
261 if (_speedSection.specifyFlightSpeed()) {
262 return _speedSection.flightSpeed()->rawValue().toDouble();
263 } else {
264 return std::numeric_limits<double>::quiet_NaN();
265 }
266}
267
268void MissionSettingsItem::_setHomeAltFromTerrain(double terrainAltitude)
269{
270 if (!_plannedHomePositionFromVehicle && !qIsNaN(terrainAltitude)) {
271 qCDebug(MissionSettingsItemLog) << "MissionSettingsItem::_setHomeAltFromTerrain" << terrainAltitude;
272 _plannedHomePositionAltitudeFact.setRawValue(terrainAltitude);
273 }
274}
275
277{
278 return _flyView ? tr("L") : tr("Launch");
279}
280
281void MissionSettingsItem::_updateHomePosition(const QGeoCoordinate& homePosition)
282{
283 if (_flyView) {
284 setCoordinate(homePosition);
285 }
286}
#define QGC_LOGGING_CATEGORY(name, categoryStr)
bool scanForSection(QmlObjectListModel *visualItems, int scanIndex) override
void appendSectionItems(QList< MissionItem * > &items, QObject *missionItemParent, int &seqNum) override
void specifiedGimbalYawChanged(double gimbalYaw)
Fact * gimbalPitch(void)
Fact * gimbalYaw(void)
void specifiedGimbalPitchChanged(double gimbalPitch)
int itemCount(void) const override
void setDirty(bool dirty) override
void maxAMSLAltitudeChanged(void)
void minAMSLAltitudeChanged(void)
static QMap< QString, FactMetaData * > createMapFromJsonFile(const QString &jsonFilename, QObject *metaDataParent)
void rawValueChanged(const QVariant &value)
void save(QJsonObject &json) const
void setInitialHomePositionFromUser(const QGeoCoordinate &coordinate)
bool scanForMissionSettings(QmlObjectListModel *visualItems, int scanIndex)
Scans the loaded items for settings items.
bool load(const QJsonObject &complexObject, int sequenceNumber, QString &errorString) final
void setDirty(bool dirty) final
void setSequenceNumber(int sequenceNumber) final
QGeoCoordinate coordinate(void) const final
QString abbreviation(void) const final
double specifiedFlightSpeed(void) final
void setHomePositionFromVehicle(Vehicle *vehicle)
Called to update home position coordinate when it comes from a connected vehicle.
void setCoordinate(const QGeoCoordinate &coordinate) final
double specifiedGimbalYaw(void) final
void appendMissionItems(QList< MissionItem * > &items, QObject *missionItemParent) final
void specifyMissionFlightSpeedChanged(bool specifyMissionFlightSpeed)
bool dirty(void) const final
void setInitialHomePosition(const QGeoCoordinate &coordinate)
void save(QJsonArray &missionItems) final
bool addMissionEndAction(QList< MissionItem * > &items, int seqNum, QObject *missionItemParent)
int sequenceNumber(void) const final
double specifiedGimbalPitch(void) final
int lastSequenceNumber(void) const final
double greatestDistanceTo(const QGeoCoordinate &other) const final
double complexDistance(void) const final
bool specifiesCoordinate(void) const final
Master controller for mission, fence, rally.
int count() const override final
void dirtyChanged(bool dirty)
void itemCountChanged(int itemCount)
Fact * flightSpeed(void)
int itemCount(void) const override
void specifiedFlightSpeedChanged(double flightSpeed)
void appendSectionItems(QList< MissionItem * > &items, QObject *missionItemParent, int &seqNum) override
void setDirty(bool dirty) override
bool scanForSection(QmlObjectListModel *visualItems, int scanIndex) override
QGeoCoordinate homePosition()
Definition Vehicle.cc:1515
void homePositionChanged(const QGeoCoordinate &homePosition)
void amslExitAltChanged(double alt)
void terrainAltitudeChanged(double terrainAltitude)
void lastSequenceNumberChanged(int sequenceNumber)
void entryCoordinateChanged(const QGeoCoordinate &entryCoordinate)
void coordinateChanged(const QGeoCoordinate &coordinate)
void specifiedFlightSpeedChanged(void)
void specifiedGimbalYawChanged(void)
void amslEntryAltChanged(double alt)
void specifiedGimbalPitchChanged(void)
void _amslEntryAltChanged(void)
void dirtyChanged(bool dirty)
void sequenceNumberChanged(int sequenceNumber)
void exitCoordinateChanged(const QGeoCoordinate &exitCoordinate)
double terrainAltitude(void) const
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