mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
AP_Motors: set_throttle takes a float
This commit is contained in:
parent
ab2532a609
commit
a07b322d31
@ -121,7 +121,7 @@ public:
|
||||
void set_roll(int16_t roll_in) { _rc_roll.servo_out = roll_in; }; // range -4500 ~ 4500
|
||||
void set_pitch(int16_t pitch_in) { _rc_pitch.servo_out = pitch_in; }; // range -4500 ~ 4500
|
||||
void set_yaw(int16_t yaw_in) { _rc_yaw.servo_out = yaw_in; }; // range -4500 ~ 4500
|
||||
void set_throttle(int16_t throttle_in) { _throttle_in = throttle_in; }; // range 0 ~ 1000
|
||||
void set_throttle(float throttle_in) { _throttle_in = throttle_in; }; // range 0 ~ 1000
|
||||
void set_stabilizing(bool stabilizing) { _flags.stabilizing = stabilizing; }
|
||||
|
||||
// accessors for roll, pitch, yaw and throttle inputs to motors
|
||||
|
Loading…
Reference in New Issue
Block a user