@ -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 ;
}
}
@ -667,6 +669,9 @@ QGCCameraControl::_mavCommandResult(int vehicleId, int component, int command, i
@@ -667,6 +669,9 @@ QGCCameraControl::_mavCommandResult(int vehicleId, int component, int command, i
case MAV_CMD_REQUEST_STORAGE_INFORMATION :
_storageInfoRetries = 0 ;
break ;
case MAV_CMD_IMAGE_START_CAPTURE :
_captureStatusTimer . start ( 1000 ) ;
break ;
}
} else {
if ( noReponseFromVehicle | | result = = MAV_RESULT_TEMPORARILY_REJECTED | | result = = MAV_RESULT_FAILED ) {
@ -1471,10 +1476,12 @@ QGCCameraControl::handleCaptureStatus(const mavlink_camera_capture_status_t& cap
@@ -1471,10 +1476,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 ) ;
}
}
}