From abe04db372635d2f3b453416da7624bdae1a329b Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 21 Aug 2019 15:19:06 +0900 Subject: [PATCH] Rover: RC_Channel uses sailboat::set_motor_state --- APMrover2/RC_Channel.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/APMrover2/RC_Channel.cpp b/APMrover2/RC_Channel.cpp index 44d13660ca..7594cbbd43 100644 --- a/APMrover2/RC_Channel.cpp +++ b/APMrover2/RC_Channel.cpp @@ -103,13 +103,13 @@ void RC_Channel_Rover::do_aux_function_sailboat_motor_3pos(const aux_switch_pos_ { switch(ch_flag) { case HIGH: - rover.g2.sailboat.throttle_state = rover.g2.sailboat.Sailboat_Throttle::FORCE_MOTOR; + rover.g2.sailboat.set_motor_state(Sailboat::UseMotor::USE_MOTOR_ALWAYS); break; case MIDDLE: - rover.g2.sailboat.throttle_state = rover.g2.sailboat.Sailboat_Throttle::ASSIST; + rover.g2.sailboat.set_motor_state(Sailboat::UseMotor::USE_MOTOR_ASSIST); break; case LOW: - rover.g2.sailboat.throttle_state = rover.g2.sailboat.Sailboat_Throttle::NEVER; + rover.g2.sailboat.set_motor_state(Sailboat::UseMotor::USE_MOTOR_NEVER); break; } }