From 666a92ae2fcc9777d9fa5bb332ac556dd7e6d9ce Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Mon, 18 Jan 2016 13:22:10 +0900 Subject: [PATCH] AP_Motors: set_throttle accepts 0 to 1 range --- libraries/AP_Motors/AP_Motors_Class.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Motors/AP_Motors_Class.h b/libraries/AP_Motors/AP_Motors_Class.h index 5a85e76f9b..be138f2ad2 100644 --- a/libraries/AP_Motors/AP_Motors_Class.h +++ b/libraries/AP_Motors/AP_Motors_Class.h @@ -62,7 +62,7 @@ public: void set_roll(int16_t roll_in) { _roll_control_input = roll_in; }; // range -4500 ~ 4500 void set_pitch(int16_t pitch_in) { _pitch_control_input = pitch_in; }; // range -4500 ~ 4500 void set_yaw(int16_t yaw_in) { _yaw_control_input = yaw_in; }; // range -4500 ~ 4500 - void set_throttle(float throttle_in) { _throttle_in = constrain_float(throttle_in,-100.0f,1100.0f); }; // range 0 ~ 1000 + void set_throttle(float throttle_in) { _throttle_in = constrain_float(throttle_in,0.0f,1.0f); }; // range 0 ~ 1 void set_stabilizing(bool stabilizing) { _flags.stabilizing = stabilizing; } // accessors for roll, pitch, yaw and throttle inputs to motors