mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
TradHeli: Initialize Rate FF filters.
This commit is contained in:
parent
26be7aed97
commit
7ef4c11c92
@ -16,6 +16,7 @@ static int8_t heli_dynamic_flight_counter;
|
|||||||
// heli_init - perform any special initialisation required for the tradheli
|
// heli_init - perform any special initialisation required for the tradheli
|
||||||
static void heli_init()
|
static void heli_init()
|
||||||
{
|
{
|
||||||
|
attitude_control.update_feedforward_filter_rates(MAIN_LOOP_SECONDS);
|
||||||
}
|
}
|
||||||
|
|
||||||
// get_pilot_desired_collective - converts pilot input (from 0 ~ 1000) to a value that can be fed into the g.rc_3.servo_out function
|
// get_pilot_desired_collective - converts pilot input (from 0 ~ 1000) to a value that can be fed into the g.rc_3.servo_out function
|
||||||
|
Loading…
Reference in New Issue
Block a user