Copter: remove unused init_rate_controllers
This commit is contained in:
parent
6c5f2e6368
commit
43b0c4f0f4
@ -59,15 +59,6 @@ static void check_dynamic_flight(void)
|
||||
}
|
||||
}
|
||||
|
||||
// init_rate_controllers - set-up filters for rate controller inputs
|
||||
void init_rate_controllers()
|
||||
{
|
||||
// initalise low pass filters on rate controller inputs
|
||||
// 1st parameter is time_step, 2nd parameter is time_constant
|
||||
// rate_roll_filter.set_cutoff_frequency(0.01f, 0.1f);
|
||||
// rate_pitch_filter.set_cutoff_frequency(0.01f, 0.1f);
|
||||
}
|
||||
|
||||
// heli_integrated_swash_controller - convert desired roll and pitch rate to roll and pitch swash angles
|
||||
// should be called at 100hz
|
||||
// output placed directly into g.rc_1.servo_out and g.rc_2.servo_out
|
||||
|
@ -234,11 +234,6 @@ static void init_ardupilot()
|
||||
init_sonar();
|
||||
#endif
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// initialise controller filters
|
||||
init_rate_controllers();
|
||||
#endif // HELI_FRAME
|
||||
|
||||
// initialize commands
|
||||
// -------------------
|
||||
init_commands();
|
||||
|
Loading…
Reference in New Issue
Block a user