diff --git a/src/Camera/QGCCameraControl.cc b/src/Camera/QGCCameraControl.cc index 49600b339bb21e519bcffcaf378757d882646df9..cf98ea1854aa20276a9d777860c3298d16aae70a 100644 --- a/src/Camera/QGCCameraControl.cc +++ b/src/Camera/QGCCameraControl.cc @@ -364,10 +364,12 @@ QGCCameraControl::takePhoto() _setPhotoStatus(PHOTO_CAPTURE_IN_PROGRESS); _captureInfoRetries = 0; //-- Capture local image as well - QString photoPath = qgcApp()->toolbox()->settingsManager()->appSettings()->savePath()->rawValue().toString() + QStringLiteral("/Photo"); - QDir().mkpath(photoPath); - photoPath += + "/" + QDateTime::currentDateTime().toString("yyyy-MM-dd_hh.mm.ss.zzz") + ".jpg"; - qgcApp()->toolbox()->videoManager()->videoReceiver()->grabImage(photoPath); + if(qgcApp()->toolbox()->videoManager()->videoReceiver()) { + QString photoPath = qgcApp()->toolbox()->settingsManager()->appSettings()->savePath()->rawValue().toString() + QStringLiteral("/Photo"); + QDir().mkpath(photoPath); + photoPath += + "/" + QDateTime::currentDateTime().toString("yyyy-MM-dd_hh.mm.ss.zzz") + ".jpg"; + qgcApp()->toolbox()->videoManager()->videoReceiver()->grabImage(photoPath); + } return true; } } @@ -1471,10 +1473,12 @@ QGCCameraControl::handleCaptureStatus(const mavlink_camera_capture_status_t& cap //-- Time Lapse if(photoStatus() == PHOTO_CAPTURE_INTERVAL_IDLE || photoStatus() == PHOTO_CAPTURE_INTERVAL_IN_PROGRESS) { //-- Capture local image as well - QString photoPath = qgcApp()->toolbox()->settingsManager()->appSettings()->savePath()->rawValue().toString() + QStringLiteral("/Photo"); - QDir().mkpath(photoPath); - photoPath += + "/" + QDateTime::currentDateTime().toString("yyyy-MM-dd_hh.mm.ss.zzz") + ".jpg"; - qgcApp()->toolbox()->videoManager()->videoReceiver()->grabImage(photoPath); + if(qgcApp()->toolbox()->videoManager()->videoReceiver()) { + QString photoPath = qgcApp()->toolbox()->settingsManager()->appSettings()->savePath()->rawValue().toString() + QStringLiteral("/Photo"); + QDir().mkpath(photoPath); + photoPath += + "/" + QDateTime::currentDateTime().toString("yyyy-MM-dd_hh.mm.ss.zzz") + ".jpg"; + qgcApp()->toolbox()->videoManager()->videoReceiver()->grabImage(photoPath); + } } } diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 9f540b7fc56959c81724739fc555a40d91a64ea0..22abf839e68eeb3f2f5971c47079a2d4637135db 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -1640,9 +1640,11 @@ void Vehicle::_updateArmed(bool armed) } else { _mapTrajectoryStop(); // Also handle Video Streaming - if(_settingsManager->videoSettings()->disableWhenDisarmed()->rawValue().toBool()) { - _settingsManager->videoSettings()->streamEnabled()->setRawValue(false); - qgcApp()->toolbox()->videoManager()->videoReceiver()->stop(); + if(qgcApp()->toolbox()->videoManager()->videoReceiver()) { + if(_settingsManager->videoSettings()->disableWhenDisarmed()->rawValue().toBool()) { + _settingsManager->videoSettings()->streamEnabled()->setRawValue(false); + qgcApp()->toolbox()->videoManager()->videoReceiver()->stop(); + } } } } @@ -1654,8 +1656,8 @@ void Vehicle::_handlePing(LinkInterface* link, mavlink_message_t& message) mavlink_message_t msg; mavlink_msg_ping_decode(&message, &ping); - mavlink_msg_ping_pack_chan(_mavlink->getSystemId(), - _mavlink->getComponentId(), + mavlink_msg_ping_pack_chan(static_cast(_mavlink->getSystemId()), + static_cast(_mavlink->getComponentId()), priorityLink()->mavlinkChannel(), &msg, ping.time_usec,