AP_Mission: support set-camera-source

This commit is contained in:
Randy Mackay 2024-02-08 17:30:08 +09:00
parent a6a5cde34c
commit 3a570943d5
3 changed files with 39 additions and 0 deletions

View File

@ -387,6 +387,7 @@ bool AP_Mission::verify_command(const Mission_Command& cmd)
case MAV_CMD_IMAGE_STOP_CAPTURE: case MAV_CMD_IMAGE_STOP_CAPTURE:
case MAV_CMD_SET_CAMERA_ZOOM: case MAV_CMD_SET_CAMERA_ZOOM:
case MAV_CMD_SET_CAMERA_FOCUS: case MAV_CMD_SET_CAMERA_FOCUS:
case MAV_CMD_SET_CAMERA_SOURCE:
case MAV_CMD_VIDEO_START_CAPTURE: case MAV_CMD_VIDEO_START_CAPTURE:
case MAV_CMD_VIDEO_STOP_CAPTURE: case MAV_CMD_VIDEO_STOP_CAPTURE:
return true; return true;
@ -434,6 +435,7 @@ bool AP_Mission::start_command(const Mission_Command& cmd)
case MAV_CMD_IMAGE_STOP_CAPTURE: case MAV_CMD_IMAGE_STOP_CAPTURE:
case MAV_CMD_SET_CAMERA_ZOOM: case MAV_CMD_SET_CAMERA_ZOOM:
case MAV_CMD_SET_CAMERA_FOCUS: case MAV_CMD_SET_CAMERA_FOCUS:
case MAV_CMD_SET_CAMERA_SOURCE:
case MAV_CMD_VIDEO_START_CAPTURE: case MAV_CMD_VIDEO_START_CAPTURE:
case MAV_CMD_VIDEO_STOP_CAPTURE: case MAV_CMD_VIDEO_STOP_CAPTURE:
return start_command_camera(cmd); return start_command_camera(cmd);
@ -1357,6 +1359,12 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_
cmd.content.set_camera_focus.focus_value = packet.param2; cmd.content.set_camera_focus.focus_value = packet.param2;
break; break;
case MAV_CMD_SET_CAMERA_SOURCE:
cmd.content.set_camera_source.instance = packet.param1;
cmd.content.set_camera_source.primary_source = packet.param2;
cmd.content.set_camera_source.secondary_source = packet.param3;
break;
case MAV_CMD_VIDEO_START_CAPTURE: case MAV_CMD_VIDEO_START_CAPTURE:
cmd.content.video_start_capture.video_stream_id = packet.param1; cmd.content.video_start_capture.video_stream_id = packet.param1;
break; break;
@ -1865,6 +1873,12 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c
packet.param2 = cmd.content.set_camera_focus.focus_value; packet.param2 = cmd.content.set_camera_focus.focus_value;
break; break;
case MAV_CMD_SET_CAMERA_SOURCE:
packet.param1 = cmd.content.set_camera_source.instance;
packet.param2 = cmd.content.set_camera_source.primary_source;
packet.param3 = cmd.content.set_camera_source.secondary_source;
break;
case MAV_CMD_VIDEO_START_CAPTURE: case MAV_CMD_VIDEO_START_CAPTURE:
packet.param1 = cmd.content.video_start_capture.video_stream_id; packet.param1 = cmd.content.video_start_capture.video_stream_id;
break; break;
@ -2686,6 +2700,8 @@ const char *AP_Mission::Mission_Command::type() const
return "SetCameraZoom"; return "SetCameraZoom";
case MAV_CMD_SET_CAMERA_FOCUS: case MAV_CMD_SET_CAMERA_FOCUS:
return "SetCameraFocus"; return "SetCameraFocus";
case MAV_CMD_SET_CAMERA_SOURCE:
return "SetCameraSource";
case MAV_CMD_VIDEO_START_CAPTURE: case MAV_CMD_VIDEO_START_CAPTURE:
return "VideoStartCapture"; return "VideoStartCapture";
case MAV_CMD_VIDEO_STOP_CAPTURE: case MAV_CMD_VIDEO_STOP_CAPTURE:

View File

@ -288,6 +288,13 @@ public:
float focus_value; float focus_value;
}; };
// MAV_CMD_SET_CAMERA_SOURCE support
struct PACKED set_camera_source_Command {
uint8_t instance;
uint8_t primary_source;
uint8_t secondary_source;
};
// MAV_CMD_VIDEO_START_CAPTURE support // MAV_CMD_VIDEO_START_CAPTURE support
struct PACKED video_start_capture_Command { struct PACKED video_start_capture_Command {
uint8_t video_stream_id; uint8_t video_stream_id;
@ -388,6 +395,9 @@ public:
// MAV_CMD_SET_CAMERA_FOCUS support // MAV_CMD_SET_CAMERA_FOCUS support
set_camera_focus_Command set_camera_focus; set_camera_focus_Command set_camera_focus;
// MAV_CMD_SET_CAMEARA_SOURCE support
set_camera_source_Command set_camera_source;
// MAV_CMD_VIDEO_START_CAPTURE support // MAV_CMD_VIDEO_START_CAPTURE support
video_start_capture_Command video_start_capture; video_start_capture_Command video_start_capture;

View File

@ -165,6 +165,19 @@ bool AP_Mission::start_command_camera(const AP_Mission::Mission_Command& cmd)
} }
return false; return false;
#if AP_CAMERA_SET_CAMERA_SOURCE_ENABLED
case MAV_CMD_SET_CAMERA_SOURCE:
if (cmd.content.set_camera_source.instance == 0) {
// set lens for every backend
bool ret = false;
for (uint8_t i=0; i<AP_CAMERA_MAX_INSTANCES; i++) {
ret |= camera->set_camera_source(i, (AP_Camera::CameraSource)cmd.content.set_camera_source.primary_source, (AP_Camera::CameraSource)cmd.content.set_camera_source.secondary_source);
}
return ret;
}
return camera->set_camera_source(cmd.content.set_camera_source.instance-1, (AP_Camera::CameraSource)cmd.content.set_camera_source.primary_source, (AP_Camera::CameraSource)cmd.content.set_camera_source.secondary_source);
#endif
case MAV_CMD_IMAGE_START_CAPTURE: case MAV_CMD_IMAGE_START_CAPTURE:
// check if this is a single picture request (e.g. total images is 1 or interval and total images are zero) // check if this is a single picture request (e.g. total images is 1 or interval and total images are zero)
if ((cmd.content.image_start_capture.total_num_images == 1) || if ((cmd.content.image_start_capture.total_num_images == 1) ||