Browse Source

Making sure the commands are sent to the camera's actual component ID rather than a hardcoded constant.

QGC4.4
Gus Grubba 7 years ago
parent
commit
59d00bb1f9
  1. 2
      libs/mavlink/include/mavlink/v2.0
  2. 10
      src/Camera/QGCCameraControl.cc

2
libs/mavlink/include/mavlink/v2.0

@ -1 +1 @@ @@ -1 +1 @@
Subproject commit 653ac745a57794a38c831f1ff296066a2e09c09b
Subproject commit 033fa8e7a4a75a0c3f17cea57e3be8966e05f770

10
src/Camera/QGCCameraControl.cc

@ -311,7 +311,7 @@ QGCCameraControl::takePhoto() @@ -311,7 +311,7 @@ QGCCameraControl::takePhoto()
}
if(capturesPhotos()) {
_vehicle->sendMavCommand(
MAV_COMP_ID_CAMERA, // Target component
_compID, // Target component
MAV_CMD_IMAGE_START_CAPTURE, // Command id
false, // ShowError
0, // Reserved (Set to 0)
@ -339,7 +339,7 @@ QGCCameraControl::stopTakePhoto() @@ -339,7 +339,7 @@ QGCCameraControl::stopTakePhoto()
}
if(capturesPhotos()) {
_vehicle->sendMavCommand(
MAV_COMP_ID_CAMERA, // Target component
_compID, // Target component
MAV_CMD_IMAGE_STOP_CAPTURE, // Command id
false, // ShowError
0); // Reserved (Set to 0)
@ -361,7 +361,7 @@ QGCCameraControl::startVideo() @@ -361,7 +361,7 @@ QGCCameraControl::startVideo()
}
if(videoStatus() != VIDEO_CAPTURE_STATUS_RUNNING) {
_vehicle->sendMavCommand(
MAV_COMP_ID_CAMERA, // Target component
_compID, // Target component
MAV_CMD_VIDEO_START_CAPTURE, // Command id
true, // ShowError
0, // Reserved (Set to 0)
@ -378,7 +378,7 @@ QGCCameraControl::stopVideo() @@ -378,7 +378,7 @@ QGCCameraControl::stopVideo()
qCDebug(CameraControlLog) << "stopVideo()";
if(videoStatus() == VIDEO_CAPTURE_STATUS_RUNNING) {
_vehicle->sendMavCommand(
MAV_COMP_ID_CAMERA, // Target component
_compID, // Target component
MAV_CMD_VIDEO_STOP_CAPTURE, // Command id
true, // ShowError
0); // Reserved (Set to 0)
@ -399,7 +399,7 @@ QGCCameraControl::setVideoMode() @@ -399,7 +399,7 @@ QGCCameraControl::setVideoMode()
MAV_CMD_SET_CAMERA_MODE, // Command id
true, // ShowError
0, // Reserved (Set to 0)
CAM_MODE_VIDEO); // Camera mode (0: photo, 1: video)
CAM_MODE_VIDEO); // Camera mode (0: photo, 1: video)
_setCameraMode(CAM_MODE_VIDEO);
}
}

Loading…
Cancel
Save