MissionSettingsItem.cc 11.5 KB
Newer Older
1 2
/****************************************************************************
 *
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
#include "JsonHelper.h"
#include "MissionController.h"
#include "QGCGeo.h"
#include "SimpleMissionItem.h"
#include "SettingsManager.h"
#include "AppSettings.h"
17
#include "MissionCommandUIInfo.h"
18
#include "PlanMasterController.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 30
MissionSettingsItem::MissionSettingsItem(PlanMasterController* masterController, bool flyView, QObject* parent)
    : ComplexMissionItem                (masterController, flyView, parent)
    , _managerVehicle                   (masterController->managerVehicle())
31
    , _plannedHomePositionAltitudeFact  (0, _plannedHomePositionAltitudeName,   FactMetaData::valueTypeDouble)
32 33
    , _cameraSection                    (masterController)
    , _speedSection                     (masterController)
34
{
35
    _isIncomplete = false;
36 37 38
    _editorQml = "qrc:/qml/MissionSettingsEditor.qml";

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

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

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

49
    connect(this,               &MissionSettingsItem::specifyMissionFlightSpeedChanged, this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber);
50 51
    connect(&_cameraSection,    &CameraSection::itemCountChanged,                       this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber);
    connect(&_speedSection,     &CameraSection::itemCountChanged,                       this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber);
52
    connect(this,               &MissionSettingsItem::terrainAltitudeChanged,           this, &MissionSettingsItem::_setHomeAltFromTerrain);
53 54 55 56 57 58 59 60 61
    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(this,               &MissionSettingsItem::coordinateChanged,                this, &MissionSettingsItem::_amslEntryAltChanged);
    connect(this,               &MissionSettingsItem::amslEntryAltChanged,              this, &MissionSettingsItem::amslExitAltChanged);
    connect(this,               &MissionSettingsItem::amslEntryAltChanged,              this, &MissionSettingsItem::minAMSLAltitudeChanged);
    connect(this,               &MissionSettingsItem::amslEntryAltChanged,              this, &MissionSettingsItem::maxAMSLAltitudeChanged);
62

63
    connect(&_plannedHomePositionAltitudeFact,  &Fact::rawValueChanged,                 this, &MissionSettingsItem::_updateAltitudeInCoordinate);
64

65 66
    connect(_managerVehicle, &Vehicle::homePositionChanged, this, &MissionSettingsItem::_updateHomePosition);
    _updateHomePosition(_managerVehicle->homePosition());
67 68
}

69
int MissionSettingsItem::lastSequenceNumber(void) const
70
{
71
    int lastSequenceNumber = _sequenceNumber;
72

73 74
    lastSequenceNumber += _cameraSection.itemCount();
    lastSequenceNumber += _speedSection.itemCount();
75 76 77 78

    return lastSequenceNumber;
}

79
void MissionSettingsItem::setDirty(bool dirty)
80 81 82
{
    if (_dirty != dirty) {
        _dirty = dirty;
83 84 85 86
        if (!dirty) {
            _cameraSection.setDirty(false);
            _speedSection.setDirty(false);
        }
87 88 89 90
        emit dirtyChanged(_dirty);
    }
}

91
void MissionSettingsItem::save(QJsonArray&  missionItems)
92
{
93 94 95
    QList<MissionItem*> items;

    appendMissionItems(items, this);
96

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

108
void MissionSettingsItem::setSequenceNumber(int sequenceNumber)
109 110 111 112 113 114 115 116
{
    if (_sequenceNumber != sequenceNumber) {
        _sequenceNumber = sequenceNumber;
        emit sequenceNumberChanged(sequenceNumber);
        emit lastSequenceNumberChanged(lastSequenceNumber());
    }
}

117
bool MissionSettingsItem::load(const QJsonObject& complexObject, int sequenceNumber, QString& errorString)
118 119 120 121 122 123 124 125
{
    Q_UNUSED(complexObject);
    Q_UNUSED(sequenceNumber);
    Q_UNUSED(errorString);

    return true;
}

126
double MissionSettingsItem::greatestDistanceTo(const QGeoCoordinate &other) const
127 128 129 130 131
{
    Q_UNUSED(other);
    return 0;
}

132
bool MissionSettingsItem::specifiesCoordinate(void) const
133
{
DonLakeFlyer's avatar
DonLakeFlyer committed
134
    return true;
135 136
}

137
void MissionSettingsItem::appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
138 139 140
{
    int seqNum = _sequenceNumber;

141
    // IMPORTANT NOTE: If anything changes here you must also change MissionSettingsItem::scanForMissionSettings
142 143 144 145 146 147 148 149 150

    // 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
151 152
                                        coordinate().latitude(),
                                        coordinate().longitude(),
153 154 155
                                        _plannedHomePositionAltitudeFact.rawValue().toDouble(),
                                        true,                   // autoContinue
                                        false,                  // isCurrentItem
156 157
                                        missionItemParent);
    items.append(item);
158

159 160
    _cameraSection.appendSectionItems(items, missionItemParent, seqNum);
    _speedSection.appendSectionItems(items, missionItemParent, seqNum);
161 162
}

163
bool MissionSettingsItem::addMissionEndAction(QList<MissionItem*>& /*items*/, int /*seqNum*/, QObject* /*missionItemParent*/)
164
{
165
    return false;
166 167
}

168
bool MissionSettingsItem::scanForMissionSettings(QmlObjectListModel* visualItems, int scanIndex)
169
{
170
    bool foundSpeedSection = false;
171 172
    bool foundCameraSection = false;

173
    qCDebug(MissionSettingsComplexItemLog) << "MissionSettingsItem::scanForMissionSettings count:scanIndex" << visualItems->count() << scanIndex;
174 175

    // Scan through the initial mission items for possible mission settings
176 177
    foundCameraSection = _cameraSection.scanForSection(visualItems, scanIndex);
    foundSpeedSection = _speedSection.scanForSection(visualItems, scanIndex);
178

179
    return foundSpeedSection || foundCameraSection;
180 181
}

182
double MissionSettingsItem::complexDistance(void) const
183 184 185 186
{
    return 0;
}

187
void MissionSettingsItem::_setDirty(void)
188 189 190 191
{
    setDirty(true);
}

192
void MissionSettingsItem::_setCoordinateWorker(const QGeoCoordinate& coordinate)
193
{
194 195 196 197 198 199 200 201
    if (_plannedHomePositionCoordinate != coordinate) {
        _plannedHomePositionCoordinate = coordinate;
        emit coordinateChanged(coordinate);
        emit exitCoordinateChanged(coordinate);
        if (_plannedHomePositionFromVehicle) {
            _plannedHomePositionAltitudeFact.setRawValue(coordinate.altitude());
        }
    }
202 203
}

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

217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241
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);
    }
}

242
void MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber(void)
243 244 245 246 247
{
    emit lastSequenceNumberChanged(lastSequenceNumber());
    setDirty(true);
}

248
void MissionSettingsItem::_sectionDirtyChanged(bool dirty)
249 250 251 252 253
{
    if (dirty) {
        setDirty(true);
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
254

255
double MissionSettingsItem::specifiedGimbalYaw(void)
DonLakeFlyer's avatar
DonLakeFlyer committed
256 257 258
{
    return _cameraSection.specifyGimbal() ? _cameraSection.gimbalYaw()->rawValue().toDouble() : std::numeric_limits<double>::quiet_NaN();
}
259

260 261 262 263 264
double MissionSettingsItem::specifiedGimbalPitch(void)
{
    return _cameraSection.specifyGimbal() ? _cameraSection.gimbalPitch()->rawValue().toDouble() : std::numeric_limits<double>::quiet_NaN();
}

265 266 267 268
void MissionSettingsItem::_updateAltitudeInCoordinate(QVariant value)
{
    double newAltitude = value.toDouble();

269
    if (QGC::fuzzyCompare(_plannedHomePositionCoordinate.altitude(), newAltitude)) {
270 271 272 273 274
        _plannedHomePositionCoordinate.setAltitude(newAltitude);
        emit coordinateChanged(_plannedHomePositionCoordinate);
        emit exitCoordinateChanged(_plannedHomePositionCoordinate);
    }
}
275 276 277 278 279 280 281 282 283

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

285 286
void MissionSettingsItem::_setHomeAltFromTerrain(double terrainAltitude)
{
287
    if (!_plannedHomePositionFromVehicle && !qIsNaN(terrainAltitude)) {
288 289 290
        _plannedHomePositionAltitudeFact.setRawValue(terrainAltitude);
    }
}
291 292 293

QString MissionSettingsItem::abbreviation(void) const
{
294 295 296 297 298 299 300 301
    return _flyView ? tr("L") : tr("Launch");
}

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