|
|
@ -157,6 +157,7 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh |
|
|
|
, _photo_status(PHOTO_CAPTURE_STATUS_UNDEFINED) |
|
|
|
, _photo_status(PHOTO_CAPTURE_STATUS_UNDEFINED) |
|
|
|
, _storageInfoRetries(0) |
|
|
|
, _storageInfoRetries(0) |
|
|
|
, _captureInfoRetries(0) |
|
|
|
, _captureInfoRetries(0) |
|
|
|
|
|
|
|
, _resetting(false) |
|
|
|
{ |
|
|
|
{ |
|
|
|
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); |
|
|
|
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); |
|
|
|
memcpy(&_info, info, sizeof(mavlink_camera_information_t)); |
|
|
|
memcpy(&_info, info, sizeof(mavlink_camera_information_t)); |
|
|
@ -251,14 +252,16 @@ QGCCameraControl::storageFreeStr() |
|
|
|
void |
|
|
|
void |
|
|
|
QGCCameraControl::setCameraMode(CameraMode mode) |
|
|
|
QGCCameraControl::setCameraMode(CameraMode mode) |
|
|
|
{ |
|
|
|
{ |
|
|
|
qCDebug(CameraControlLog) << "setCameraMode(" << mode << ")"; |
|
|
|
if(!_resetting) { |
|
|
|
if(mode == CAM_MODE_VIDEO) { |
|
|
|
qCDebug(CameraControlLog) << "setCameraMode(" << mode << ")"; |
|
|
|
setVideoMode(); |
|
|
|
if(mode == CAM_MODE_VIDEO) { |
|
|
|
} else if(mode == CAM_MODE_PHOTO) { |
|
|
|
setVideoMode(); |
|
|
|
setPhotoMode(); |
|
|
|
} else if(mode == CAM_MODE_PHOTO) { |
|
|
|
} else { |
|
|
|
setPhotoMode(); |
|
|
|
qCDebug(CameraControlLog) << "setCameraMode() Invalid mode:" << mode; |
|
|
|
} else { |
|
|
|
return; |
|
|
|
qCDebug(CameraControlLog) << "setCameraMode() Invalid mode:" << mode; |
|
|
|
|
|
|
|
return; |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
@ -266,10 +269,12 @@ QGCCameraControl::setCameraMode(CameraMode mode) |
|
|
|
void |
|
|
|
void |
|
|
|
QGCCameraControl::setPhotoMode(PhotoMode mode) |
|
|
|
QGCCameraControl::setPhotoMode(PhotoMode mode) |
|
|
|
{ |
|
|
|
{ |
|
|
|
_photoMode = mode; |
|
|
|
if(!_resetting) { |
|
|
|
QSettings settings; |
|
|
|
_photoMode = mode; |
|
|
|
settings.setValue(kPhotoMode, static_cast<int>(mode)); |
|
|
|
QSettings settings; |
|
|
|
emit photoModeChanged(); |
|
|
|
settings.setValue(kPhotoMode, static_cast<int>(mode)); |
|
|
|
|
|
|
|
emit photoModeChanged(); |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
//-----------------------------------------------------------------------------
|
|
|
|
//-----------------------------------------------------------------------------
|
|
|
@ -304,10 +309,12 @@ QGCCameraControl::_setCameraMode(CameraMode mode) |
|
|
|
void |
|
|
|
void |
|
|
|
QGCCameraControl::toggleMode() |
|
|
|
QGCCameraControl::toggleMode() |
|
|
|
{ |
|
|
|
{ |
|
|
|
if(cameraMode() == CAM_MODE_PHOTO || cameraMode() == CAM_MODE_SURVEY) { |
|
|
|
if(!_resetting) { |
|
|
|
setVideoMode(); |
|
|
|
if(cameraMode() == CAM_MODE_PHOTO || cameraMode() == CAM_MODE_SURVEY) { |
|
|
|
} else if(cameraMode() == CAM_MODE_VIDEO) { |
|
|
|
setVideoMode(); |
|
|
|
setPhotoMode(); |
|
|
|
} else if(cameraMode() == CAM_MODE_VIDEO) { |
|
|
|
|
|
|
|
setPhotoMode(); |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
@ -315,11 +322,14 @@ QGCCameraControl::toggleMode() |
|
|
|
bool |
|
|
|
bool |
|
|
|
QGCCameraControl::toggleVideo() |
|
|
|
QGCCameraControl::toggleVideo() |
|
|
|
{ |
|
|
|
{ |
|
|
|
if(videoStatus() == VIDEO_CAPTURE_STATUS_RUNNING) { |
|
|
|
if(!_resetting) { |
|
|
|
return stopVideo(); |
|
|
|
if(videoStatus() == VIDEO_CAPTURE_STATUS_RUNNING) { |
|
|
|
} else { |
|
|
|
return stopVideo(); |
|
|
|
return startVideo(); |
|
|
|
} else { |
|
|
|
|
|
|
|
return startVideo(); |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
return false; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
//-----------------------------------------------------------------------------
|
|
|
|
//-----------------------------------------------------------------------------
|
|
|
@ -331,22 +341,24 @@ QGCCameraControl::takePhoto() |
|
|
|
if(!capturesPhotos() || (cameraMode() == CAM_MODE_VIDEO && !photosInVideoMode()) || photoStatus() != PHOTO_CAPTURE_IDLE) { |
|
|
|
if(!capturesPhotos() || (cameraMode() == CAM_MODE_VIDEO && !photosInVideoMode()) || photoStatus() != PHOTO_CAPTURE_IDLE) { |
|
|
|
return false; |
|
|
|
return false; |
|
|
|
} |
|
|
|
} |
|
|
|
if(capturesPhotos()) { |
|
|
|
if(!_resetting) { |
|
|
|
_vehicle->sendMavCommand( |
|
|
|
if(capturesPhotos()) { |
|
|
|
_compID, // Target component
|
|
|
|
_vehicle->sendMavCommand( |
|
|
|
MAV_CMD_IMAGE_START_CAPTURE, // Command id
|
|
|
|
_compID, // Target component
|
|
|
|
false, // ShowError
|
|
|
|
MAV_CMD_IMAGE_START_CAPTURE, // Command id
|
|
|
|
0, // Reserved (Set to 0)
|
|
|
|
false, // ShowError
|
|
|
|
static_cast<float>(_photoMode == PHOTO_CAPTURE_SINGLE ? 0 : _photoLapse), // Duration between two consecutive pictures (in seconds--ignored if single image)
|
|
|
|
0, // Reserved (Set to 0)
|
|
|
|
_photoMode == PHOTO_CAPTURE_SINGLE ? 1 : _photoLapseCount); // Number of images to capture total - 0 for unlimited capture
|
|
|
|
static_cast<float>(_photoMode == PHOTO_CAPTURE_SINGLE ? 0 : _photoLapse), // Duration between two consecutive pictures (in seconds--ignored if single image)
|
|
|
|
_setPhotoStatus(PHOTO_CAPTURE_IN_PROGRESS); |
|
|
|
_photoMode == PHOTO_CAPTURE_SINGLE ? 1 : _photoLapseCount); // Number of images to capture total - 0 for unlimited capture
|
|
|
|
_captureInfoRetries = 0; |
|
|
|
_setPhotoStatus(PHOTO_CAPTURE_IN_PROGRESS); |
|
|
|
//-- Capture local image as well
|
|
|
|
_captureInfoRetries = 0; |
|
|
|
QString photoPath = qgcApp()->toolbox()->settingsManager()->appSettings()->savePath()->rawValue().toString() + QStringLiteral("/Photo"); |
|
|
|
//-- Capture local image as well
|
|
|
|
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"; |
|
|
|
return true; |
|
|
|
qgcApp()->toolbox()->videoManager()->videoReceiver()->grabImage(photoPath); |
|
|
|
|
|
|
|
return true; |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
return false; |
|
|
|
return false; |
|
|
|
} |
|
|
|
} |
|
|
@ -355,19 +367,21 @@ QGCCameraControl::takePhoto() |
|
|
|
bool |
|
|
|
bool |
|
|
|
QGCCameraControl::stopTakePhoto() |
|
|
|
QGCCameraControl::stopTakePhoto() |
|
|
|
{ |
|
|
|
{ |
|
|
|
qCDebug(CameraControlLog) << "stopTakePhoto()"; |
|
|
|
if(!_resetting) { |
|
|
|
if(photoStatus() == PHOTO_CAPTURE_IDLE || (photoStatus() != PHOTO_CAPTURE_INTERVAL_IDLE && photoStatus() != PHOTO_CAPTURE_INTERVAL_IN_PROGRESS)) { |
|
|
|
qCDebug(CameraControlLog) << "stopTakePhoto()"; |
|
|
|
return false; |
|
|
|
if(photoStatus() == PHOTO_CAPTURE_IDLE || (photoStatus() != PHOTO_CAPTURE_INTERVAL_IDLE && photoStatus() != PHOTO_CAPTURE_INTERVAL_IN_PROGRESS)) { |
|
|
|
} |
|
|
|
return false; |
|
|
|
if(capturesPhotos()) { |
|
|
|
} |
|
|
|
_vehicle->sendMavCommand( |
|
|
|
if(capturesPhotos()) { |
|
|
|
_compID, // Target component
|
|
|
|
_vehicle->sendMavCommand( |
|
|
|
MAV_CMD_IMAGE_STOP_CAPTURE, // Command id
|
|
|
|
_compID, // Target component
|
|
|
|
false, // ShowError
|
|
|
|
MAV_CMD_IMAGE_STOP_CAPTURE, // Command id
|
|
|
|
0); // Reserved (Set to 0)
|
|
|
|
false, // ShowError
|
|
|
|
_setPhotoStatus(PHOTO_CAPTURE_IDLE); |
|
|
|
0); // Reserved (Set to 0)
|
|
|
|
_captureInfoRetries = 0; |
|
|
|
_setPhotoStatus(PHOTO_CAPTURE_IDLE); |
|
|
|
return true; |
|
|
|
_captureInfoRetries = 0; |
|
|
|
|
|
|
|
return true; |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
return false; |
|
|
|
return false; |
|
|
|
} |
|
|
|
} |
|
|
@ -376,19 +390,21 @@ QGCCameraControl::stopTakePhoto() |
|
|
|
bool |
|
|
|
bool |
|
|
|
QGCCameraControl::startVideo() |
|
|
|
QGCCameraControl::startVideo() |
|
|
|
{ |
|
|
|
{ |
|
|
|
qCDebug(CameraControlLog) << "startVideo()"; |
|
|
|
if(!_resetting) { |
|
|
|
//-- Check if camera can capture videos or if it can capture it while in Photo Mode
|
|
|
|
qCDebug(CameraControlLog) << "startVideo()"; |
|
|
|
if(!capturesVideo() || (cameraMode() == CAM_MODE_PHOTO && !videoInPhotoMode())) { |
|
|
|
//-- Check if camera can capture videos or if it can capture it while in Photo Mode
|
|
|
|
return false; |
|
|
|
if(!capturesVideo() || (cameraMode() == CAM_MODE_PHOTO && !videoInPhotoMode())) { |
|
|
|
} |
|
|
|
return false; |
|
|
|
if(videoStatus() != VIDEO_CAPTURE_STATUS_RUNNING) { |
|
|
|
} |
|
|
|
_vehicle->sendMavCommand( |
|
|
|
if(videoStatus() != VIDEO_CAPTURE_STATUS_RUNNING) { |
|
|
|
_compID, // Target component
|
|
|
|
_vehicle->sendMavCommand( |
|
|
|
MAV_CMD_VIDEO_START_CAPTURE, // Command id
|
|
|
|
_compID, // Target component
|
|
|
|
true, // ShowError
|
|
|
|
MAV_CMD_VIDEO_START_CAPTURE, // Command id
|
|
|
|
0, // Reserved (Set to 0)
|
|
|
|
true, // ShowError
|
|
|
|
0); // CAMERA_CAPTURE_STATUS Frequency
|
|
|
|
0, // Reserved (Set to 0)
|
|
|
|
return true; |
|
|
|
0); // CAMERA_CAPTURE_STATUS Frequency
|
|
|
|
|
|
|
|
return true; |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
return false; |
|
|
|
return false; |
|
|
|
} |
|
|
|
} |
|
|
@ -397,14 +413,16 @@ QGCCameraControl::startVideo() |
|
|
|
bool |
|
|
|
bool |
|
|
|
QGCCameraControl::stopVideo() |
|
|
|
QGCCameraControl::stopVideo() |
|
|
|
{ |
|
|
|
{ |
|
|
|
qCDebug(CameraControlLog) << "stopVideo()"; |
|
|
|
if(!_resetting) { |
|
|
|
if(videoStatus() == VIDEO_CAPTURE_STATUS_RUNNING) { |
|
|
|
qCDebug(CameraControlLog) << "stopVideo()"; |
|
|
|
_vehicle->sendMavCommand( |
|
|
|
if(videoStatus() == VIDEO_CAPTURE_STATUS_RUNNING) { |
|
|
|
_compID, // Target component
|
|
|
|
_vehicle->sendMavCommand( |
|
|
|
MAV_CMD_VIDEO_STOP_CAPTURE, // Command id
|
|
|
|
_compID, // Target component
|
|
|
|
true, // ShowError
|
|
|
|
MAV_CMD_VIDEO_STOP_CAPTURE, // Command id
|
|
|
|
0); // Reserved (Set to 0)
|
|
|
|
true, // ShowError
|
|
|
|
return true; |
|
|
|
0); // Reserved (Set to 0)
|
|
|
|
|
|
|
|
return true; |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
return false; |
|
|
|
return false; |
|
|
|
} |
|
|
|
} |
|
|
@ -413,16 +431,18 @@ QGCCameraControl::stopVideo() |
|
|
|
void |
|
|
|
void |
|
|
|
QGCCameraControl::setVideoMode() |
|
|
|
QGCCameraControl::setVideoMode() |
|
|
|
{ |
|
|
|
{ |
|
|
|
if(hasModes() && _cameraMode != CAM_MODE_VIDEO) { |
|
|
|
if(!_resetting) { |
|
|
|
qCDebug(CameraControlLog) << "setVideoMode()"; |
|
|
|
if(hasModes() && _cameraMode != CAM_MODE_VIDEO) { |
|
|
|
//-- Use basic MAVLink message
|
|
|
|
qCDebug(CameraControlLog) << "setVideoMode()"; |
|
|
|
_vehicle->sendMavCommand( |
|
|
|
//-- Use basic MAVLink message
|
|
|
|
_compID, // Target component
|
|
|
|
_vehicle->sendMavCommand( |
|
|
|
MAV_CMD_SET_CAMERA_MODE, // Command id
|
|
|
|
_compID, // Target component
|
|
|
|
true, // ShowError
|
|
|
|
MAV_CMD_SET_CAMERA_MODE, // Command id
|
|
|
|
0, // Reserved (Set to 0)
|
|
|
|
true, // ShowError
|
|
|
|
CAM_MODE_VIDEO); // Camera mode (0: photo, 1: video)
|
|
|
|
0, // Reserved (Set to 0)
|
|
|
|
_setCameraMode(CAM_MODE_VIDEO); |
|
|
|
CAM_MODE_VIDEO); // Camera mode (0: photo, 1: video)
|
|
|
|
|
|
|
|
_setCameraMode(CAM_MODE_VIDEO); |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
@ -430,16 +450,18 @@ QGCCameraControl::setVideoMode() |
|
|
|
void |
|
|
|
void |
|
|
|
QGCCameraControl::setPhotoMode() |
|
|
|
QGCCameraControl::setPhotoMode() |
|
|
|
{ |
|
|
|
{ |
|
|
|
if(hasModes() && _cameraMode != CAM_MODE_PHOTO) { |
|
|
|
if(!_resetting) { |
|
|
|
qCDebug(CameraControlLog) << "setPhotoMode()"; |
|
|
|
if(hasModes() && _cameraMode != CAM_MODE_PHOTO) { |
|
|
|
//-- Use basic MAVLink message
|
|
|
|
qCDebug(CameraControlLog) << "setPhotoMode()"; |
|
|
|
_vehicle->sendMavCommand( |
|
|
|
//-- Use basic MAVLink message
|
|
|
|
_compID, // Target component
|
|
|
|
_vehicle->sendMavCommand( |
|
|
|
MAV_CMD_SET_CAMERA_MODE, // Command id
|
|
|
|
_compID, // Target component
|
|
|
|
true, // ShowError
|
|
|
|
MAV_CMD_SET_CAMERA_MODE, // Command id
|
|
|
|
0, // Reserved (Set to 0)
|
|
|
|
true, // ShowError
|
|
|
|
CAM_MODE_PHOTO); // Camera mode (0: photo, 1: video)
|
|
|
|
0, // Reserved (Set to 0)
|
|
|
|
_setCameraMode(CAM_MODE_PHOTO); |
|
|
|
CAM_MODE_PHOTO); // Camera mode (0: photo, 1: video)
|
|
|
|
|
|
|
|
_setCameraMode(CAM_MODE_PHOTO); |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
@ -447,26 +469,31 @@ QGCCameraControl::setPhotoMode() |
|
|
|
void |
|
|
|
void |
|
|
|
QGCCameraControl::resetSettings() |
|
|
|
QGCCameraControl::resetSettings() |
|
|
|
{ |
|
|
|
{ |
|
|
|
qCDebug(CameraControlLog) << "resetSettings()"; |
|
|
|
if(!_resetting) { |
|
|
|
_vehicle->sendMavCommand( |
|
|
|
qCDebug(CameraControlLog) << "resetSettings()"; |
|
|
|
_compID, // Target component
|
|
|
|
_resetting = true; |
|
|
|
MAV_CMD_RESET_CAMERA_SETTINGS, // Command id
|
|
|
|
_vehicle->sendMavCommand( |
|
|
|
true, // ShowError
|
|
|
|
_compID, // Target component
|
|
|
|
1); // Do Reset
|
|
|
|
MAV_CMD_RESET_CAMERA_SETTINGS, // Command id
|
|
|
|
|
|
|
|
true, // ShowError
|
|
|
|
|
|
|
|
1); // Do Reset
|
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
//-----------------------------------------------------------------------------
|
|
|
|
//-----------------------------------------------------------------------------
|
|
|
|
void |
|
|
|
void |
|
|
|
QGCCameraControl::formatCard(int id) |
|
|
|
QGCCameraControl::formatCard(int id) |
|
|
|
{ |
|
|
|
{ |
|
|
|
qCDebug(CameraControlLog) << "formatCard()"; |
|
|
|
if(!_resetting) { |
|
|
|
if(_vehicle) { |
|
|
|
qCDebug(CameraControlLog) << "formatCard()"; |
|
|
|
_vehicle->sendMavCommand( |
|
|
|
if(_vehicle) { |
|
|
|
_compID, // Target component
|
|
|
|
_vehicle->sendMavCommand( |
|
|
|
MAV_CMD_STORAGE_FORMAT, // Command id
|
|
|
|
_compID, // Target component
|
|
|
|
true, // ShowError
|
|
|
|
MAV_CMD_STORAGE_FORMAT, // Command id
|
|
|
|
id, // Storage ID (1 for first, 2 for second, etc.)
|
|
|
|
true, // ShowError
|
|
|
|
1); // Do Format
|
|
|
|
id, // Storage ID (1 for first, 2 for second, etc.)
|
|
|
|
|
|
|
|
1); // Do Format
|
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
@ -504,6 +531,7 @@ QGCCameraControl::_mavCommandResult(int vehicleId, int component, int command, i |
|
|
|
}else if(!noReponseFromVehicle && result == MAV_RESULT_ACCEPTED) { |
|
|
|
}else if(!noReponseFromVehicle && result == MAV_RESULT_ACCEPTED) { |
|
|
|
switch(command) { |
|
|
|
switch(command) { |
|
|
|
case MAV_CMD_RESET_CAMERA_SETTINGS: |
|
|
|
case MAV_CMD_RESET_CAMERA_SETTINGS: |
|
|
|
|
|
|
|
_resetting = false; |
|
|
|
if(isBasic()) { |
|
|
|
if(isBasic()) { |
|
|
|
_requestCameraSettings(); |
|
|
|
_requestCameraSettings(); |
|
|
|
} else { |
|
|
|
} else { |
|
|
|