From 5a8a3963d49fbfc135fa1c6474767eb8c0b736d4 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 23 Oct 2018 17:25:52 +1100 Subject: [PATCH] Sub: move servorelayevents mission handling into AP_Mission --- ArduSub/commands_logic.cpp | 22 ---------------------- 1 file changed, 22 deletions(-) diff --git a/ArduSub/commands_logic.cpp b/ArduSub/commands_logic.cpp index 60391bdc81..d8f1514d16 100644 --- a/ArduSub/commands_logic.cpp +++ b/ArduSub/commands_logic.cpp @@ -95,24 +95,6 @@ bool Sub::start_command(const AP_Mission::Mission_Command& cmd) do_set_home(cmd); break; - case MAV_CMD_DO_SET_SERVO: - ServoRelayEvents.do_set_servo(cmd.content.servo.channel, cmd.content.servo.pwm); - break; - - case MAV_CMD_DO_SET_RELAY: - ServoRelayEvents.do_set_relay(cmd.content.relay.num, cmd.content.relay.state); - break; - - case MAV_CMD_DO_REPEAT_SERVO: - ServoRelayEvents.do_repeat_servo(cmd.content.repeat_servo.channel, cmd.content.repeat_servo.pwm, - cmd.content.repeat_servo.repeat_count, cmd.content.repeat_servo.cycle_time * 1000.0f); - break; - - case MAV_CMD_DO_REPEAT_RELAY: - ServoRelayEvents.do_repeat_relay(cmd.content.repeat_relay.num, cmd.content.repeat_relay.repeat_count, - cmd.content.repeat_relay.cycle_time * 1000.0f); - break; - case MAV_CMD_DO_SET_ROI: // 201 // point the vehicle and camera at a region of interest (ROI) do_roi(cmd); @@ -228,10 +210,6 @@ bool Sub::verify_command(const AP_Mission::Mission_Command& cmd) // do commands (always return true) case MAV_CMD_DO_CHANGE_SPEED: case MAV_CMD_DO_SET_HOME: - case MAV_CMD_DO_SET_SERVO: - case MAV_CMD_DO_SET_RELAY: - case MAV_CMD_DO_REPEAT_SERVO: - case MAV_CMD_DO_REPEAT_RELAY: case MAV_CMD_DO_SET_ROI: case MAV_CMD_DO_MOUNT_CONTROL: case MAV_CMD_DO_CONTROL_VIDEO: