mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: log a picture if AP_Camera::control() returns true
This commit is contained in:
parent
39b9ae7e91
commit
5be21cc178
|
@ -1303,13 +1303,14 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
break;
|
||||
|
||||
case MAV_CMD_DO_DIGICAM_CONTROL:
|
||||
copter.camera.control(packet.param1,
|
||||
packet.param2,
|
||||
packet.param3,
|
||||
packet.param4,
|
||||
packet.param5,
|
||||
packet.param6);
|
||||
|
||||
if (copter.camera.control(packet.param1,
|
||||
packet.param2,
|
||||
packet.param3,
|
||||
packet.param4,
|
||||
packet.param5,
|
||||
packet.param6)) {
|
||||
copter.log_picture();
|
||||
}
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
break;
|
||||
#endif // CAMERA == ENABLED
|
||||
|
|
|
@ -873,13 +873,14 @@ void Copter::do_digicam_configure(const AP_Mission::Mission_Command& cmd)
|
|||
void Copter::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
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue