mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
TradHeli: integrate init_targets rename to relax_bf_rate_controller
This commit is contained in:
parent
77d5d682c1
commit
75c328a752
@ -7,8 +7,7 @@
|
||||
// heli_acro_init - initialise acro controller
|
||||
static bool heli_acro_init(bool ignore_checks)
|
||||
{
|
||||
// clear stabilized rate errors
|
||||
attitude_control.init_targets();
|
||||
// always successfully enter acro
|
||||
return true;
|
||||
}
|
||||
|
||||
@ -22,7 +21,7 @@ static void heli_acro_run()
|
||||
// if not armed or main rotor not up to full speed clear stabilized rate errors
|
||||
// unlike multicopters we do not set throttle (i.e. collective pitch) to zero so the swash servos move
|
||||
if(!motors.armed() || !motors.motor_runup_complete()) {
|
||||
attitude_control.init_targets();
|
||||
attitude_control.relax_bf_rate_controller();
|
||||
}
|
||||
|
||||
// To-Do: add support for flybarred helis
|
||||
|
Loading…
Reference in New Issue
Block a user