mirror of https://github.com/ArduPilot/ardupilot
Rover: update PID notch centers at 1Hz with average loop rate
This commit is contained in:
parent
d6287e90f1
commit
e327691540
|
@ -468,6 +468,7 @@ void Rover::one_second_loop(void)
|
|||
// send latest param values to wp_nav
|
||||
g2.wp_nav.set_turn_params(g2.turn_radius, g2.motors.have_skid_steering());
|
||||
g2.pos_control.set_turn_params(g2.turn_radius, g2.motors.have_skid_steering());
|
||||
g2.wheel_rate_control.set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());
|
||||
}
|
||||
|
||||
void Rover::update_current_mode(void)
|
||||
|
|
Loading…
Reference in New Issue