mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
AP_Mission: add MAV_CMD_IMAGE_STOP_CAPTURE support
Co-authored-by: Zachary Zalass <zachzalass@gmail.com>
This commit is contained in:
parent
f30af5e072
commit
844d552b22
@ -378,6 +378,7 @@ bool AP_Mission::verify_command(const Mission_Command& cmd)
|
||||
case MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW:
|
||||
case MAV_CMD_JUMP_TAG:
|
||||
case MAV_CMD_IMAGE_START_CAPTURE:
|
||||
case MAV_CMD_IMAGE_STOP_CAPTURE:
|
||||
case MAV_CMD_SET_CAMERA_ZOOM:
|
||||
case MAV_CMD_SET_CAMERA_FOCUS:
|
||||
case MAV_CMD_VIDEO_START_CAPTURE:
|
||||
@ -422,6 +423,7 @@ bool AP_Mission::start_command(const Mission_Command& cmd)
|
||||
case MAV_CMD_DO_DIGICAM_CONTROL:
|
||||
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
|
||||
case MAV_CMD_IMAGE_START_CAPTURE:
|
||||
case MAV_CMD_IMAGE_STOP_CAPTURE:
|
||||
case MAV_CMD_SET_CAMERA_ZOOM:
|
||||
case MAV_CMD_SET_CAMERA_FOCUS:
|
||||
case MAV_CMD_VIDEO_START_CAPTURE:
|
||||
@ -1318,6 +1320,10 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_
|
||||
cmd.content.image_start_capture.start_seq_number = packet.param4;
|
||||
break;
|
||||
|
||||
case MAV_CMD_IMAGE_STOP_CAPTURE:
|
||||
cmd.p1 = packet.param1;
|
||||
break;
|
||||
|
||||
case MAV_CMD_SET_CAMERA_ZOOM:
|
||||
cmd.content.set_camera_zoom.zoom_type = packet.param1;
|
||||
cmd.content.set_camera_zoom.zoom_value = packet.param2;
|
||||
@ -1814,6 +1820,10 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c
|
||||
packet.param4 = cmd.content.image_start_capture.start_seq_number;
|
||||
break;
|
||||
|
||||
case MAV_CMD_IMAGE_STOP_CAPTURE:
|
||||
packet.param1 = cmd.p1;
|
||||
break;
|
||||
|
||||
case MAV_CMD_SET_CAMERA_ZOOM:
|
||||
packet.param1 = cmd.content.set_camera_zoom.zoom_type;
|
||||
packet.param2 = cmd.content.set_camera_zoom.zoom_value;
|
||||
@ -2637,6 +2647,8 @@ const char *AP_Mission::Mission_Command::type() const
|
||||
return "GimbalPitchYaw";
|
||||
case MAV_CMD_IMAGE_START_CAPTURE:
|
||||
return "ImageStartCapture";
|
||||
case MAV_CMD_IMAGE_STOP_CAPTURE:
|
||||
return "ImageStopCapture";
|
||||
case MAV_CMD_SET_CAMERA_ZOOM:
|
||||
return "SetCameraZoom";
|
||||
case MAV_CMD_SET_CAMERA_FOCUS:
|
||||
|
@ -189,6 +189,14 @@ bool AP_Mission::start_command_camera(const AP_Mission::Mission_Command& cmd)
|
||||
}
|
||||
return false;
|
||||
|
||||
case MAV_CMD_IMAGE_STOP_CAPTURE:
|
||||
if (cmd.p1 == 0) {
|
||||
// stop capture for each backend
|
||||
camera->stop_capture();
|
||||
return true;
|
||||
}
|
||||
return camera->stop_capture(cmd.p1);
|
||||
|
||||
case MAV_CMD_VIDEO_START_CAPTURE:
|
||||
case MAV_CMD_VIDEO_STOP_CAPTURE:
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user