AP_Mission: add MAV_CMD_START_CAPTURE support in mission

This commit is contained in:
Asif Khan 2023-09-07 15:35:40 +05:30 committed by Peter Barker
parent 2cc080620c
commit 518feedf41
3 changed files with 28 additions and 2 deletions

View File

@ -1312,6 +1312,7 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_
break;
case MAV_CMD_IMAGE_START_CAPTURE:
cmd.content.image_start_capture.instance = packet.param1;
cmd.content.image_start_capture.interval_s = packet.param2;
cmd.content.image_start_capture.total_num_images = packet.param3;
cmd.content.image_start_capture.start_seq_number = packet.param4;
@ -1807,6 +1808,7 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c
break;
case MAV_CMD_IMAGE_START_CAPTURE:
packet.param1 = cmd.content.image_start_capture.instance;
packet.param2 = cmd.content.image_start_capture.interval_s;
packet.param3 = cmd.content.image_start_capture.total_num_images;
packet.param4 = cmd.content.image_start_capture.start_seq_number;

View File

@ -269,6 +269,7 @@ public:
// MAV_CMD_IMAGE_START_CAPTURE support
struct PACKED image_start_capture_Command {
uint8_t instance;
float interval_s;
uint16_t total_num_images;
uint16_t start_seq_number;

View File

@ -163,8 +163,31 @@ bool AP_Mission::start_command_camera(const AP_Mission::Mission_Command& cmd)
return false;
case MAV_CMD_IMAGE_START_CAPTURE:
camera->take_picture();
return true;
// check if this is a single picture request
if (cmd.content.image_start_capture.total_num_images == 1) {
if (cmd.content.image_start_capture.instance == 0) {
// take pictures for every backend
camera->take_picture();
return true;
}
return camera->take_picture(cmd.content.image_start_capture.instance-1);
} else if (cmd.content.image_start_capture.total_num_images == 0) {
// multiple picture request, take pictures forever
if (cmd.content.image_start_capture.instance == 0) {
// take pictures for every backend
camera->take_multiple_pictures(cmd.content.image_start_capture.interval_s*1000, -1);
return true;
}
return camera->take_multiple_pictures(cmd.content.image_start_capture.instance-1, cmd.content.image_start_capture.interval_s*1000, -1);
} else {
if (cmd.content.image_start_capture.instance == 0) {
// take pictures for every backend
camera->take_multiple_pictures(cmd.content.image_start_capture.interval_s*1000, cmd.content.image_start_capture.total_num_images);
return true;
}
return camera->take_multiple_pictures(cmd.content.image_start_capture.instance-1, cmd.content.image_start_capture.interval_s*1000, cmd.content.image_start_capture.total_num_images);
}
return false;
case MAV_CMD_VIDEO_START_CAPTURE:
case MAV_CMD_VIDEO_STOP_CAPTURE: