diff --git a/libs/mavlink/include/mavlink/v2.0 b/libs/mavlink/include/mavlink/v2.0 index 653ac745a57794a38c831f1ff296066a2e09c09b..033fa8e7a4a75a0c3f17cea57e3be8966e05f770 160000 --- a/libs/mavlink/include/mavlink/v2.0 +++ b/libs/mavlink/include/mavlink/v2.0 @@ -1 +1 @@ -Subproject commit 653ac745a57794a38c831f1ff296066a2e09c09b +Subproject commit 033fa8e7a4a75a0c3f17cea57e3be8966e05f770 diff --git a/src/Camera/QGCCameraControl.cc b/src/Camera/QGCCameraControl.cc index ff11f7f6328f1377b94350fb078a91b29ebf216d..6c5374c71b680941c336d2d1ebc7cb7ea8d31ef6 100644 --- a/src/Camera/QGCCameraControl.cc +++ b/src/Camera/QGCCameraControl.cc @@ -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() } 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() } 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() 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() 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); } }