diff --git a/APMrover2/AP_MotorsUGV.cpp b/APMrover2/AP_MotorsUGV.cpp index 3c09daf51f..b5ee5fb86e 100644 --- a/APMrover2/AP_MotorsUGV.cpp +++ b/APMrover2/AP_MotorsUGV.cpp @@ -342,7 +342,7 @@ void AP_MotorsUGV::output(bool armed, float ground_speed, float dt) output_custom_config(armed, _steering, _throttle, _lateral); // output to mainsail - output_mainsail(_mainsail); + output_mainsail(); // send values to the PWM timers for output SRV_Channels::calc_pwm(); @@ -777,13 +777,13 @@ void AP_MotorsUGV::output_throttle(SRV_Channel::Aux_servo_function_t function, f } // output for sailboat's mainsail -void AP_MotorsUGV::output_mainsail(float mainsail) +void AP_MotorsUGV::output_mainsail() { if (!has_sail()) { return; } - SRV_Channels::set_output_scaled(SRV_Channel::k_mainsail_sheet, constrain_float(mainsail, 0.0f, 100.0f)); + SRV_Channels::set_output_scaled(SRV_Channel::k_mainsail_sheet, _mainsail); } // slew limit throttle for one iteration diff --git a/APMrover2/AP_MotorsUGV.h b/APMrover2/AP_MotorsUGV.h index bf68e63e74..300249a1f9 100644 --- a/APMrover2/AP_MotorsUGV.h +++ b/APMrover2/AP_MotorsUGV.h @@ -137,7 +137,7 @@ protected: void output_throttle(SRV_Channel::Aux_servo_function_t function, float throttle, float dt = 0.0f); // output for sailboat's mainsail in the range of 0 to 100 - void output_mainsail(float mainsail); + void output_mainsail(); // slew limit throttle for one iteration void slew_limit_throttle(float dt);