Browse Source

Make sure video streaming is running before accessing the video receiver.

QGC4.4
Gus Grubba 6 years ago
parent
commit
4d851c949c
  1. 20
      src/Camera/QGCCameraControl.cc
  2. 12
      src/Vehicle/Vehicle.cc

20
src/Camera/QGCCameraControl.cc

@ -364,10 +364,12 @@ QGCCameraControl::takePhoto() @@ -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 @@ -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);
}
}
}

12
src/Vehicle/Vehicle.cc

@ -1640,9 +1640,11 @@ void Vehicle::_updateArmed(bool armed) @@ -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) @@ -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<uint8_t>(_mavlink->getSystemId()),
static_cast<uint8_t>(_mavlink->getComponentId()),
priorityLink()->mavlinkChannel(),
&msg,
ping.time_usec,

Loading…
Cancel
Save