mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
AP_L1_Control: correct zeroing of cross-track integrator
This routine is generally only called at 10Hz, so the integrator was regularly reset.
This commit is contained in:
parent
d6869b9234
commit
fd9068de8a
@ -205,9 +205,13 @@ void AP_L1_Control::update_waypoint(const struct Location &prev_WP, const struct
|
||||
|
||||
uint32_t now = AP_HAL::micros();
|
||||
float dt = (now - _last_update_waypoint_us) * 1.0e-6f;
|
||||
if (dt > 1) {
|
||||
// controller hasn't been called for an extended period of
|
||||
// time. Reinitialise it.
|
||||
_L1_xtrack_i = 0.0f;
|
||||
}
|
||||
if (dt > 0.1) {
|
||||
dt = 0.1;
|
||||
_L1_xtrack_i = 0.0f;
|
||||
}
|
||||
_last_update_waypoint_us = now;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user