MissionSettingsItem.cc 10.9 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
#include "PlanMasterController.h"
20 21 22 23 24

#include <QPolygonF>

QGC_LOGGING_CATEGORY(MissionSettingsComplexItemLog, "MissionSettingsComplexItemLog")

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

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

29 30 31
MissionSettingsItem::MissionSettingsItem(PlanMasterController* masterController, bool flyView, QObject* parent)
    : ComplexMissionItem                (masterController, flyView, parent)
    , _managerVehicle                   (masterController->managerVehicle())
32
    , _plannedHomePositionAltitudeFact  (0, _plannedHomePositionAltitudeName,   FactMetaData::valueTypeDouble)
33 34
    , _cameraSection                    (masterController)
    , _speedSection                     (masterController)
35
{
36
    _isIncomplete = false;
37 38 39
    _editorQml = "qrc:/qml/MissionSettingsEditor.qml";

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

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

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

50
    connect(this,               &MissionSettingsItem::specifyMissionFlightSpeedChanged, this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber);
51 52
    connect(&_cameraSection,    &CameraSection::itemCountChanged,                       this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber);
    connect(&_speedSection,     &CameraSection::itemCountChanged,                       this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber);
53
    connect(this,               &MissionSettingsItem::terrainAltitudeChanged,           this, &MissionSettingsItem::_setHomeAltFromTerrain);
54 55 56 57 58
    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);
59
    connect(&_plannedHomePositionAltitudeFact,  &Fact::rawValueChanged,                 this, &MissionSettingsItem::_updateAltitudeInCoordinate);
60

61 62
    connect(_managerVehicle, &Vehicle::homePositionChanged, this, &MissionSettingsItem::_updateHomePosition);
    _updateHomePosition(_managerVehicle->homePosition());
63 64
}

65
int MissionSettingsItem::lastSequenceNumber(void) const
66
{
67
    int lastSequenceNumber = _sequenceNumber;
68

69 70
    lastSequenceNumber += _cameraSection.itemCount();
    lastSequenceNumber += _speedSection.itemCount();
71 72 73 74

    return lastSequenceNumber;
}

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

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

    appendMissionItems(items, this);
92

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

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

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

    return true;
}

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

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

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

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

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

155 156
    _cameraSection.appendSectionItems(items, missionItemParent, seqNum);
    _speedSection.appendSectionItems(items, missionItemParent, seqNum);
157 158
}

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

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

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

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

175
    return foundSpeedSection || foundCameraSection;
176 177
}

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

183
void MissionSettingsItem::_setDirty(void)
184 185 186 187
{
    setDirty(true);
}

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

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

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

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

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

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

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

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

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

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

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

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