diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 93dc2693c3..a49985c015 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -653,10 +653,6 @@ private: void do_set_home(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); -#if CAMERA == ENABLED - void do_digicam_configure(const AP_Mission::Mission_Command& cmd); - void do_digicam_control(const AP_Mission::Mission_Command& cmd); -#endif bool verify_nav_wp(const AP_Mission::Mission_Command& cmd); bool verify_surface(const AP_Mission::Mission_Command& cmd); diff --git a/ArduSub/commands_logic.cpp b/ArduSub/commands_logic.cpp index d8f1514d16..343aa58481 100644 --- a/ArduSub/commands_logic.cpp +++ b/ArduSub/commands_logic.cpp @@ -105,23 +105,6 @@ bool Sub::start_command(const AP_Mission::Mission_Command& cmd) do_mount_control(cmd); 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: - camera.set_trigger_distance(cmd.content.cam_trigg_dist.meters); - break; -#endif - #if NAV_GUIDED == ENABLED case MAV_CMD_DO_GUIDED_LIMITS: // 222 accept guided mode limits do_guided_limits(cmd); @@ -213,8 +196,6 @@ bool Sub::verify_command(const AP_Mission::Mission_Command& cmd) case MAV_CMD_DO_SET_ROI: 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_GUIDED_LIMITS: return true; @@ -805,32 +786,6 @@ void Sub::do_roi(const AP_Mission::Mission_Command& cmd) set_auto_yaw_roi(cmd.content.location); } -#if CAMERA == ENABLED -// do_digicam_configure Send Digicam Configure message with the camera library -void Sub::do_digicam_configure(const AP_Mission::Mission_Command& 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); -} - -// do_digicam_control Send Digicam Control message with the camera library -void Sub::do_digicam_control(const AP_Mission::Mission_Command& 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); -} - -#endif - // point the camera to a specified angle void Sub::do_mount_control(const AP_Mission::Mission_Command& cmd) {