CameraSection.cc 22.2 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

DonLakeFlyer's avatar
DonLakeFlyer committed
118 119 120 121 122 123
    if (_specifyCameraMode) {
        MissionItem* item = new MissionItem(nextSequenceNumber++,
                                            MAV_CMD_SET_CAMERA_MODE,
                                            MAV_FRAME_MISSION,
                                            0,                                      // camera id, all cameras
                                            _cameraModeFact.rawValue().toDouble(),
124 125
                                            NAN,                                    // Audio off/on
                                            NAN, NAN, NAN, NAN,                     // param 4-7 reserved
DonLakeFlyer's avatar
DonLakeFlyer committed
126 127 128 129 130 131
                                            true,                                   // autoContinue
                                            false,                                  // isCurrentItem
                                            missionItemParent);
        items.append(item);
    }

132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154
    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,
155
                                   0,                                               // Camera ID, all cameras
156 157
                                   _cameraPhotoIntervalTimeFact.rawValue().toInt(), // Interval
                                   0,                                               // Unlimited photo count
158
                                   NAN, NAN, NAN, NAN,                              // param 4-7 reserved
159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178
                                   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,
179
                                   0,                           // camera id = 0, all cameras
180 181
                                   0,                           // No CAMERA_CAPTURE_STATUS streaming
                                   NAN, NAN, NAN, NAN, NAN,     // param 3-7 reserved
182 183 184 185
                                   true,                        // autoContinue
                                   false,                       // isCurrentItem
                                   missionItemParent);
            break;
186 187 188 189 190

        case StopTakingVideo:
            item = new MissionItem(nextSequenceNumber++,
                                   MAV_CMD_VIDEO_STOP_CAPTURE,
                                   MAV_FRAME_MISSION,
191 192 193 194
                                   0,                               // Camera ID, all cameras
                                   NAN, NAN, NAN, NAN, NAN, NAN,    // param 2-7 reserved
                                   true,                            // autoContinue
                                   false,                           // isCurrentItem
195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210
                                   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,
211 212 213 214
                                   0,                               // camera id, all cameras
                                   NAN, NAN, NAN, NAN, NAN, NAN,    // param 2-7 reserved
                                   true,                            // autoContinue
                                   false,                           // isCurrentItem
215 216
                                   missionItemParent);
            break;
DonLakeFlyer's avatar
DonLakeFlyer committed
217 218

        case TakePhoto:
219 220 221
            item = new MissionItem(nextSequenceNumber++,
                                   MAV_CMD_IMAGE_START_CAPTURE,
                                   MAV_FRAME_MISSION,
222 223 224 225 226 227
                                   0,                           // camera id = 0, all cameras
                                   0,                           // Interval (none)
                                   1,                           // Take 1 photo
                                   NAN, NAN, NAN, NAN,          // param 4-7 reserved
                                   true,                        // autoContinue
                                   false,                       // isCurrentItem
228
                                   missionItemParent);
DonLakeFlyer's avatar
DonLakeFlyer committed
229
            break;
230 231 232 233 234 235 236
        }
        if (item) {
            items.append(item);
        }
    }
}

237
bool CameraSection::_scanGimbal(QmlObjectListModel* visualItems, int scanIndex)
238
{
239 240
    SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
    if (item) {
241
        MissionItem& missionItem = item->missionItem();
242 243
        if ((MAV_CMD)item->command() == MAV_CMD_DO_MOUNT_CONTROL) {
            if (missionItem.param2() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == MAV_MOUNT_MODE_MAVLINK_TARGETING) {
244 245 246 247
                setSpecifyGimbal(true);
                gimbalPitch()->setRawValue(missionItem.param1());
                gimbalYaw()->setRawValue(missionItem.param3());
                visualItems->removeAt(scanIndex)->deleteLater();
248
                return true;
249
            }
250 251
        }
    }
252

253 254 255 256 257 258 259 260 261
    return false;
}

bool CameraSection::_scanTakePhoto(QmlObjectListModel* visualItems, int scanIndex)
{
    SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
    if (item) {
        MissionItem& missionItem = item->missionItem();
        if ((MAV_CMD)item->command() == MAV_CMD_IMAGE_START_CAPTURE) {
262
            if (missionItem.param1() == 0 && missionItem.param2() == 0 && missionItem.param3() == 1) {
263
                cameraAction()->setRawValue(TakePhoto);
264
                visualItems->removeAt(scanIndex)->deleteLater();
265
                return true;
266
            }
267 268
        }
    }
269

270 271
    return false;
}
272

273 274 275 276 277 278
bool CameraSection::_scanTakePhotosIntervalTime(QmlObjectListModel* visualItems, int scanIndex)
{
    SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
    if (item) {
        MissionItem& missionItem = item->missionItem();
        if ((MAV_CMD)item->command() == MAV_CMD_IMAGE_START_CAPTURE) {
279
            if (missionItem.param1() == 0 && missionItem.param2() >= 1 && missionItem.param3() == 0) {
280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298
                cameraAction()->setRawValue(TakePhotosIntervalTime);
                cameraPhotoIntervalTime()->setRawValue(missionItem.param2());
                visualItems->removeAt(scanIndex)->deleteLater();
                return true;
            }
        }
    }

    return false;
}

bool CameraSection::_scanStopTakingPhotos(QmlObjectListModel* visualItems, int scanIndex)
{
    SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
    if (item) {
        MissionItem& missionItem = item->missionItem();
        if ((MAV_CMD)item->command() == MAV_CMD_DO_SET_CAM_TRIGG_DIST) {
            if (missionItem.param1() == 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
                if (scanIndex < visualItems->count() - 1) {
299 300
                    SimpleMissionItem* nextItem = visualItems->value<SimpleMissionItem*>(scanIndex + 1);
                    if (nextItem) {
301
                        MissionItem& nextMissionItem = nextItem->missionItem();
302
                        if (nextMissionItem.command() == MAV_CMD_IMAGE_STOP_CAPTURE && nextMissionItem.param1() == 0) {
303 304 305
                            cameraAction()->setRawValue(StopTakingPhotos);
                            visualItems->removeAt(scanIndex)->deleteLater();
                            visualItems->removeAt(scanIndex)->deleteLater();
306
                            return true;
307 308 309
                        }
                    }
                }
310 311 312
            }
        }
    }
313

314 315 316 317 318 319 320 321 322 323 324 325 326 327
    return false;
}

bool CameraSection::_scanTriggerDistance(QmlObjectListModel* visualItems, int scanIndex)
{
    SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
    if (item) {
        MissionItem& missionItem = item->missionItem();
        if ((MAV_CMD)item->command() == MAV_CMD_DO_SET_CAM_TRIGG_DIST) {
            if (missionItem.param1() >= 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
                cameraAction()->setRawValue(TakePhotoIntervalDistance);
                cameraPhotoIntervalDistance()->setRawValue(missionItem.param1());
                visualItems->removeAt(scanIndex)->deleteLater();
                return true;
328
            }
329 330 331 332 333
        }
    }

    return false;
}
334

335 336 337 338 339 340
bool CameraSection::_scanTakeVideo(QmlObjectListModel* visualItems, int scanIndex)
{
    SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
    if (item) {
        MissionItem& missionItem = item->missionItem();
        if ((MAV_CMD)item->command() == MAV_CMD_VIDEO_START_CAPTURE) {
341
            if (missionItem.param1() == 0 && missionItem.param2() == 0) {
342 343
                cameraAction()->setRawValue(TakeVideo);
                visualItems->removeAt(scanIndex)->deleteLater();
344
                return true;
345
            }
346 347
        }
    }
348

349 350 351 352 353 354 355 356 357
    return false;
}

bool CameraSection::_scanStopTakingVideo(QmlObjectListModel* visualItems, int scanIndex)
{
    SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
    if (item) {
        MissionItem& missionItem = item->missionItem();
        if ((MAV_CMD)item->command() == MAV_CMD_VIDEO_STOP_CAPTURE) {
358
            if (missionItem.param1() == 0) {
359 360
                cameraAction()->setRawValue(StopTakingVideo);
                visualItems->removeAt(scanIndex)->deleteLater();
361
                return true;
362
            }
363 364
        }
    }
365

366 367 368 369 370 371 372 373 374
    return false;
}

bool CameraSection::_scanSetCameraMode(QmlObjectListModel* visualItems, int scanIndex)
{
    SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
    if (item) {
        MissionItem& missionItem = item->missionItem();
        if ((MAV_CMD)item->command() == MAV_CMD_SET_CAMERA_MODE) {
375
            // We specifically don't test param 5/6/7 since we don't have NaN persistence for those fields
376
            if (missionItem.param1() == 0 && (missionItem.param2() == 0 || missionItem.param2() == 1) && qIsNaN(missionItem.param3())) {
377 378 379
                setSpecifyCameraMode(true);
                cameraMode()->setRawValue(missionItem.param2());
                visualItems->removeAt(scanIndex)->deleteLater();
380
                return true;
381
            }
382 383
        }
    }
384

385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433
    return false;
}

bool CameraSection::scanForSection(QmlObjectListModel* visualItems, int scanIndex)
{
    bool foundGimbal = false;
    bool foundCameraAction = false;
    bool foundCameraMode = false;

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

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

    // Scan through the initial mission items for possible mission settings

    while (visualItems->count() > scanIndex) {
        if (!foundGimbal && _scanGimbal(visualItems, scanIndex)) {
            foundGimbal = true;
            continue;
        }
        if (!foundCameraAction && _scanTakePhoto(visualItems, scanIndex)) {
            foundCameraAction = true;
            continue;
        }
        if (!foundCameraAction && _scanTakePhotosIntervalTime(visualItems, scanIndex)) {
            foundCameraAction = true;
            continue;
        }
        if (!foundCameraAction && _scanStopTakingPhotos(visualItems, scanIndex)) {
            foundCameraAction = true;
            continue;
        }
        if (!foundCameraAction && _scanTriggerDistance(visualItems, scanIndex)) {
            foundCameraAction = true;
            continue;
        }
        if (!foundCameraAction && _scanTakeVideo(visualItems, scanIndex)) {
            foundCameraAction = true;
            continue;
        }
        if (!foundCameraAction && _scanStopTakingVideo(visualItems, scanIndex)) {
            foundCameraAction = true;
            continue;
        }
        if (!foundCameraMode && _scanSetCameraMode(visualItems, scanIndex)) {
            foundCameraMode = true;
            continue;
434
        }
435
        break;
436 437
    }

438
    qCDebug(CameraSectionLog) << "CameraSection::scanForCameraSection foundGimbal:foundCameraAction:foundCameraMode;" << foundGimbal << foundCameraAction << foundCameraMode;
439

440
    _settingsSpecified = foundGimbal || foundCameraAction || foundCameraMode;
441 442
    emit settingsSpecifiedChanged(_settingsSpecified);

443
    return _settingsSpecified;
444 445 446 447 448 449 450
}

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

451
void CameraSection::_setDirtyAndUpdateItemCount(void)
452
{
453
    emit itemCountChanged(itemCount());
454 455 456 457 458 459 460 461 462 463
    setDirty(true);
}

void CameraSection::setAvailable(bool available)
{
    if (_available != available) {
        _available = available;
        emit availableChanged(available);
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
464 465 466 467 468 469 470 471 472 473

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

void CameraSection::_updateSpecifiedGimbalYaw(void)
{
    emit specifiedGimbalYawChanged(specifiedGimbalYaw());
}
474 475 476

void CameraSection::_updateSettingsSpecified(void)
{
477
    bool newSettingsSpecified = _specifyGimbal || _specifyCameraMode || _cameraActionFact.rawValue().toInt() != CameraActionNone;
478 479 480 481 482 483
    if (newSettingsSpecified != _settingsSpecified) {
        _settingsSpecified = newSettingsSpecified;
        emit settingsSpecifiedChanged(newSettingsSpecified);
    }
}

484
void CameraSection::_specifyChanged(void)
485 486 487 488 489 490 491 492 493 494
{
    _setDirtyAndUpdateItemCount();
    _updateSettingsSpecified();
}

void CameraSection::_cameraActionChanged(void)
{
    _setDirtyAndUpdateItemCount();
    _updateSettingsSpecified();
}
495 496 497 498 499

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