Skip to content

Commit 6345f41

Browse files
committed
AP_L1_Control: Add integral term to loiter nav.
Extracted the logic to calculate the integral term for waypoint navigation into a private method, and applied it to the loiter navigation.
1 parent 826662f commit 6345f41

File tree

2 files changed

+56
-32
lines changed

2 files changed

+56
-32
lines changed

libraries/AP_L1_Control/AP_L1_Control.cpp

Lines changed: 54 additions & 31 deletions
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ const AP_Param::GroupInfo AP_L1_Control::var_info[] = {
4545
// S. Park, J. Deyst, and J. P. How, "A New Nonlinear Guidance Logic for Trajectory Tracking,"
4646
// Proceedings of the AIAA Guidance, Navigation and Control
4747
// Conference, Aug 2004. AIAA-2004-4900.
48-
// Modified to use PD control for circle tracking to enable loiter radius less than L1 length
48+
// Modified to use PID control for circle tracking to enable loiter radius less than L1 length
4949
// Modified to enable period and damping of guidance loop to be set explicitly
5050
// Modified to provide explicit control over capture angle
5151

@@ -202,11 +202,47 @@ void AP_L1_Control::_prevent_indecision(float &Nu)
202202
}
203203
}
204204

205+
void AP_L1_Control::_update_xtrack_integral(float error, float max_abs_error, float clamp)
206+
{
207+
uint32_t now_us = AP_HAL::micros();
208+
float dt = (now_us - _last_update_xtrack_i_us) * 1.0e-6f;
209+
if (dt > 1) {
210+
// Controller hasn't been called for an extended period of
211+
// time. Reset it.
212+
_L1_xtrack_i = 0.0f;
213+
}
214+
if (dt > 0.1) {
215+
dt = 0.1;
216+
}
217+
_last_update_xtrack_i_us = now_us;
218+
219+
// Reset integral error component if gain parameter has changed. This allows
220+
// for much easier tuning by having it re-converge each time it changes.
221+
if (!is_positive(_L1_xtrack_i_gain) ||
222+
!is_equal(_L1_xtrack_i_gain.get(), _L1_xtrack_i_gain_prev)) {
223+
_L1_xtrack_i = 0;
224+
_L1_xtrack_i_gain_prev = _L1_xtrack_i_gain;
225+
226+
return;
227+
}
228+
229+
// Return if error is too large
230+
if (fabsf(error) >= max_abs_error) {
231+
return;
232+
}
233+
234+
// Compute integral error component to converge to a crosstrack of zero, and
235+
// clamp it
236+
_L1_xtrack_i += error * _L1_xtrack_i_gain * dt;
237+
_L1_xtrack_i = constrain_float(_L1_xtrack_i, -clamp, clamp);
238+
}
239+
205240
// update L1 control for waypoint navigation
206241
void AP_L1_Control::update_waypoint(const Location &prev_WP, const Location &next_WP, float dist_min)
207242
{
208243
// Update nav. mode
209244
if (_current_nav_mode != NavMode::WAYPOINT) {
245+
_L1_xtrack_i = 0.0f; // Reset integral component on nav. mode change
210246
_current_nav_mode = NavMode::WAYPOINT;
211247
}
212248

@@ -215,18 +251,6 @@ void AP_L1_Control::update_waypoint(const Location &prev_WP, const Location &nex
215251
float xtrackVel;
216252
float ltrackVel;
217253

218-
uint32_t now = AP_HAL::micros();
219-
float dt = (now - _last_update_waypoint_us) * 1.0e-6f;
220-
if (dt > 1) {
221-
// controller hasn't been called for an extended period of
222-
// time. Reinitialise it.
223-
_L1_xtrack_i = 0.0f;
224-
}
225-
if (dt > 0.1) {
226-
dt = 0.1;
227-
}
228-
_last_update_waypoint_us = now;
229-
230254
// Calculate L1 gain required for specified damping
231255
float K_L1 = 4.0f * _L1_damping * _L1_damping;
232256

@@ -314,18 +338,10 @@ void AP_L1_Control::update_waypoint(const Location &prev_WP, const Location &nex
314338
sine_Nu1 = constrain_float(sine_Nu1, -0.7071f, 0.7071f);
315339
float Nu1 = asinf(sine_Nu1);
316340

317-
// compute integral error component to converge to a crosstrack of zero when traveling
318-
// straight but reset it when disabled or if it changes. That allows for much easier
319-
// tuning by having it re-converge each time it changes.
320-
if (_L1_xtrack_i_gain <= 0 || !is_equal(_L1_xtrack_i_gain.get(), _L1_xtrack_i_gain_prev)) {
321-
_L1_xtrack_i = 0;
322-
_L1_xtrack_i_gain_prev = _L1_xtrack_i_gain;
323-
} else if (fabsf(Nu1) < radians(5)) {
324-
_L1_xtrack_i += Nu1 * _L1_xtrack_i_gain * dt;
325-
326-
// an AHRS_TRIM_X=0.1 will drift to about 0.08 so 0.1 is a good worst-case to clip at
327-
_L1_xtrack_i = constrain_float(_L1_xtrack_i, -0.1f, 0.1f);
328-
}
341+
// Update the integral term up to 5º of error
342+
// An AHRS_TRIM_X=0.1 will drift to about 0.08 so 0.1 is a good
343+
// worst-case to clip at
344+
_update_xtrack_integral(Nu1, radians(5), 0.1f);
329345

330346
// to converge to zero we must push Nu1 harder
331347
Nu1 += _L1_xtrack_i;
@@ -355,6 +371,7 @@ void AP_L1_Control::update_loiter(const Location &center_WP, float radius, int8_
355371
{
356372
// Update nav. mode
357373
if (_current_nav_mode != NavMode::LOITER) {
374+
_L1_xtrack_i = 0.0f; // Reset integral component on nav. mode change
358375
_current_nav_mode = NavMode::LOITER;
359376
}
360377

@@ -367,6 +384,7 @@ void AP_L1_Control::update_loiter(const Location &center_WP, float radius, int8_
367384
radius = loiter_radius(fabsf(radius));
368385

369386
// Calculate guidance gains used by PD loop (used during circle tracking)
387+
// Calculate guidance gains used by PID loop (used during circle tracking)
370388
float omega = (6.2832f / _L1_period);
371389
float Kx = omega * omega;
372390
float Kv = 2.0f * _L1_damping * omega;
@@ -434,22 +452,27 @@ void AP_L1_Control::update_loiter(const Location &center_WP, float radius, int8_
434452
// keep crosstrack error for reporting
435453
_crosstrack_error = xtrackErrCirc;
436454

437-
// Calculate PD control correction to circle waypoint_ahrs.roll
438-
float latAccDemCircPD = (xtrackErrCirc * Kx + xtrackVelCirc * Kv);
455+
// Correct errors up to half the radius. Clamping to a value of 4
456+
// produces good results, allowing for precise 50 m radius loiters at a
457+
// speed of 22 m/s
458+
_update_xtrack_integral(_crosstrack_error, radius / 2, 4.0f);
459+
460+
// Calculate PID control correction to circle waypoint_ahrs.roll
461+
float latAccDemCircPID = xtrackErrCirc * Kx + xtrackVelCirc * Kv + _L1_xtrack_i;
439462

440463
// Calculate tangential velocity
441464
float velTangent = xtrackVelCap * float(loiter_direction);
442465

443-
// Prevent PD demand from turning the wrong way by limiting the command when flying the wrong way
466+
// Prevent PID demand from turning the wrong way by limiting the command when flying the wrong way
444467
if (ltrackVelCap < 0.0f && velTangent < 0.0f) {
445-
latAccDemCircPD = MAX(latAccDemCircPD, 0.0f);
468+
latAccDemCircPID = MAX(latAccDemCircPID, 0.0f);
446469
}
447470

448471
// Calculate centripetal acceleration demand
449472
float latAccDemCircCtr = velTangent * velTangent / MAX((0.5f * radius), (radius + xtrackErrCirc));
450473

451-
// Sum PD control and centripetal acceleration to calculate lateral manoeuvre demand
452-
float latAccDemCirc = loiter_direction * (latAccDemCircPD + latAccDemCircCtr);
474+
// Sum PID control and centripetal acceleration to calculate lateral manoeuvre demand
475+
float latAccDemCirc = loiter_direction * (latAccDemCircPID + latAccDemCircCtr);
453476

454477
// Perform switchover between 'capture' and 'circle' modes at the
455478
// point where the commands cross over to achieve a seamless transfer

libraries/AP_L1_Control/AP_L1_Control.h

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -125,10 +125,11 @@ class AP_L1_Control : public AP_Navigation {
125125

126126
// integral feedback to correct crosstrack error. Used to ensure xtrack converges to zero.
127127
// For tuning purposes it's helpful to clear the integrator when it changes so a _prev is used
128+
void _update_xtrack_integral(float error, float max_abs_error, float clamp);
129+
uint32_t _last_update_xtrack_i_us;
128130
float _L1_xtrack_i = 0;
129131
AP_Float _L1_xtrack_i_gain;
130132
float _L1_xtrack_i_gain_prev = 0;
131-
uint32_t _last_update_waypoint_us;
132133
bool _data_is_stale = true;
133134

134135
AP_Float _loiter_bank_limit;

0 commit comments

Comments
 (0)