QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MissionItem.cc
Go to the documentation of this file.
1#include <QtCore/QStringList>
2#include <QtCore/QJsonArray>
3
4#include "MissionItem.h"
5#include "JsonHelper.h"
6#include "JsonParsing.h"
7#include "VisualMissionItem.h"
8
10 : QObject(parent)
11 , _sequenceNumber(0)
12 , _doJumpId(-1)
13 , _isCurrentItem(false)
14 , _autoContinueFact (0, "AutoContinue", FactMetaData::valueTypeUint32)
15 , _commandFact (0, "", FactMetaData::valueTypeUint32)
16 , _frameFact (0, "", FactMetaData::valueTypeUint32)
17 , _param1Fact (0, "Param1:", FactMetaData::valueTypeDouble)
18 , _param2Fact (0, "Param2:", FactMetaData::valueTypeDouble)
19 , _param3Fact (0, "Param3:", FactMetaData::valueTypeDouble)
20 , _param4Fact (0, "Param4:", FactMetaData::valueTypeDouble)
21 , _param5Fact (0, "Latitude:", FactMetaData::valueTypeDouble)
22 , _param6Fact (0, "Longitude:", FactMetaData::valueTypeDouble)
23 , _param7Fact (0, "Altitude:", FactMetaData::valueTypeDouble)
24{
25 // Need a good command and frame before we start passing signals around
26 _commandFact.setRawValue(MAV_CMD_NAV_WAYPOINT);
27 _frameFact.setRawValue(MAV_FRAME_GLOBAL_RELATIVE_ALT);
28
29 setAutoContinue(true);
30
31 connect(&_param1Fact, &Fact::rawValueChanged, this, &MissionItem::_param1Changed);
32 connect(&_param2Fact, &Fact::rawValueChanged, this, &MissionItem::_param2Changed);
33 connect(&_param3Fact, &Fact::rawValueChanged, this, &MissionItem::_param3Changed);
34}
35
36MissionItem::MissionItem(int sequenceNumber,
37 MAV_CMD command,
38 MAV_FRAME frame,
39 double param1,
40 double param2,
41 double param3,
42 double param4,
43 double param5,
44 double param6,
45 double param7,
46 bool autoContinue,
47 bool isCurrentItem,
48 QObject* parent)
49 : QObject(parent)
50 , _sequenceNumber(sequenceNumber)
51 , _doJumpId(-1)
52 , _isCurrentItem(isCurrentItem)
53 , _commandFact (0, "", FactMetaData::valueTypeUint32)
54 , _frameFact (0, "", FactMetaData::valueTypeUint32)
55 , _param1Fact (0, "Param1:", FactMetaData::valueTypeDouble)
56 , _param2Fact (0, "Param2:", FactMetaData::valueTypeDouble)
57 , _param3Fact (0, "Param3:", FactMetaData::valueTypeDouble)
58 , _param4Fact (0, "Param4:", FactMetaData::valueTypeDouble)
59 , _param5Fact (0, "Lat/X:", FactMetaData::valueTypeDouble)
60 , _param6Fact (0, "Lon/Y:", FactMetaData::valueTypeDouble)
61 , _param7Fact (0, "Alt/Z:", FactMetaData::valueTypeDouble)
62{
63 // Need a good command and frame before we start passing signals around
64 _commandFact.setRawValue(MAV_CMD_NAV_WAYPOINT);
65 _frameFact.setRawValue(MAV_FRAME_GLOBAL_RELATIVE_ALT);
66
70
71 _param1Fact.setRawValue(param1);
72 _param2Fact.setRawValue(param2);
73 _param3Fact.setRawValue(param3);
74 _param4Fact.setRawValue(param4);
75 _param5Fact.setRawValue(param5);
76 _param6Fact.setRawValue(param6);
77 _param7Fact.setRawValue(param7);
78
79 connect(&_param2Fact, &Fact::rawValueChanged, this, &MissionItem::_param2Changed);
80 connect(&_param3Fact, &Fact::rawValueChanged, this, &MissionItem::_param3Changed);
81}
82
83MissionItem::MissionItem(const MissionItem& other, QObject* parent)
84 : QObject(parent)
85 , _sequenceNumber(0)
86 , _doJumpId(-1)
87 , _isCurrentItem(false)
88 , _commandFact (0, "", FactMetaData::valueTypeUint32)
89 , _frameFact (0, "", FactMetaData::valueTypeUint32)
90 , _param1Fact (0, "Param1:", FactMetaData::valueTypeDouble)
91 , _param2Fact (0, "Param2:", FactMetaData::valueTypeDouble)
92 , _param3Fact (0, "Param3:", FactMetaData::valueTypeDouble)
93 , _param4Fact (0, "Param4:", FactMetaData::valueTypeDouble)
94 , _param5Fact (0, "Lat/X:", FactMetaData::valueTypeDouble)
95 , _param6Fact (0, "Lon/Y:", FactMetaData::valueTypeDouble)
96 , _param7Fact (0, "Alt/Z:", FactMetaData::valueTypeDouble)
97{
98 // Need a good command and frame before we start passing signals around
99 _commandFact.setRawValue(MAV_CMD_NAV_WAYPOINT);
100 _frameFact.setRawValue(MAV_FRAME_GLOBAL_RELATIVE_ALT);
101
102 *this = other;
103
104 connect(&_param2Fact, &Fact::rawValueChanged, this, &MissionItem::_param2Changed);
105 connect(&_param3Fact, &Fact::rawValueChanged, this, &MissionItem::_param3Changed);
106}
107
109{
110 _doJumpId = other._doJumpId;
111
112 setCommand(other.command());
113 setFrame(other.frame());
114 setSequenceNumber(other._sequenceNumber);
116 setIsCurrentItem(other._isCurrentItem);
117
118 _param1Fact.setRawValue(other._param1Fact.rawValue());
119 _param2Fact.setRawValue(other._param2Fact.rawValue());
120 _param3Fact.setRawValue(other._param3Fact.rawValue());
121 _param4Fact.setRawValue(other._param4Fact.rawValue());
122 _param5Fact.setRawValue(other._param5Fact.rawValue());
123 _param6Fact.setRawValue(other._param6Fact.rawValue());
124 _param7Fact.setRawValue(other._param7Fact.rawValue());
125
126 return *this;
127}
128
133
134void MissionItem::save(QJsonObject& json) const
135{
137 json[_jsonFrameKey] = frame();
138 json[_jsonCommandKey] = command();
139 json[_jsonAutoContinueKey] = autoContinue();
140 json[_jsonDoJumpIdKey] = _sequenceNumber;
141
142 QJsonArray rgParams = { param1(), param2(), param3(), param4(), param5(), param6(), param7() };
143 json[_jsonParamsKey] = rgParams;
144}
145
146bool MissionItem::load(QTextStream &loadStream)
147{
148 const QStringList &wpParams = loadStream.readLine().split("\t");
149 if (wpParams.size() == 12) {
150 setCommand((MAV_CMD)wpParams[3].toInt()); // Has to be first since it triggers defaults to be set, which are then override by below set calls
151 setSequenceNumber(wpParams[0].toInt());
152 setIsCurrentItem(wpParams[1].toInt() == 1 ? true : false);
153 setFrame((MAV_FRAME)wpParams[2].toInt());
154 setParam1(wpParams[4].toDouble());
155 setParam2(wpParams[5].toDouble());
156 setParam3(wpParams[6].toDouble());
157 setParam4(wpParams[7].toDouble());
158 setParam5(wpParams[8].toDouble());
159 setParam6(wpParams[9].toDouble());
160 setParam7(wpParams[10].toDouble());
161 setAutoContinue(wpParams[11].toInt() == 1 ? true : false);
162 return true;
163 }
164
165 return false;
166}
167
168bool MissionItem::_convertJsonV1ToV2(const QJsonObject& json, QJsonObject& v2Json, QString& errorString)
169{
170 // V1 format type = "missionItem", V2 format type = "MissionItem"
171 // V1 format has params in separate param[1-n] keys
172 // V2 format has params in params array
173 v2Json = json;
174
175 if (json.contains(_jsonParamsKey)) {
176 // Already V2 format
177 return true;
178 }
179
180 QList<JsonHelper::KeyValidateInfo> keyInfoList = {
181 { VisualMissionItem::jsonTypeKey, QJsonValue::String, true },
182 { _jsonParam1Key, QJsonValue::Double, true },
183 { _jsonParam2Key, QJsonValue::Double, true },
184 { _jsonParam3Key, QJsonValue::Double, true },
185 { _jsonParam4Key, QJsonValue::Double, true },
186 };
187 if (!JsonHelper::validateKeys(json, keyInfoList, errorString)) {
188 return false;
189 }
190
191 if (v2Json[VisualMissionItem::jsonTypeKey].toString() == QStringLiteral("missionItem")) {
193 }
194
195 QJsonArray rgParams = { json[_jsonParam1Key].toDouble(), json[_jsonParam2Key].toDouble(), json[_jsonParam3Key].toDouble(), json[_jsonParam4Key].toDouble() };
196 v2Json[_jsonParamsKey] = rgParams;
197 v2Json.remove(_jsonParam1Key);
198 v2Json.remove(_jsonParam2Key);
199 v2Json.remove(_jsonParam3Key);
200 v2Json.remove(_jsonParam4Key);
201
202 return true;
203}
204
205bool MissionItem::_convertJsonV2ToV3(QJsonObject& json, QString& errorString)
206{
207 // V2 format: param 5/6/7 stored in GeoCoordinate
208 // V3 format: param 5/6/7 stored in params array
209
210 if (!json.contains(_jsonCoordinateKey)) {
211 // Already V3 format
212 return true;
213 }
214
215 QList<JsonHelper::KeyValidateInfo> keyInfoList = {
216 { _jsonCoordinateKey, QJsonValue::Array, true },
217 };
218 if (!JsonHelper::validateKeys(json, keyInfoList, errorString)) {
219 return false;
220 }
221
222 QGeoCoordinate coordinate;
223 if (!JsonHelper::loadGeoCoordinate(json[_jsonCoordinateKey], true /* altitudeRequired */, coordinate, errorString)) {
224 return false;
225 }
226
227 QJsonArray rgParam = json[_jsonParamsKey].toArray();
228 rgParam.append(coordinate.latitude());
229 rgParam.append(coordinate.longitude());
230 rgParam.append(coordinate.altitude());
231 json[_jsonParamsKey] = rgParam;
232
233 json.remove(_jsonCoordinateKey);
234
235 return true;
236}
237
238bool MissionItem::load(const QJsonObject& json, int sequenceNumber, QString& errorString)
239{
240 QJsonObject convertedJson;
241 if (!_convertJsonV1ToV2(json, convertedJson, errorString)) {
242 return false;
243 }
244 if (!_convertJsonV2ToV3(convertedJson, errorString)) {
245 return false;
246 }
247
248 QList<JsonHelper::KeyValidateInfo> keyInfoList = {
249 { VisualMissionItem::jsonTypeKey, QJsonValue::String, true },
250 { _jsonFrameKey, QJsonValue::Double, true },
251 { _jsonCommandKey, QJsonValue::Double, true },
252 { _jsonParamsKey, QJsonValue::Array, true },
253 { _jsonAutoContinueKey, QJsonValue::Bool, true },
254 { _jsonDoJumpIdKey, QJsonValue::Double, false },
255 };
256 if (!JsonHelper::validateKeys(convertedJson, keyInfoList, errorString)) {
257 return false;
258 }
259
261 errorString = tr("Type found: %1 must be: %2").arg(convertedJson[VisualMissionItem::jsonTypeKey].toString()).arg(VisualMissionItem::jsonTypeSimpleItemValue);
262 return false;
263 }
264
265 QJsonArray rgParams = convertedJson[_jsonParamsKey].toArray();
266 if (rgParams.count() != 7) {
267 errorString = tr("%1 key must contains 7 values").arg(_jsonParamsKey);
268 return false;
269 }
270
271 for (int i=0; i<4; i++) {
272 if (rgParams[i].type() != QJsonValue::Double && rgParams[i].type() != QJsonValue::Null) {
273 errorString = tr("Param %1 incorrect type %2, must be double or null").arg(i+1).arg(rgParams[i].type());
274 return false;
275 }
276 }
277
278 // Make sure to set these first since they can signal other changes
279 setCommand((MAV_CMD)convertedJson[_jsonCommandKey].toInt());
280 setFrame((MAV_FRAME)convertedJson[_jsonFrameKey].toInt());
281
282 _doJumpId = -1;
283 if (convertedJson.contains(_jsonDoJumpIdKey)) {
284 _doJumpId = convertedJson[_jsonDoJumpIdKey].toInt();
285 }
286 setIsCurrentItem(false);
288 setAutoContinue(convertedJson[_jsonAutoContinueKey].toBool());
289
297
298 return true;
299}
300
301
302void MissionItem::setSequenceNumber(int sequenceNumber)
303{
304 if (_sequenceNumber != sequenceNumber) {
305 _sequenceNumber = sequenceNumber;
306 emit sequenceNumberChanged(_sequenceNumber);
307 }
308}
309
310void MissionItem::setCommand(MAV_CMD command)
311{
312 if ((MAV_CMD)this->command() != command) {
313 _commandFact.setRawValue(command);
314 }
315}
316
317void MissionItem::setFrame(MAV_FRAME frame)
318{
319 if (this->frame() != frame) {
320 _frameFact.setRawValue(frame);
321 }
322}
323
324void MissionItem::setAutoContinue(bool autoContinue)
325{
326 if (this->autoContinue() != autoContinue) {
327 _autoContinueFact.setRawValue(autoContinue);
328 }
329}
330
331void MissionItem::setIsCurrentItem(bool isCurrentItem)
332{
333 if (_isCurrentItem != isCurrentItem) {
334 _isCurrentItem = isCurrentItem;
336 }
337}
338
339void MissionItem::setParam1(double param)
340{
341 if (param1() != param) {
342 _param1Fact.setRawValue(param);
343 }
344}
345
346void MissionItem::setParam2(double param)
347{
348 if (param2() != param) {
349 _param2Fact.setRawValue(param);
350 }
351}
352
353void MissionItem::setParam3(double param)
354{
355 if (param3() != param) {
356 _param3Fact.setRawValue(param);
357 }
358}
359
360void MissionItem::setParam4(double param)
361{
362 if (param4() != param) {
363 _param4Fact.setRawValue(param);
364 }
365}
366
367void MissionItem::setParam5(double param)
368{
369 if (param5() != param) {
370 _param5Fact.setRawValue(param);
371 }
372}
373
374void MissionItem::setParam6(double param)
375{
376 if (param6() != param) {
377 _param6Fact.setRawValue(param);
378 }
379}
380
381void MissionItem::setParam7(double param)
382{
383 if (param7() != param) {
384 _param7Fact.setRawValue(param);
385 }
386}
387
388QGeoCoordinate MissionItem::coordinate(void) const
389{
390 if(!std::isfinite(param5()) || !std::isfinite(param6())) {
391 //-- If either of these are NAN, return an invalid (QGeoCoordinate::isValid() == false) coordinate
392 return QGeoCoordinate();
393 }
394 return QGeoCoordinate(param5(), param6(), param7());
395}
396
398{
399 double flightSpeed = std::numeric_limits<double>::quiet_NaN();
400
401 if (_commandFact.rawValue().toInt() == MAV_CMD_DO_CHANGE_SPEED && _param2Fact.rawValue().toDouble() > 0) {
402 flightSpeed = _param2Fact.rawValue().toDouble();
403 }
404
405 return flightSpeed;
406}
407
409{
410 double gimbalYaw = std::numeric_limits<double>::quiet_NaN();
411
412 if (_commandFact.rawValue().toInt() == MAV_CMD_DO_MOUNT_CONTROL && _param7Fact.rawValue().toInt() == MAV_MOUNT_MODE_MAVLINK_TARGETING) {
413 gimbalYaw = _param3Fact.rawValue().toDouble();
414 }
415
416 return gimbalYaw;
417}
418
420{
421 double gimbalPitch = std::numeric_limits<double>::quiet_NaN();
422
423 if (_commandFact.rawValue().toInt() == MAV_CMD_DO_MOUNT_CONTROL && _param7Fact.rawValue().toInt() == MAV_MOUNT_MODE_MAVLINK_TARGETING) {
424 gimbalPitch = _param1Fact.rawValue().toDouble();
425 }
426
427 return gimbalPitch;
428}
429
430void MissionItem::_param1Changed(QVariant value)
431{
432 Q_UNUSED(value);
433
434 double gimbalPitch = specifiedGimbalPitch();
435 if (!qIsNaN(gimbalPitch)) {
436 emit specifiedGimbalPitchChanged(gimbalPitch);
437 }
438}
439
440void MissionItem::_param2Changed(QVariant value)
441{
442 Q_UNUSED(value);
443
444 double flightSpeed = specifiedFlightSpeed();
445 if (!qIsNaN(flightSpeed)) {
446 emit specifiedFlightSpeedChanged(flightSpeed);
447 }
448}
449
450void MissionItem::_param3Changed(QVariant value)
451{
452 Q_UNUSED(value);
453
454 double gimbalYaw = specifiedGimbalYaw();
455 if (!qIsNaN(gimbalYaw)) {
456 emit specifiedGimbalYawChanged(gimbalYaw);
457 }
458}
QString errorString
void rawValueChanged(const QVariant &value)
double specifiedGimbalPitch(void) const
MAV_CMD command(void) const
Definition MissionItem.h:49
double specifiedFlightSpeed(void) const
void isCurrentItemChanged(bool isCurrentItem)
void specifiedGimbalYawChanged(double gimbalYaw)
void specifiedFlightSpeedChanged(double flightSpeed)
void setFrame(MAV_FRAME frame)
double param5(void) const
Definition MissionItem.h:58
void setParam7(double param7)
void setParam4(double param4)
double specifiedGimbalYaw(void) const
void setAutoContinue(bool autoContinue)
void setParam6(double param6)
double param7(void) const
Definition MissionItem.h:60
void setParam1(double param1)
MAV_FRAME frame(void) const
Definition MissionItem.h:52
void save(QJsonObject &json) const
const MissionItem & operator=(const MissionItem &other)
void setParam3(double param3)
void setIsCurrentItem(bool isCurrentItem)
bool autoContinue(void) const
Definition MissionItem.h:53
bool isCurrentItem(void) const
Definition MissionItem.h:50
double param3(void) const
Definition MissionItem.h:56
double param6(void) const
Definition MissionItem.h:59
double param1(void) const
Definition MissionItem.h:54
QGeoCoordinate coordinate(void) const
void setParam2(double param2)
int sequenceNumber(void) const
Definition MissionItem.h:51
double param4(void) const
Definition MissionItem.h:57
void specifiedGimbalPitchChanged(double gimbalPitch)
void setSequenceNumber(int sequenceNumber)
double param2(void) const
Definition MissionItem.h:55
void sequenceNumberChanged(int sequenceNumber)
bool load(QTextStream &loadStream)
MissionItem(QObject *parent=nullptr)
Definition MissionItem.cc:9
void setParam5(double param5)
void setCommand(MAV_CMD command)
static constexpr const char * jsonTypeKey
Json file attribute which specifies the item type.
static constexpr const char * jsonTypeSimpleItemValue
Item type is MISSION_ITEM.
bool validateKeys(const QJsonObject &jsonObject, const QList< KeyValidateInfo > &keyInfo, QString &errorString)
bool loadGeoCoordinate(const QJsonValue &jsonValue, bool altitudeRequired, QGeoCoordinate &coordinate, QString &errorString, bool geoJsonFormat=false)
if true, use [lon, lat], [lat, lon] otherwise
double possibleNaNJsonValue(const QJsonValue &value)
Returns NaN if the value is null, or the value converted to double otherwise.