mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: set_throttle accepts 0 to 1 range
This commit is contained in:
parent
3c74b4cc69
commit
666a92ae2f
|
@ -62,7 +62,7 @@ public:
|
||||||
void set_roll(int16_t roll_in) { _roll_control_input = roll_in; }; // range -4500 ~ 4500
|
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_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_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; }
|
void set_stabilizing(bool stabilizing) { _flags.stabilizing = stabilizing; }
|
||||||
|
|
||||||
// accessors for roll, pitch, yaw and throttle inputs to motors
|
// accessors for roll, pitch, yaw and throttle inputs to motors
|
||||||
|
|
Loading…
Reference in New Issue