|
|
@ -364,10 +364,12 @@ QGCCameraControl::takePhoto() |
|
|
|
_setPhotoStatus(PHOTO_CAPTURE_IN_PROGRESS); |
|
|
|
_setPhotoStatus(PHOTO_CAPTURE_IN_PROGRESS); |
|
|
|
_captureInfoRetries = 0; |
|
|
|
_captureInfoRetries = 0; |
|
|
|
//-- Capture local image as well
|
|
|
|
//-- Capture local image as well
|
|
|
|
QString photoPath = qgcApp()->toolbox()->settingsManager()->appSettings()->savePath()->rawValue().toString() + QStringLiteral("/Photo"); |
|
|
|
if(qgcApp()->toolbox()->videoManager()->videoReceiver()) { |
|
|
|
QDir().mkpath(photoPath); |
|
|
|
QString photoPath = qgcApp()->toolbox()->settingsManager()->appSettings()->savePath()->rawValue().toString() + QStringLiteral("/Photo"); |
|
|
|
photoPath += + "/" + QDateTime::currentDateTime().toString("yyyy-MM-dd_hh.mm.ss.zzz") + ".jpg"; |
|
|
|
QDir().mkpath(photoPath); |
|
|
|
qgcApp()->toolbox()->videoManager()->videoReceiver()->grabImage(photoPath); |
|
|
|
photoPath += + "/" + QDateTime::currentDateTime().toString("yyyy-MM-dd_hh.mm.ss.zzz") + ".jpg"; |
|
|
|
|
|
|
|
qgcApp()->toolbox()->videoManager()->videoReceiver()->grabImage(photoPath); |
|
|
|
|
|
|
|
} |
|
|
|
return true; |
|
|
|
return true; |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
@ -1471,10 +1473,12 @@ QGCCameraControl::handleCaptureStatus(const mavlink_camera_capture_status_t& cap |
|
|
|
//-- Time Lapse
|
|
|
|
//-- Time Lapse
|
|
|
|
if(photoStatus() == PHOTO_CAPTURE_INTERVAL_IDLE || photoStatus() == PHOTO_CAPTURE_INTERVAL_IN_PROGRESS) { |
|
|
|
if(photoStatus() == PHOTO_CAPTURE_INTERVAL_IDLE || photoStatus() == PHOTO_CAPTURE_INTERVAL_IN_PROGRESS) { |
|
|
|
//-- Capture local image as well
|
|
|
|
//-- Capture local image as well
|
|
|
|
QString photoPath = qgcApp()->toolbox()->settingsManager()->appSettings()->savePath()->rawValue().toString() + QStringLiteral("/Photo"); |
|
|
|
if(qgcApp()->toolbox()->videoManager()->videoReceiver()) { |
|
|
|
QDir().mkpath(photoPath); |
|
|
|
QString photoPath = qgcApp()->toolbox()->settingsManager()->appSettings()->savePath()->rawValue().toString() + QStringLiteral("/Photo"); |
|
|
|
photoPath += + "/" + QDateTime::currentDateTime().toString("yyyy-MM-dd_hh.mm.ss.zzz") + ".jpg"; |
|
|
|
QDir().mkpath(photoPath); |
|
|
|
qgcApp()->toolbox()->videoManager()->videoReceiver()->grabImage(photoPath); |
|
|
|
photoPath += + "/" + QDateTime::currentDateTime().toString("yyyy-MM-dd_hh.mm.ss.zzz") + ".jpg"; |
|
|
|
|
|
|
|
qgcApp()->toolbox()->videoManager()->videoReceiver()->grabImage(photoPath); |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|