|
|
|
@ -873,13 +873,14 @@ void Copter::do_digicam_configure(const AP_Mission::Mission_Command& cmd)
@@ -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 |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|