APMrover2: log a picture if AP_Camera::control() returns true

This commit is contained in:
Andrew Tridgell 2016-01-29 09:32:15 +11:00
parent dc998a2eaf
commit 39b9ae7e91
2 changed files with 16 additions and 14 deletions

View File

@ -934,13 +934,14 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;
case MAV_CMD_DO_DIGICAM_CONTROL:
rover.camera.control(packet.param1,
packet.param2,
packet.param3,
packet.param4,
packet.param5,
packet.param6);
if (rover.camera.control(packet.param1,
packet.param2,
packet.param3,
packet.param4,
packet.param5,
packet.param6)) {
rover.log_picture();
}
result = MAV_RESULT_ACCEPTED;
break;
#endif // CAMERA == ENABLED

View File

@ -348,13 +348,14 @@ void Rover::do_digicam_configure(const AP_Mission::Mission_Command& cmd)
void Rover::do_digicam_control(const AP_Mission::Mission_Command& cmd)
{
#if CAMERA == ENABLED
camera.control(cmd.content.digicam_control.session,
cmd.content.digicam_control.zoom_pos,
cmd.content.digicam_control.zoom_step,
cmd.content.digicam_control.focus_lock,
cmd.content.digicam_control.shooting_cmd,
cmd.content.digicam_control.cmd_id);
log_picture();
if (camera.control(cmd.content.digicam_control.session,
cmd.content.digicam_control.zoom_pos,
cmd.content.digicam_control.zoom_step,
cmd.content.digicam_control.focus_lock,
cmd.content.digicam_control.shooting_cmd,
cmd.content.digicam_control.cmd_id)) {
log_picture();
}
#endif
}