mirror of https://github.com/ArduPilot/ardupilot
AP_Mission: start-image-capture with all zeros takes single pic
fails if no cameras configured
This commit is contained in:
parent
999a3fe8d9
commit
b08fa29574
|
@ -163,32 +163,28 @@ bool AP_Mission::start_command_camera(const AP_Mission::Mission_Command& cmd)
|
|||
return false;
|
||||
|
||||
case MAV_CMD_IMAGE_START_CAPTURE:
|
||||
// check if this is a single picture request
|
||||
if (cmd.content.image_start_capture.total_num_images == 1) {
|
||||
// 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) ||
|
||||
(cmd.content.image_start_capture.total_num_images == 0 && is_zero(cmd.content.image_start_capture.interval_s))) {
|
||||
if (cmd.content.image_start_capture.instance == 0) {
|
||||
// take pictures for every backend
|
||||
camera->take_picture();
|
||||
return true;
|
||||
return camera->take_picture();
|
||||
}
|
||||
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.interval_s*1000, -1);
|
||||
}
|
||||
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.interval_s*1000, cmd.content.image_start_capture.total_num_images);
|
||||
}
|
||||
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_IMAGE_STOP_CAPTURE:
|
||||
if (cmd.p1 == 0) {
|
||||
// stop capture for each backend
|
||||
|
|
Loading…
Reference in New Issue