ArduPlane: 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 5be21cc178
commit 8dba91658c
2 changed files with 16 additions and 14 deletions

View File

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

View File

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