Browse Source

AP_Motors: remove constrain on throttle input

This constraint is redundant because we already constrain the filtered throttle
master
Randy Mackay 9 years ago
parent
commit
b4a61e6ccf
  1. 2
      libraries/AP_Motors/AP_Motors_Class.h

2
libraries/AP_Motors/AP_Motors_Class.h

@ -62,7 +62,7 @@ public: @@ -62,7 +62,7 @@ public:
void set_roll(float roll_in) { _roll_in = roll_in; }; // range -1 ~ +1
void set_pitch(float pitch_in) { _pitch_in = pitch_in; }; // range -1 ~ +1
void set_yaw(float yaw_in) { _yaw_in = yaw_in; }; // range -1 ~ +1
void set_throttle(float throttle_in) { _throttle_in = constrain_float(throttle_in,0.0f,1.0f); }; // range 0 ~ 1
void set_throttle(float throttle_in) { _throttle_in = throttle_in; }; // range 0 ~ 1
void set_throttle_filter_cutoff(float filt_hz) { _throttle_filter.set_cutoff_frequency(filt_hz); }
void set_stabilizing(bool stabilizing) { _flags.stabilizing = stabilizing; }

Loading…
Cancel
Save