Copter: let AP_Mission handle common camera commands

This commit is contained in:
Peter Barker 2018-10-23 18:04:07 +11:00 committed by Peter Barker
parent b1b5a7868d
commit a339d77f08
2 changed files with 0 additions and 53 deletions

View File

@ -371,10 +371,6 @@ private:
void do_set_home(const AP_Mission::Mission_Command& cmd); void do_set_home(const AP_Mission::Mission_Command& cmd);
void do_roi(const AP_Mission::Mission_Command& cmd); void do_roi(const AP_Mission::Mission_Command& cmd);
void do_mount_control(const AP_Mission::Mission_Command& cmd); void do_mount_control(const AP_Mission::Mission_Command& cmd);
#if CAMERA == ENABLED
void do_digicam_configure(const AP_Mission::Mission_Command& cmd);
void do_digicam_control(const AP_Mission::Mission_Command& cmd);
#endif
#if PARACHUTE == ENABLED #if PARACHUTE == ENABLED
void do_parachute(const AP_Mission::Mission_Command& cmd); void do_parachute(const AP_Mission::Mission_Command& cmd);
#endif #endif

View File

@ -478,23 +478,6 @@ bool Copter::ModeAuto::start_command(const AP_Mission::Mission_Command& cmd)
#endif //AC_FENCE == ENABLED #endif //AC_FENCE == ENABLED
break; break;
#if CAMERA == ENABLED
case MAV_CMD_DO_CONTROL_VIDEO: // Control on-board camera capturing. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty|
break;
case MAV_CMD_DO_DIGICAM_CONFIGURE: // Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)|
do_digicam_configure(cmd);
break;
case MAV_CMD_DO_DIGICAM_CONTROL: // Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty|
do_digicam_control(cmd);
break;
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
copter.camera.set_trigger_distance(cmd.content.cam_trigg_dist.meters);
break;
#endif
#if PARACHUTE == ENABLED #if PARACHUTE == ENABLED
case MAV_CMD_DO_PARACHUTE: // Mission command to configure or release parachute case MAV_CMD_DO_PARACHUTE: // Mission command to configure or release parachute
do_parachute(cmd); do_parachute(cmd);
@ -681,10 +664,6 @@ bool Copter::ModeAuto::verify_command(const AP_Mission::Mission_Command& cmd)
case MAV_CMD_DO_SET_HOME: case MAV_CMD_DO_SET_HOME:
case MAV_CMD_DO_SET_ROI: case MAV_CMD_DO_SET_ROI:
case MAV_CMD_DO_MOUNT_CONTROL: case MAV_CMD_DO_MOUNT_CONTROL:
case MAV_CMD_DO_CONTROL_VIDEO:
case MAV_CMD_DO_DIGICAM_CONFIGURE:
case MAV_CMD_DO_DIGICAM_CONTROL:
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
case MAV_CMD_DO_PARACHUTE: // assume parachute was released successfully case MAV_CMD_DO_PARACHUTE: // assume parachute was released successfully
case MAV_CMD_DO_GUIDED_LIMITS: case MAV_CMD_DO_GUIDED_LIMITS:
case MAV_CMD_DO_FENCE_ENABLE: case MAV_CMD_DO_FENCE_ENABLE:
@ -1301,34 +1280,6 @@ void Copter::ModeAuto::do_mount_control(const AP_Mission::Mission_Command& cmd)
#endif #endif
} }
#if CAMERA == ENABLED
// do_digicam_configure Send Digicam Configure message with the camera library
void Copter::ModeAuto::do_digicam_configure(const AP_Mission::Mission_Command& cmd)
{
copter.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);
}
// do_digicam_control Send Digicam Control message with the camera library
void Copter::ModeAuto::do_digicam_control(const AP_Mission::Mission_Command& cmd)
{
copter.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);
}
#endif
#if PARACHUTE == ENABLED #if PARACHUTE == ENABLED
// do_parachute - configure or release parachute // do_parachute - configure or release parachute
void Copter::ModeAuto::do_parachute(const AP_Mission::Mission_Command& cmd) void Copter::ModeAuto::do_parachute(const AP_Mission::Mission_Command& cmd)