mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_MotorsHeli: Overload update_throttle_filter()
Do not reset filter to zero when disarmed to allow collective pitch servo movement.
This commit is contained in:
parent
6299a8c90d
commit
d3ce68a8ca
@ -820,3 +820,12 @@ void AP_MotorsHeli::set_delta_phase_angle(int16_t angle)
|
||||
_delta_phase_angle = angle;
|
||||
calculate_roll_pitch_collective_factors();
|
||||
}
|
||||
|
||||
// update the throttle input filter
|
||||
void AP_MotorsHeli::update_throttle_filter()
|
||||
{
|
||||
_throttle_filter.apply(_throttle_in, 1.0f/_loop_rate);
|
||||
|
||||
// prevent _rc_throttle.servo_out from wrapping at int16 max or min
|
||||
_rc_throttle.servo_out = constrain_float(_throttle_filter.get(),-32000,32000);
|
||||
}
|
||||
|
@ -215,6 +215,9 @@ protected:
|
||||
void output_armed_zero_throttle();
|
||||
void output_disarmed();
|
||||
|
||||
// update the throttle input filter
|
||||
void update_throttle_filter();
|
||||
|
||||
private:
|
||||
|
||||
// heli_move_swash - moves swash plate to attitude of parameters passed in
|
||||
|
@ -223,7 +223,7 @@ protected:
|
||||
virtual void output_disarmed()=0;
|
||||
|
||||
// update the throttle input filter
|
||||
void update_throttle_filter();
|
||||
virtual void update_throttle_filter();
|
||||
|
||||
// update_max_throttle - updates the limits on _max_throttle for slow_start and current limiting flag
|
||||
void update_max_throttle();
|
||||
|
Loading…
Reference in New Issue
Block a user