CameraSection.cc 19.9 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/

#include "CameraSection.h"
#include "SimpleMissionItem.h"
12
#include "FirmwarePlugin.h"
13 14 15

QGC_LOGGING_CATEGORY(CameraSectionLog, "CameraSectionLog")

16 17 18 19 20 21
const char* CameraSection::_gimbalPitchName =                   "GimbalPitch";
const char* CameraSection::_gimbalYawName =                     "GimbalYaw";
const char* CameraSection::_cameraActionName =                  "CameraAction";
const char* CameraSection::_cameraPhotoIntervalDistanceName =   "CameraPhotoIntervalDistance";
const char* CameraSection::_cameraPhotoIntervalTimeName =       "CameraPhotoIntervalTime";
const char* CameraSection::_cameraModeName =                    "CameraMode";
22 23 24

QMap<QString, FactMetaData*> CameraSection::_metaDataMap;

25 26
CameraSection::CameraSection(Vehicle* vehicle, QObject* parent)
    : Section(vehicle, parent)
27 28 29
    , _available(false)
    , _settingsSpecified(false)
    , _specifyGimbal(false)
30
    , _specifyCameraMode(false)
31 32 33 34 35
    , _gimbalYawFact                    (0, _gimbalYawName,                     FactMetaData::valueTypeDouble)
    , _gimbalPitchFact                  (0, _gimbalPitchName,                   FactMetaData::valueTypeDouble)
    , _cameraActionFact                 (0, _cameraActionName,                  FactMetaData::valueTypeDouble)
    , _cameraPhotoIntervalDistanceFact  (0, _cameraPhotoIntervalDistanceName,   FactMetaData::valueTypeDouble)
    , _cameraPhotoIntervalTimeFact      (0, _cameraPhotoIntervalTimeName,       FactMetaData::valueTypeUint32)
36
    , _cameraModeFact                   (0, _cameraModeName,                    FactMetaData::valueTypeUint32)
37 38 39 40 41 42 43 44 45 46 47
    , _dirty(false)
{
    if (_metaDataMap.isEmpty()) {
        _metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/CameraSection.FactMetaData.json"), NULL /* metaDataParent */);
    }

    _gimbalPitchFact.setMetaData                    (_metaDataMap[_gimbalPitchName]);
    _gimbalYawFact.setMetaData                      (_metaDataMap[_gimbalYawName]);
    _cameraActionFact.setMetaData                   (_metaDataMap[_cameraActionName]);
    _cameraPhotoIntervalDistanceFact.setMetaData    (_metaDataMap[_cameraPhotoIntervalDistanceName]);
    _cameraPhotoIntervalTimeFact.setMetaData        (_metaDataMap[_cameraPhotoIntervalTimeName]);
48
    _cameraModeFact.setMetaData                     (_metaDataMap[_cameraModeName]);
49 50 51 52 53 54

    _gimbalPitchFact.setRawValue                    (_gimbalPitchFact.rawDefaultValue());
    _gimbalYawFact.setRawValue                      (_gimbalYawFact.rawDefaultValue());
    _cameraActionFact.setRawValue                   (_cameraActionFact.rawDefaultValue());
    _cameraPhotoIntervalDistanceFact.setRawValue    (_cameraPhotoIntervalDistanceFact.rawDefaultValue());
    _cameraPhotoIntervalTimeFact.setRawValue        (_cameraPhotoIntervalTimeFact.rawDefaultValue());
55
    _cameraModeFact.setRawValue                     (_cameraModeFact.rawDefaultValue());
56

57 58
    connect(this,                               &CameraSection::specifyGimbalChanged,       this, &CameraSection::_specifyChanged);
    connect(this,                               &CameraSection::specifyCameraModeChanged,   this, &CameraSection::_specifyChanged);
59

60
    connect(&_cameraActionFact,                 &Fact::valueChanged,                        this, &CameraSection::_cameraActionChanged);
DonLakeFlyer's avatar
DonLakeFlyer committed
61

62 63 64 65 66 67 68 69 70
    connect(&_gimbalPitchFact,                  &Fact::valueChanged,                        this, &CameraSection::_setDirty);
    connect(&_gimbalYawFact,                    &Fact::valueChanged,                        this, &CameraSection::_setDirty);
    connect(&_cameraPhotoIntervalDistanceFact,  &Fact::valueChanged,                        this, &CameraSection::_setDirty);
    connect(&_cameraPhotoIntervalTimeFact,      &Fact::valueChanged,                        this, &CameraSection::_setDirty);
    connect(&_cameraModeFact,                   &Fact::valueChanged,                        this, &CameraSection::_setDirty);
    connect(this,                               &CameraSection::specifyGimbalChanged,       this, &CameraSection::_setDirty);
    connect(this,                               &CameraSection::specifyCameraModeChanged,   this, &CameraSection::_setDirty);

    connect(&_gimbalYawFact,                    &Fact::valueChanged,                        this, &CameraSection::_updateSpecifiedGimbalYaw);
71 72 73 74 75 76 77 78 79 80
}

void CameraSection::setSpecifyGimbal(bool specifyGimbal)
{
    if (specifyGimbal != _specifyGimbal) {
        _specifyGimbal = specifyGimbal;
        emit specifyGimbalChanged(specifyGimbal);
    }
}

81 82 83 84 85 86 87 88
void CameraSection::setSpecifyCameraMode(bool specifyCameraMode)
{
    if (specifyCameraMode != _specifyCameraMode) {
        _specifyCameraMode = specifyCameraMode;
        emit specifyCameraModeChanged(specifyCameraMode);
    }
}

89
int CameraSection::itemCount(void) const
90 91 92 93 94 95
{
    int itemCount = 0;

    if (_specifyGimbal) {
        itemCount++;
    }
96 97 98
    if (_specifyCameraMode) {
        itemCount++;
    }
99 100 101 102 103 104 105 106 107 108 109 110 111 112 113
    if (_cameraActionFact.rawValue().toInt() != CameraActionNone) {
        itemCount++;
    }

    return itemCount;
}

void CameraSection::setDirty(bool dirty)
{
    if (_dirty != dirty) {
        _dirty = dirty;
        emit dirtyChanged(_dirty);
    }
}

114
void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* missionItemParent, int& nextSequenceNumber)
115
{
116
    // IMPORTANT NOTE: If anything changes here you must also change CameraSection::scanForSection
117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140

    if (_specifyGimbal) {
        MissionItem* item = new MissionItem(nextSequenceNumber++,
                                            MAV_CMD_DO_MOUNT_CONTROL,
                                            MAV_FRAME_MISSION,
                                            _gimbalPitchFact.rawValue().toDouble(),
                                            0,                                      // Gimbal roll
                                            _gimbalYawFact.rawValue().toDouble(),
                                            0, 0, 0,                                // param 4-6 not used
                                            MAV_MOUNT_MODE_MAVLINK_TARGETING,
                                            true,                                   // autoContinue
                                            false,                                  // isCurrentItem
                                            missionItemParent);
        items.append(item);
    }

    if (_cameraActionFact.rawValue().toInt() != CameraActionNone) {
        MissionItem* item = NULL;

        switch (_cameraActionFact.rawValue().toInt()) {
        case TakePhotosIntervalTime:
            item = new MissionItem(nextSequenceNumber++,
                                   MAV_CMD_IMAGE_START_CAPTURE,
                                   MAV_FRAME_MISSION,
141
                                   0,                                               // Camera ID, all cameras
142 143
                                   _cameraPhotoIntervalTimeFact.rawValue().toInt(), // Interval
                                   0,                                               // Unlimited photo count
144 145 146
                                   -1,                                              // Max horizontal resolution
                                   -1,                                              // Max vertical resolution
                                   0, 0,                                            // param 6-7 not used
147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166
                                   true,                                            // autoContinue
                                   false,                                           // isCurrentItem
                                   missionItemParent);
            break;

        case TakePhotoIntervalDistance:
            item = new MissionItem(nextSequenceNumber++,
                                   MAV_CMD_DO_SET_CAM_TRIGG_DIST,
                                   MAV_FRAME_MISSION,
                                   _cameraPhotoIntervalDistanceFact.rawValue().toDouble(),  // Trigger distance
                                   0, 0, 0, 0, 0, 0,                                        // param 2-7 not used
                                   true,                                                    // autoContinue
                                   false,                                                   // isCurrentItem
                                   missionItemParent);
            break;

        case TakeVideo:
            item = new MissionItem(nextSequenceNumber++,
                                   MAV_CMD_VIDEO_START_CAPTURE,
                                   MAV_FRAME_MISSION,
167
                                   0,                           // Camera ID, all cameras
168 169 170 171 172 173 174
                                   -1,                          // Max fps
                                   -1,                          // Max resolution
                                   0, 0, 0, 0,                  // param 5-7 not used
                                   true,                        // autoContinue
                                   false,                       // isCurrentItem
                                   missionItemParent);
            break;
175 176 177 178 179

        case StopTakingVideo:
            item = new MissionItem(nextSequenceNumber++,
                                   MAV_CMD_VIDEO_STOP_CAPTURE,
                                   MAV_FRAME_MISSION,
180
                                   0,                           // Camera ID, all cameras
181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199
                                   0, 0, 0, 0, 0, 0,            // param 2-7 not used
                                   true,                        // autoContinue
                                   false,                       // isCurrentItem
                                   missionItemParent);
            break;

        case StopTakingPhotos:
            item = new MissionItem(nextSequenceNumber++,
                                   MAV_CMD_DO_SET_CAM_TRIGG_DIST,
                                   MAV_FRAME_MISSION,
                                   0,                               // Trigger distance = 0 means stop
                                   0, 0, 0, 0, 0, 0,                // param 2-7 not used
                                   true,                            // autoContinue
                                   false,                           // isCurrentItem
                                   missionItemParent);
            items.append(item);
            item = new MissionItem(nextSequenceNumber++,
                                   MAV_CMD_IMAGE_STOP_CAPTURE,
                                   MAV_FRAME_MISSION,
200
                                   0,                           // camera id, all cameras
201 202 203 204 205
                                   0, 0, 0, 0, 0, 0,            // param 2-7 not used
                                   true,                        // autoContinue
                                   false,                       // isCurrentItem
                                   missionItemParent);
            break;
206 207 208 209 210
        }
        if (item) {
            items.append(item);
        }
    }
211 212 213 214 215 216 217 218 219 220 221 222 223

    if (_specifyCameraMode) {
        MissionItem* item = new MissionItem(nextSequenceNumber++,
                                            MAV_CMD_SET_CAMERA_MODE,
                                            MAV_FRAME_MISSION,
                                            0,                                      // camera id, all cameras
                                            _cameraModeFact.rawValue().toDouble(),
                                            NAN, NAN, NAN, NAN, NAN,                // param 3-7 unused
                                            true,                                   // autoContinue
                                            false,                                  // isCurrentItem
                                            missionItemParent);
        items.append(item);
    }
224 225
}

226
bool CameraSection::scanForSection(QmlObjectListModel* visualItems, int scanIndex)
227 228 229
{
    bool foundGimbal = false;
    bool foundCameraAction = false;
230
    bool foundCameraMode = false;
231 232 233 234
    bool stopLooking = false;

    qCDebug(CameraSectionLog) << "CameraSection::scanForCameraSection" << visualItems->count() << scanIndex;

235 236 237 238
    if (!_available || scanIndex >= visualItems->count()) {
        return false;
    }

239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266
    // Scan through the initial mission items for possible mission settings

    while (!stopLooking && visualItems->count() > scanIndex) {
        SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
        if (!item) {
            // We hit a complex item there can be no more possible mission settings
            return foundGimbal || foundCameraAction;
        }
        MissionItem& missionItem = item->missionItem();

        qCDebug(CameraSectionLog) << item->command() << missionItem.param1() << missionItem.param2() << missionItem.param3() << missionItem.param4() << missionItem.param5() << missionItem.param6() << missionItem.param7() ;

        // See CameraSection::appendMissionItems for specs on what compomises a known camera section item

        switch ((MAV_CMD)item->command()) {
        case MAV_CMD_DO_MOUNT_CONTROL:
            if (!foundGimbal && missionItem.param2() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == MAV_MOUNT_MODE_MAVLINK_TARGETING) {
                foundGimbal = true;
                setSpecifyGimbal(true);
                gimbalPitch()->setRawValue(missionItem.param1());
                gimbalYaw()->setRawValue(missionItem.param3());
                visualItems->removeAt(scanIndex)->deleteLater();
            } else {
                stopLooking = true;
            }
            break;

        case MAV_CMD_IMAGE_START_CAPTURE:
267
            if (!foundCameraAction && missionItem.param1() == 0 && missionItem.param2() >= 1 && missionItem.param3() == 0 && missionItem.param4() == -1 && missionItem.param5() == -1 && missionItem.param6() == 0 && missionItem.param7() == 0) {
268 269
                foundCameraAction = true;
                cameraAction()->setRawValue(TakePhotosIntervalTime);
270
                cameraPhotoIntervalTime()->setRawValue(missionItem.param2());
271
                visualItems->removeAt(scanIndex)->deleteLater();
272 273
            } else {
                stopLooking = true;
274 275 276 277
            }
            break;

        case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
278
            if (!foundCameraAction && missionItem.param1() >= 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
279
                // At this point we don't know if we have a stop taking photos pair, or just a distance trigger
280 281

                if (missionItem.param1() == 0 && scanIndex < visualItems->count() - 1) {
282
                    // Possible stop taking photos pair
283 284
                    SimpleMissionItem* nextItem = visualItems->value<SimpleMissionItem*>(scanIndex + 1);
                    if (nextItem) {
285 286 287
                        MissionItem& nextMissionItem = nextItem->missionItem();
                        if (nextMissionItem.command() == MAV_CMD_IMAGE_STOP_CAPTURE && nextMissionItem.param1() == 0 && nextMissionItem.param2() == 0 && nextMissionItem.param3() == 0 && nextMissionItem.param4() == 0 && nextMissionItem.param5() == 0 && nextMissionItem.param6() == 0 && nextMissionItem.param7() == 0) {
                            // We found a stop taking photos pair
288 289 290 291
                            foundCameraAction = true;
                            cameraAction()->setRawValue(StopTakingPhotos);
                            visualItems->removeAt(scanIndex)->deleteLater();
                            visualItems->removeAt(scanIndex)->deleteLater();
292
                            stopLooking = true;
293 294 295 296 297
                            break;
                        }
                    }
                }

298 299 300 301 302 303 304 305 306
                // We didn't find a stop taking photos pair, check for trigger distance
                if (missionItem.param1() > 0) {
                    foundCameraAction = true;
                    cameraAction()->setRawValue(TakePhotoIntervalDistance);
                    cameraPhotoIntervalDistance()->setRawValue(missionItem.param1());
                    visualItems->removeAt(scanIndex)->deleteLater();
                    stopLooking = true;
                    break;
                }
307
            }
308
            stopLooking = true;
309 310 311 312 313 314 315
            break;

        case MAV_CMD_VIDEO_START_CAPTURE:
            if (!foundCameraAction && missionItem.param1() == 0 && missionItem.param2() == -1 && missionItem.param3() == -1 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
                foundCameraAction = true;
                cameraAction()->setRawValue(TakeVideo);
                visualItems->removeAt(scanIndex)->deleteLater();
316 317
            } else {
                stopLooking = true;
318 319 320 321 322 323 324 325
            }
            break;

        case MAV_CMD_VIDEO_STOP_CAPTURE:
            if (!foundCameraAction && missionItem.param1() == 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
                foundCameraAction = true;
                cameraAction()->setRawValue(StopTakingVideo);
                visualItems->removeAt(scanIndex)->deleteLater();
326 327 328 329 330 331 332 333 334 335 336 337 338 339
            } else {
                stopLooking = true;
            }
            break;

        case MAV_CMD_SET_CAMERA_MODE:
            // We specifically don't test param 5/6/7 since we don't have NaN persistence for those fields
            if (!foundCameraMode && missionItem.param1() == 0 && (missionItem.param2() == 0 || missionItem.param2() == 1) && qIsNaN(missionItem.param3())) {
                foundCameraMode = true;
                setSpecifyCameraMode(true);
                cameraMode()->setRawValue(missionItem.param2());
                visualItems->removeAt(scanIndex)->deleteLater();
            } else {
                stopLooking = true;
340 341 342 343 344 345 346 347 348
            }
            break;

        default:
            stopLooking = true;
            break;
        }
    }

349
    qCDebug(CameraSectionLog) << foundGimbal << foundCameraAction << foundCameraMode;
350

351
    _settingsSpecified = foundGimbal || foundCameraAction || foundCameraMode;
352 353
    emit settingsSpecifiedChanged(_settingsSpecified);

354
    return _settingsSpecified;
355 356 357 358 359 360 361
}

void CameraSection::_setDirty(void)
{
    setDirty(true);
}

362
void CameraSection::_setDirtyAndUpdateItemCount(void)
363
{
364
    emit itemCountChanged(itemCount());
365 366 367 368 369 370 371 372 373 374
    setDirty(true);
}

void CameraSection::setAvailable(bool available)
{
    if (_available != available) {
        _available = available;
        emit availableChanged(available);
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
375 376 377 378 379 380 381 382 383 384

double CameraSection::specifiedGimbalYaw(void) const
{
    return _specifyGimbal ? _gimbalYawFact.rawValue().toDouble() : std::numeric_limits<double>::quiet_NaN();
}

void CameraSection::_updateSpecifiedGimbalYaw(void)
{
    emit specifiedGimbalYawChanged(specifiedGimbalYaw());
}
385 386 387

void CameraSection::_updateSettingsSpecified(void)
{
388
    bool newSettingsSpecified = _specifyGimbal || _specifyCameraMode || _cameraActionFact.rawValue().toInt() != CameraActionNone;
389 390 391 392 393 394
    if (newSettingsSpecified != _settingsSpecified) {
        _settingsSpecified = newSettingsSpecified;
        emit settingsSpecifiedChanged(newSettingsSpecified);
    }
}

395
void CameraSection::_specifyChanged(void)
396 397 398 399 400 401 402 403 404 405
{
    _setDirtyAndUpdateItemCount();
    _updateSettingsSpecified();
}

void CameraSection::_cameraActionChanged(void)
{
    _setDirtyAndUpdateItemCount();
    _updateSettingsSpecified();
}
406 407 408 409 410

bool CameraSection::cameraModeSupported(void) const
{
    return _vehicle->firmwarePlugin()->supportedMissionCommands().contains(MAV_CMD_SET_CAMERA_MODE);
}