MissionSettingsItem.cc 10.8 KB
Newer Older
1 2
/****************************************************************************
 *
Gus Grubba's avatar
Gus Grubba committed
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8 9
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/

10
#include "MissionSettingsItem.h"
11 12 13 14 15 16 17
#include "JsonHelper.h"
#include "MissionController.h"
#include "QGCGeo.h"
#include "QGroundControlQmlGlobal.h"
#include "SimpleMissionItem.h"
#include "SettingsManager.h"
#include "AppSettings.h"
18
#include "MissionCommandUIInfo.h"
19 20 21 22 23

#include <QPolygonF>

QGC_LOGGING_CATEGORY(MissionSettingsComplexItemLog, "MissionSettingsComplexItemLog")

DonLakeFlyer's avatar
DonLakeFlyer committed
24
const char* MissionSettingsItem::_plannedHomePositionAltitudeName = "PlannedHomePositionAltitude";
25

26
QMap<QString, FactMetaData*> MissionSettingsItem::_metaDataMap;
27

28 29
MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, bool flyView, QObject* parent)
    : ComplexMissionItem                (vehicle, flyView, parent)
30
    , _plannedHomePositionAltitudeFact  (0, _plannedHomePositionAltitudeName,   FactMetaData::valueTypeDouble)
31 32
    , _cameraSection                    (vehicle)
    , _speedSection                     (vehicle)
33
{
34
    _isIncomplete = false;
35 36 37
    _editorQml = "qrc:/qml/MissionSettingsEditor.qml";

    if (_metaDataMap.isEmpty()) {
38
        _metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/MissionSettings.FactMetaData.json"), nullptr /* metaDataParent */);
39 40 41 42 43 44
    }

    _plannedHomePositionAltitudeFact.setMetaData    (_metaDataMap[_plannedHomePositionAltitudeName]);
    _plannedHomePositionAltitudeFact.setRawValue    (_plannedHomePositionAltitudeFact.rawDefaultValue());
    setHomePositionSpecialCase(true);

45 46 47
    _cameraSection.setAvailable(true);
    _speedSection.setAvailable(true);

48
    connect(this,               &MissionSettingsItem::specifyMissionFlightSpeedChanged, this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber);
49 50
    connect(&_cameraSection,    &CameraSection::itemCountChanged,                       this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber);
    connect(&_speedSection,     &CameraSection::itemCountChanged,                       this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber);
51
    connect(this,               &MissionSettingsItem::terrainAltitudeChanged,           this, &MissionSettingsItem::_setHomeAltFromTerrain);
52 53 54 55 56 57
    connect(&_cameraSection,    &CameraSection::dirtyChanged,                           this, &MissionSettingsItem::_sectionDirtyChanged);
    connect(&_speedSection,     &SpeedSection::dirtyChanged,                            this, &MissionSettingsItem::_sectionDirtyChanged);
    connect(&_cameraSection,    &CameraSection::specifiedGimbalYawChanged,              this, &MissionSettingsItem::specifiedGimbalYawChanged);
    connect(&_cameraSection,    &CameraSection::specifiedGimbalPitchChanged,            this, &MissionSettingsItem::specifiedGimbalPitchChanged);
    connect(&_speedSection,     &SpeedSection::specifiedFlightSpeedChanged,             this, &MissionSettingsItem::specifiedFlightSpeedChanged);
    connect(_vehicle,           &Vehicle::homePositionChanged,                          this, &MissionSettingsItem::_updateHomePosition);
58
    connect(&_plannedHomePositionAltitudeFact,  &Fact::rawValueChanged,                 this, &MissionSettingsItem::_updateAltitudeInCoordinate);
59

60
    _updateHomePosition(_vehicle->homePosition());
61 62
}

63
int MissionSettingsItem::lastSequenceNumber(void) const
64
{
65
    int lastSequenceNumber = _sequenceNumber;
66

67 68
    lastSequenceNumber += _cameraSection.itemCount();
    lastSequenceNumber += _speedSection.itemCount();
69 70 71 72

    return lastSequenceNumber;
}

73
void MissionSettingsItem::setDirty(bool dirty)
74 75 76
{
    if (_dirty != dirty) {
        _dirty = dirty;
77 78 79 80
        if (!dirty) {
            _cameraSection.setDirty(false);
            _speedSection.setDirty(false);
        }
81 82 83 84
        emit dirtyChanged(_dirty);
    }
}

85
void MissionSettingsItem::save(QJsonArray&  missionItems)
86
{
87 88 89
    QList<MissionItem*> items;

    appendMissionItems(items, this);
90

91
    // First item should be planned home position, we are not responsible for save/load
92
    // Remaining items we just output as is
93 94
    for (int i=1; i<items.count(); i++) {
        MissionItem* item = items[i];
95 96 97
        QJsonObject saveObject;
        item->save(saveObject);
        missionItems.append(saveObject);
98
        item->deleteLater();
99 100 101
    }
}

102
void MissionSettingsItem::setSequenceNumber(int sequenceNumber)
103 104 105 106 107 108 109 110
{
    if (_sequenceNumber != sequenceNumber) {
        _sequenceNumber = sequenceNumber;
        emit sequenceNumberChanged(sequenceNumber);
        emit lastSequenceNumberChanged(lastSequenceNumber());
    }
}

111
bool MissionSettingsItem::load(const QJsonObject& complexObject, int sequenceNumber, QString& errorString)
112 113 114 115 116 117 118 119
{
    Q_UNUSED(complexObject);
    Q_UNUSED(sequenceNumber);
    Q_UNUSED(errorString);

    return true;
}

120
double MissionSettingsItem::greatestDistanceTo(const QGeoCoordinate &other) const
121 122 123 124 125
{
    Q_UNUSED(other);
    return 0;
}

126
bool MissionSettingsItem::specifiesCoordinate(void) const
127
{
DonLakeFlyer's avatar
DonLakeFlyer committed
128
    return true;
129 130
}

131
void MissionSettingsItem::appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
132 133 134
{
    int seqNum = _sequenceNumber;

135
    // IMPORTANT NOTE: If anything changes here you must also change MissionSettingsItem::scanForMissionSettings
136 137 138 139 140 141 142 143 144

    // Planned home position
    MissionItem* item = new MissionItem(seqNum++,
                                        MAV_CMD_NAV_WAYPOINT,
                                        MAV_FRAME_GLOBAL,
                                        0,                      // Hold time
                                        0,                      // Acceptance radius
                                        0,                      // Not sure?
                                        0,                      // Yaw
145 146
                                        coordinate().latitude(),
                                        coordinate().longitude(),
147 148 149
                                        _plannedHomePositionAltitudeFact.rawValue().toDouble(),
                                        true,                   // autoContinue
                                        false,                  // isCurrentItem
150 151
                                        missionItemParent);
    items.append(item);
152

153 154
    _cameraSection.appendSectionItems(items, missionItemParent, seqNum);
    _speedSection.appendSectionItems(items, missionItemParent, seqNum);
155 156
}

157
bool MissionSettingsItem::addMissionEndAction(QList<MissionItem*>& /*items*/, int /*seqNum*/, QObject* /*missionItemParent*/)
158
{
159
    return false;
160 161
}

162
bool MissionSettingsItem::scanForMissionSettings(QmlObjectListModel* visualItems, int scanIndex)
163
{
164
    bool foundSpeedSection = false;
165 166
    bool foundCameraSection = false;

167
    qCDebug(MissionSettingsComplexItemLog) << "MissionSettingsItem::scanForMissionSettings count:scanIndex" << visualItems->count() << scanIndex;
168 169

    // Scan through the initial mission items for possible mission settings
170 171
    foundCameraSection = _cameraSection.scanForSection(visualItems, scanIndex);
    foundSpeedSection = _speedSection.scanForSection(visualItems, scanIndex);
172

173
    return foundSpeedSection || foundCameraSection;
174 175
}

176
double MissionSettingsItem::complexDistance(void) const
177 178 179 180
{
    return 0;
}

181
void MissionSettingsItem::_setDirty(void)
182 183 184 185
{
    setDirty(true);
}

186
void MissionSettingsItem::_setCoordinateWorker(const QGeoCoordinate& coordinate)
187
{
188 189 190 191 192 193
    if (_plannedHomePositionCoordinate != coordinate) {
        _plannedHomePositionCoordinate = coordinate;
        emit coordinateChanged(coordinate);
        emit exitCoordinateChanged(coordinate);
        _plannedHomePositionAltitudeFact.setRawValue(coordinate.altitude());
    }
194 195
}

196
void MissionSettingsItem::setHomePositionFromVehicle(Vehicle* vehicle)
197
{
198 199 200
    // If the user hasn't moved the planned home position manually we use the value from the vehicle
    if (!_plannedHomePositionMovedByUser) {
        QGeoCoordinate coordinate = vehicle->homePosition();
201
        // ArduPilot tends to send crap home positions at initial vehicle boot, discard them
Don Gagne's avatar
Don Gagne committed
202
        if (coordinate.isValid() && (coordinate.latitude() != 0 || coordinate.longitude() != 0)) {
203 204
            _plannedHomePositionFromVehicle = true;
            _setCoordinateWorker(coordinate);
205
        }
206 207 208
    }
}

209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233
void MissionSettingsItem::setInitialHomePosition(const QGeoCoordinate& coordinate)
{
    _plannedHomePositionMovedByUser = false;
    _plannedHomePositionFromVehicle = false;
    _setCoordinateWorker(coordinate);
}

void MissionSettingsItem::setInitialHomePositionFromUser(const QGeoCoordinate& coordinate)
{
    _plannedHomePositionMovedByUser = true;
    _plannedHomePositionFromVehicle = false;
    _setCoordinateWorker(coordinate);
}


void MissionSettingsItem::setCoordinate(const QGeoCoordinate& coordinate)
{
    if (coordinate != this->coordinate()) {
        // The user is moving the planned home position manually. Stop tracking vehicle home position.
        _plannedHomePositionMovedByUser = true;
        _plannedHomePositionFromVehicle = false;
        _setCoordinateWorker(coordinate);
    }
}

234
void MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber(void)
235 236 237 238 239
{
    emit lastSequenceNumberChanged(lastSequenceNumber());
    setDirty(true);
}

240
void MissionSettingsItem::_sectionDirtyChanged(bool dirty)
241 242 243 244 245
{
    if (dirty) {
        setDirty(true);
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
246

247
double MissionSettingsItem::specifiedGimbalYaw(void)
DonLakeFlyer's avatar
DonLakeFlyer committed
248 249 250
{
    return _cameraSection.specifyGimbal() ? _cameraSection.gimbalYaw()->rawValue().toDouble() : std::numeric_limits<double>::quiet_NaN();
}
251

252 253 254 255 256
double MissionSettingsItem::specifiedGimbalPitch(void)
{
    return _cameraSection.specifyGimbal() ? _cameraSection.gimbalPitch()->rawValue().toDouble() : std::numeric_limits<double>::quiet_NaN();
}

257 258 259 260 261 262 263 264 265 266
void MissionSettingsItem::_updateAltitudeInCoordinate(QVariant value)
{
    double newAltitude = value.toDouble();

    if (!qFuzzyCompare(_plannedHomePositionCoordinate.altitude(), newAltitude)) {
        _plannedHomePositionCoordinate.setAltitude(newAltitude);
        emit coordinateChanged(_plannedHomePositionCoordinate);
        emit exitCoordinateChanged(_plannedHomePositionCoordinate);
    }
}
267 268 269 270 271 272 273 274 275

double MissionSettingsItem::specifiedFlightSpeed(void)
{
    if (_speedSection.specifyFlightSpeed()) {
        return _speedSection.flightSpeed()->rawValue().toDouble();
    } else {
        return std::numeric_limits<double>::quiet_NaN();
    }
}
276

277 278
void MissionSettingsItem::_setHomeAltFromTerrain(double terrainAltitude)
{
279
    if (!_plannedHomePositionFromVehicle && !qIsNaN(terrainAltitude)) {
280 281 282
        _plannedHomePositionAltitudeFact.setRawValue(terrainAltitude);
    }
}
283 284 285

QString MissionSettingsItem::abbreviation(void) const
{
286
    return _flyView ? tr("L") : tr("Launch");
287
}
288 289 290 291 292 293 294

void MissionSettingsItem::_updateHomePosition(const QGeoCoordinate& homePosition)
{
    if (_flyView) {
        setCoordinate(homePosition);
    }
}