mirror of https://github.com/ArduPilot/ardupilot
AP_MotorsHeli: add range checking to ext_gyro_gain
This commit is contained in:
parent
a5bdd12bfa
commit
928d7c7e71
|
@ -79,8 +79,8 @@ public:
|
|||
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
|
||||
uint16_t get_motor_mask() override;
|
||||
|
||||
// ext_gyro_gain - set external gyro gain in range 0 ~ 1
|
||||
void ext_gyro_gain(float gain) override { _ext_gyro_gain_std = gain * 1000.0f; }
|
||||
// ext_gyro_gain - set external gyro gain in range 0 ~ 1000
|
||||
void ext_gyro_gain(float gain) override { if (gain >= 0 && gain <= 1000) { _ext_gyro_gain_std = gain; }}
|
||||
|
||||
// has_flybar - returns true if we have a mechical flybar
|
||||
bool has_flybar() const override { return _flybar_mode; }
|
||||
|
|
Loading…
Reference in New Issue