mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 08:23:56 -04:00
AC_AttitudeControl: added get_throttle_mix()
and when we use set_throttle_mix_value(), set both desired and actual thanks to Leonard for the suggestions
This commit is contained in:
parent
8e3f8f47c8
commit
fe3e7e8153
@ -247,6 +247,7 @@ public:
|
||||
virtual void set_throttle_mix_man() {}
|
||||
virtual void set_throttle_mix_max() {}
|
||||
virtual void set_throttle_mix_value(float value) {}
|
||||
virtual float get_throttle_mix(void) const { return 0; }
|
||||
|
||||
// enable use of flybass passthrough on heli
|
||||
virtual void use_flybar_passthrough(bool passthrough, bool tail_passthrough) {}
|
||||
|
@ -66,7 +66,8 @@ public:
|
||||
void set_throttle_mix_min() override { _throttle_rpy_mix_desired = _thr_mix_min; }
|
||||
void set_throttle_mix_man() override { _throttle_rpy_mix_desired = _thr_mix_man; }
|
||||
void set_throttle_mix_max() override { _throttle_rpy_mix_desired = _thr_mix_max; }
|
||||
void set_throttle_mix_value(float value) override { _throttle_rpy_mix_desired = value; }
|
||||
void set_throttle_mix_value(float value) override { _throttle_rpy_mix_desired = _throttle_rpy_mix = value; }
|
||||
float get_throttle_mix(void) const override { return _throttle_rpy_mix; }
|
||||
|
||||
// are we producing min throttle?
|
||||
bool is_throttle_mix_min() const override { return (_throttle_rpy_mix < 1.25f*_thr_mix_min); }
|
||||
|
Loading…
Reference in New Issue
Block a user