1#include <QtCore/QStringList>
2#include <QtCore/QJsonArray>
13 , _isCurrentItem(false)
14 , _autoContinueFact (0,
"AutoContinue",
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)
26 _commandFact.setRawValue(MAV_CMD_NAV_WAYPOINT);
27 _frameFact.setRawValue(MAV_FRAME_GLOBAL_RELATIVE_ALT);
50 , _sequenceNumber(sequenceNumber)
52 , _isCurrentItem(isCurrentItem)
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)
64 _commandFact.setRawValue(MAV_CMD_NAV_WAYPOINT);
65 _frameFact.setRawValue(MAV_FRAME_GLOBAL_RELATIVE_ALT);
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);
87 , _isCurrentItem(false)
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)
99 _commandFact.setRawValue(MAV_CMD_NAV_WAYPOINT);
100 _frameFact.setRawValue(MAV_FRAME_GLOBAL_RELATIVE_ALT);
110 _doJumpId = other._doJumpId;
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());
137 json[_jsonFrameKey] =
frame();
138 json[_jsonCommandKey] =
command();
140 json[_jsonDoJumpIdKey] = _sequenceNumber;
143 json[_jsonParamsKey] = rgParams;
148 const QStringList &wpParams = loadStream.readLine().split(
"\t");
149 if (wpParams.size() == 12) {
153 setFrame((MAV_FRAME)wpParams[2].toInt());
168bool MissionItem::_convertJsonV1ToV2(
const QJsonObject& json, QJsonObject& v2Json, QString&
errorString)
175 if (json.contains(_jsonParamsKey)) {
180 QList<JsonHelper::KeyValidateInfo> keyInfoList = {
182 { _jsonParam1Key, QJsonValue::Double,
true },
183 { _jsonParam2Key, QJsonValue::Double,
true },
184 { _jsonParam3Key, QJsonValue::Double,
true },
185 { _jsonParam4Key, QJsonValue::Double,
true },
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);
205bool MissionItem::_convertJsonV2ToV3(QJsonObject& json, QString&
errorString)
210 if (!json.contains(_jsonCoordinateKey)) {
215 QList<JsonHelper::KeyValidateInfo> keyInfoList = {
216 { _jsonCoordinateKey, QJsonValue::Array,
true },
227 QJsonArray rgParam = json[_jsonParamsKey].toArray();
231 json[_jsonParamsKey] = rgParam;
233 json.remove(_jsonCoordinateKey);
240 QJsonObject convertedJson;
241 if (!_convertJsonV1ToV2(json, convertedJson,
errorString)) {
244 if (!_convertJsonV2ToV3(convertedJson,
errorString)) {
248 QList<JsonHelper::KeyValidateInfo> keyInfoList = {
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 },
265 QJsonArray rgParams = convertedJson[_jsonParamsKey].toArray();
266 if (rgParams.count() != 7) {
267 errorString = tr(
"%1 key must contains 7 values").arg(_jsonParamsKey);
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());
279 setCommand((MAV_CMD)convertedJson[_jsonCommandKey].toInt());
280 setFrame((MAV_FRAME)convertedJson[_jsonFrameKey].toInt());
283 if (convertedJson.contains(_jsonDoJumpIdKey)) {
284 _doJumpId = convertedJson[_jsonDoJumpIdKey].toInt();
312 if ((MAV_CMD)this->
command() != command) {
313 _commandFact.setRawValue(
command);
319 if (this->
frame() != frame) {
320 _frameFact.setRawValue(
frame);
342 _param1Fact.setRawValue(param);
349 _param2Fact.setRawValue(param);
356 _param3Fact.setRawValue(param);
363 _param4Fact.setRawValue(param);
370 _param5Fact.setRawValue(param);
377 _param6Fact.setRawValue(param);
384 _param7Fact.setRawValue(param);
390 if(!std::isfinite(
param5()) || !std::isfinite(
param6())) {
392 return QGeoCoordinate();
399 double flightSpeed = std::numeric_limits<double>::quiet_NaN();
401 if (_commandFact.rawValue().toInt() == MAV_CMD_DO_CHANGE_SPEED && _param2Fact.rawValue().toDouble() > 0) {
402 flightSpeed = _param2Fact.rawValue().toDouble();
410 double gimbalYaw = std::numeric_limits<double>::quiet_NaN();
412 if (_commandFact.rawValue().toInt() == MAV_CMD_DO_MOUNT_CONTROL && _param7Fact.rawValue().toInt() == MAV_MOUNT_MODE_MAVLINK_TARGETING) {
413 gimbalYaw = _param3Fact.rawValue().toDouble();
421 double gimbalPitch = std::numeric_limits<double>::quiet_NaN();
423 if (_commandFact.rawValue().toInt() == MAV_CMD_DO_MOUNT_CONTROL && _param7Fact.rawValue().toInt() == MAV_MOUNT_MODE_MAVLINK_TARGETING) {
424 gimbalPitch = _param1Fact.rawValue().toDouble();
430void MissionItem::_param1Changed(QVariant value)
435 if (!qIsNaN(gimbalPitch)) {
440void MissionItem::_param2Changed(QVariant value)
445 if (!qIsNaN(flightSpeed)) {
450void MissionItem::_param3Changed(QVariant value)
455 if (!qIsNaN(gimbalYaw)) {
void rawValueChanged(const QVariant &value)
double specifiedGimbalPitch(void) const
MAV_CMD command(void) const
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
void setParam7(double param7)
void setParam4(double param4)
double specifiedGimbalYaw(void) const
void setAutoContinue(bool autoContinue)
void setParam6(double param6)
double param7(void) const
void setParam1(double param1)
MAV_FRAME frame(void) const
void save(QJsonObject &json) const
const MissionItem & operator=(const MissionItem &other)
void setParam3(double param3)
void setIsCurrentItem(bool isCurrentItem)
bool autoContinue(void) const
bool isCurrentItem(void) const
double param3(void) const
double param6(void) const
double param1(void) const
QGeoCoordinate coordinate(void) const
void setParam2(double param2)
int sequenceNumber(void) const
double param4(void) const
void specifiedGimbalPitchChanged(double gimbalPitch)
void setSequenceNumber(int sequenceNumber)
double param2(void) const
void sequenceNumberChanged(int sequenceNumber)
bool load(QTextStream &loadStream)
MissionItem(QObject *parent=nullptr)
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.