|
|
|
@ -859,7 +859,13 @@ void Copter::do_roi(const AP_Mission::Mission_Command& cmd)
@@ -859,7 +859,13 @@ void Copter::do_roi(const AP_Mission::Mission_Command& cmd)
|
|
|
|
|
void Copter::do_digicam_configure(const AP_Mission::Mission_Command& cmd) |
|
|
|
|
{ |
|
|
|
|
#if CAMERA == ENABLED |
|
|
|
|
camera.configure_cmd(cmd); |
|
|
|
|
camera.configure(cmd.content.digicam_configure.shooting_mode, |
|
|
|
|
cmd.content.digicam_configure.shutter_speed, |
|
|
|
|
cmd.content.digicam_configure.aperture, |
|
|
|
|
cmd.content.digicam_configure.ISO, |
|
|
|
|
cmd.content.digicam_configure.exposure_type, |
|
|
|
|
cmd.content.digicam_configure.cmd_id, |
|
|
|
|
cmd.content.digicam_configure.engine_cutoff_time); |
|
|
|
|
#endif |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -867,7 +873,12 @@ void Copter::do_digicam_configure(const AP_Mission::Mission_Command& cmd)
@@ -867,7 +873,12 @@ 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(cmd); |
|
|
|
|
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 |
|
|
|
|
} |
|
|
|
|