8#include <QtCore/QJsonArray>
16 , _managerVehicle (masterController->managerVehicle())
17 , _plannedHomePositionAltitudeFact (0, _plannedHomePositionAltitudeName,
FactMetaData::valueTypeDouble)
18 , _cameraSection (masterController)
19 , _speedSection (masterController)
21 _isIncomplete =
false;
22 _editorQml =
"qrc:/qml/QGroundControl/Controls/MissionSettingsEditor.qml";
24 if (_metaDataMap.isEmpty()) {
28 _plannedHomePositionAltitudeFact.setMetaData (_metaDataMap[_plannedHomePositionAltitudeName]);
29 _plannedHomePositionAltitudeFact.setRawValue (_plannedHomePositionAltitudeFact.rawDefaultValue());
30 setHomePositionSpecialCase(
true);
32 _cameraSection.setAvailable(
true);
33 _speedSection.setAvailable(
true);
51 connect(&_plannedHomePositionAltitudeFact, &
Fact::rawValueChanged,
this, &MissionSettingsItem::_updateAltitudeInCoordinate);
54 _updateHomePosition(_managerVehicle->homePosition());
81 QList<MissionItem*> items;
87 for (
int i=1; i<items.count(); i++) {
89 QJsonObject saveObject;
90 item->
save(saveObject);
91 missionItems.append(saveObject);
123 int seqNum = _sequenceNumber;
129 MAV_CMD_NAV_WAYPOINT,
137 _plannedHomePositionAltitudeFact.rawValue().toDouble(),
154 bool foundSpeedSection =
false;
155 bool foundCameraSection =
false;
157 qCDebug(MissionSettingsItemLog) <<
"MissionSettingsItem::scanForMissionSettings count:scanIndex" << visualItems->
count() << scanIndex;
160 foundCameraSection = _cameraSection.
scanForSection(visualItems, scanIndex);
161 foundSpeedSection = _speedSection.
scanForSection(visualItems, scanIndex);
163 return foundSpeedSection || foundCameraSection;
171void MissionSettingsItem::_setDirty(
void)
176void MissionSettingsItem::_setCoordinateWorker(
const QGeoCoordinate& coordinate)
178 if (_plannedHomePositionCoordinate !=
coordinate) {
181 if (_plannedHomePositionFromVehicle) {
182 _plannedHomePositionAltitudeFact.setRawValue(
coordinate.altitude());
190 if (!_plannedHomePositionMovedByUser) {
194 _plannedHomePositionFromVehicle =
true;
202 _plannedHomePositionMovedByUser =
false;
203 _plannedHomePositionFromVehicle =
false;
209 _plannedHomePositionMovedByUser =
true;
210 _plannedHomePositionFromVehicle =
false;
219 _plannedHomePositionMovedByUser =
true;
220 _plannedHomePositionFromVehicle =
false;
225void MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber(
void)
231void MissionSettingsItem::_sectionDirtyChanged(
bool dirty)
240 return _cameraSection.specifyGimbal() ? _cameraSection.
gimbalYaw()->rawValue().toDouble() : std::numeric_limits<double>::quiet_NaN();
245 return _cameraSection.specifyGimbal() ? _cameraSection.
gimbalPitch()->rawValue().toDouble() : std::numeric_limits<double>::quiet_NaN();
248void MissionSettingsItem::_updateAltitudeInCoordinate(QVariant value)
250 double newAltitude = value.toDouble();
252 if (!
QGC::fuzzyCompare(_plannedHomePositionCoordinate.altitude(), newAltitude)) {
253 qCDebug(MissionSettingsItemLog) <<
"MissionSettingsItem::_updateAltitudeInCoordinate" << newAltitude;
254 _plannedHomePositionCoordinate.setAltitude(newAltitude);
261 if (_speedSection.specifyFlightSpeed()) {
262 return _speedSection.
flightSpeed()->rawValue().toDouble();
264 return std::numeric_limits<double>::quiet_NaN();
268void MissionSettingsItem::_setHomeAltFromTerrain(
double terrainAltitude)
271 qCDebug(MissionSettingsItemLog) <<
"MissionSettingsItem::_setHomeAltFromTerrain" <<
terrainAltitude;
278 return _flyView ? tr(
"L") : tr(
"Launch");
281void MissionSettingsItem::_updateHomePosition(
const QGeoCoordinate& homePosition)
#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)
void specifiedGimbalPitchChanged(double gimbalPitch)
int itemCount(void) const override
void setDirty(bool dirty) override
void maxAMSLAltitudeChanged(void)
void minAMSLAltitudeChanged(void)
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)
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()
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.