1 #include <AP_HAL/AP_HAL.h>
2 #include "AP_L1_Control.h"
4 extern const AP_HAL::HAL
& hal
;
6 // table of user settable parameters
7 const AP_Param::GroupInfo
AP_L1_Control::var_info
[] = {
9 // @DisplayName: L1 control period
10 // @Description: Period in seconds of L1 tracking loop. This parameter is the primary control for aggressiveness of turns in auto mode. This needs to be larger for less responsive airframes. The default is quite conservative, but for most RC aircraft will lead to reasonable flight. For smaller more agile aircraft a value closer to 15 is appropriate, or even as low as 10 for some very agile aircraft. When tuning, change this value in small increments, as a value that is much too small (say 5 or 10 below the right value) can lead to very radical turns, and a risk of stalling.
15 AP_GROUPINFO("PERIOD", 0, AP_L1_Control
, _L1_period
, 17),
18 // @DisplayName: L1 control damping ratio
19 // @Description: Damping ratio for L1 control. Increase this in increments of 0.05 if you are getting overshoot in path tracking. You should not need a value below 0.7 or above 0.85.
23 AP_GROUPINFO("DAMPING", 1, AP_L1_Control
, _L1_damping
, 0.75f
),
26 // @DisplayName: L1 control crosstrack integrator gain
27 // @Description: Crosstrack error integrator gain. This gain is applied to the crosstrack error to ensure it converges to zero. Set to zero to disable. Smaller values converge slower, higher values will cause crosstrack error oscillation.
31 AP_GROUPINFO("XTRACK_I", 2, AP_L1_Control
, _L1_xtrack_i_gain
, 0.02),
34 // @DisplayName: Loiter Radius Bank Angle Limit
35 // @Description: The sealevel bank angle limit for a continous loiter. (Used to calculate airframe loading limits at higher altitudes). Setting to 0, will instead just scale the loiter radius directly
39 AP_GROUPINFO("LIM_BANK", 3, AP_L1_Control
, _loiter_bank_limit
, 0.0f
),
44 // Bank angle command based on angle between aircraft velocity vector and reference vector to path.
45 // S. Park, J. Deyst, and J. P. How, "A New Nonlinear Guidance Logic for Trajectory Tracking,"
46 // Proceedings of the AIAA Guidance, Navigation and Control
47 // Conference, Aug 2004. AIAA-2004-4900.
48 // Modified to use PD control for circle tracking to enable loiter radius less than L1 length
49 // Modified to enable period and damping of guidance loop to be set explicitly
50 // Modified to provide explicit control over capture angle
54 Wrap AHRS yaw if in reverse - radians
56 float AP_L1_Control::get_yaw() const
59 return wrap_PI(M_PI
+ _ahrs
.get_yaw());
61 return _ahrs
.get_yaw();
65 Wrap AHRS yaw sensor if in reverse - centi-degress
67 int32_t AP_L1_Control::get_yaw_sensor() const
70 return wrap_180_cd(18000 + _ahrs
.yaw_sensor
);
72 return _ahrs
.yaw_sensor
;
76 return the bank angle needed to achieve tracking from the last
79 int32_t AP_L1_Control::nav_roll_cd(void) const
83 formula can be obtained through equations of balanced spiral:
84 liftForce * cos(roll) = gravityForce * cos(pitch);
85 liftForce * sin(roll) = gravityForce * lateralAcceleration / gravityAcceleration; // as mass = gravityForce/gravityAcceleration
86 see issue 24319 [https://github.com/ArduPilot/ardupilot/issues/24319]
87 Multiplier 100.0f is for converting degrees to centidegrees
88 Made changes to avoid zero division as proposed by Andrew Tridgell: https://github.com/ArduPilot/ardupilot/pull/24331#discussion_r1267798397
90 float pitchLimL1
= radians(60); // Suggestion: constraint may be modified to pitch limits if their absolute values are less than 90 degree and more than 60 degrees.
91 float pitchL1
= constrain_float(_ahrs
.get_pitch(),-pitchLimL1
,pitchLimL1
);
92 ret
= degrees(atanf(_latAccDem
* (1.0f
/(GRAVITY_MSS
* cosf(pitchL1
))))) * 100.0f
;
93 ret
= constrain_float(ret
, -9000, 9000);
98 return the lateral acceleration needed to achieve tracking from the last
101 float AP_L1_Control::lateral_acceleration(void) const
106 int32_t AP_L1_Control::nav_bearing_cd(void) const
108 return wrap_180_cd(RadiansToCentiDegrees(_nav_bearing
));
111 int32_t AP_L1_Control::bearing_error_cd(void) const
113 return RadiansToCentiDegrees(_bearing_error
);
116 int32_t AP_L1_Control::target_bearing_cd(void) const
118 return wrap_180_cd(_target_bearing_cd
);
122 this is the turn distance assuming a 90 degree turn
124 float AP_L1_Control::turn_distance(float wp_radius
) const
126 wp_radius
*= sq(_ahrs
.get_EAS2TAS());
127 return MIN(wp_radius
, _L1_dist
);
131 this approximates the turn distance for a given turn angle. If the
132 turn_angle is > 90 then a 90 degree turn distance is used, otherwise
133 the turn distance is reduced linearly.
134 This function allows straight ahead mission legs to avoid thinking
135 they have reached the waypoint early, which makes things like camera
136 trigger and ball drop at exact positions under mission control much easier
138 float AP_L1_Control::turn_distance(float wp_radius
, float turn_angle
) const
140 float distance_90
= turn_distance(wp_radius
);
141 turn_angle
= fabsf(turn_angle
);
142 if (turn_angle
>= 90) {
145 return distance_90
* turn_angle
/ 90.0f
;
148 float AP_L1_Control::loiter_radius(const float radius
) const
150 // prevent an insane loiter bank limit
151 float sanitized_bank_limit
= constrain_float(_loiter_bank_limit
, 0.0f
, 89.0f
);
152 float lateral_accel_sea_level
= tanf(radians(sanitized_bank_limit
)) * GRAVITY_MSS
;
154 float nominal_velocity_sea_level
= 0.0f
;
155 if(_tecs
!= nullptr) {
156 nominal_velocity_sea_level
= _tecs
->get_target_airspeed();
159 float eas2tas_sq
= sq(_ahrs
.get_EAS2TAS());
161 if (is_zero(sanitized_bank_limit
) || is_zero(nominal_velocity_sea_level
) ||
162 is_zero(lateral_accel_sea_level
)) {
163 // Missing a sane input for calculating the limit, or the user has
164 // requested a straight scaling with altitude. This will always vary
165 // with the current altitude, but will at least protect the airframe
166 return radius
* eas2tas_sq
;
168 float sea_level_radius
= sq(nominal_velocity_sea_level
) / lateral_accel_sea_level
;
169 if (sea_level_radius
> radius
) {
170 // If we've told the plane that its sea level radius is unachievable fallback to
171 // straight altitude scaling
172 return radius
* eas2tas_sq
;
174 // select the requested radius, or the required altitude scale, whichever is safer
175 return MAX(sea_level_radius
* eas2tas_sq
, radius
);
180 bool AP_L1_Control::reached_loiter_target(void)
186 prevent indecision in our turning by using our previous turn
187 decision if we are in a narrow angle band pointing away from the
188 target and the turn angle has changed sign
190 void AP_L1_Control::_prevent_indecision(float &Nu
)
192 const float Nu_limit
= 0.9f
*M_PI
;
193 if (fabsf(Nu
) > Nu_limit
&&
194 fabsf(_last_Nu
) > Nu_limit
&&
195 labs(wrap_180_cd(_target_bearing_cd
- get_yaw_sensor())) > 12000 &&
196 Nu
* _last_Nu
< 0.0f
) {
197 // we are moving away from the target waypoint and pointing
198 // away from the waypoint (not flying backwards). The sign
199 // of Nu has also changed, which means we are
200 // oscillating in our decision about which way to go
205 // update L1 control for waypoint navigation
206 void AP_L1_Control::update_waypoint(const Location
&prev_WP
, const Location
&next_WP
, float dist_min
)
209 Location _current_loc
;
214 uint32_t now
= AP_HAL::micros();
215 float dt
= (now
- _last_update_waypoint_us
) * 1.0e-6f
;
217 // controller hasn't been called for an extended period of
218 // time. Reinitialise it.
224 _last_update_waypoint_us
= now
;
226 // Calculate L1 gain required for specified damping
227 float K_L1
= 4.0f
* _L1_damping
* _L1_damping
;
229 // Get current position and velocity
230 if (_ahrs
.get_location(_current_loc
) == false) {
231 // if no GPS loc available, maintain last nav/target_bearing
232 _data_is_stale
= true;
236 Vector2f _groundspeed_vector
= _ahrs
.groundspeed_vector();
238 // update _target_bearing_cd
239 _target_bearing_cd
= _current_loc
.get_bearing_to(next_WP
);
241 // Calculate groundspeed
242 float groundSpeed
= _groundspeed_vector
.length();
244 // check if we are moving in the direction of the front of the vehicle
245 const bool moving_forwards
= fabsf(wrap_PI(_groundspeed_vector
.angle() - get_yaw())) < M_PI_2
;
247 if (groundSpeed
< 0.1f
|| !moving_forwards
) {
248 // use a small ground speed vector in the right direction,
249 // allowing us to use the compass heading at zero GPS velocity
251 _groundspeed_vector
= Vector2f(cosf(get_yaw()), sinf(get_yaw())) * groundSpeed
;
254 // Calculate time varying control parameters
255 // Calculate the L1 length required for specified period
256 // 0.3183099 = 1/1/pipi
257 _L1_dist
= MAX(0.3183099f
* _L1_damping
* _L1_period
* groundSpeed
, dist_min
);
259 // Calculate the NE position of WP B relative to WP A
260 Vector2f AB
= prev_WP
.get_distance_NE(next_WP
);
261 float AB_length
= AB
.length();
263 // Check for AB zero length and track directly to the destination
265 if (AB
.length() < 1.0e-6f
) {
266 AB
= _current_loc
.get_distance_NE(next_WP
);
267 if (AB
.length() < 1.0e-6f
) {
268 AB
= Vector2f(cosf(get_yaw()), sinf(get_yaw()));
273 // Calculate the NE position of the aircraft relative to WP A
274 const Vector2f A_air
= prev_WP
.get_distance_NE(_current_loc
);
276 // calculate distance to target track, for reporting
277 _crosstrack_error
= A_air
% AB
;
279 // Determine if the aircraft is behind a +-135 degree degree arc centred on WP A
280 // and further than L1 distance from WP A. Then use WP A as the L1 reference point
281 // Otherwise do normal L1 guidance
282 float WP_A_dist
= A_air
.length();
283 float alongTrackDist
= A_air
* AB
;
284 if (WP_A_dist
> _L1_dist
&& alongTrackDist
/MAX(WP_A_dist
, 1.0f
) < -0.7071f
)
286 // Calc Nu to fly To WP A
287 Vector2f A_air_unit
= (A_air
).normalized(); // Unit vector from WP A to aircraft
288 xtrackVel
= _groundspeed_vector
% (-A_air_unit
); // Velocity across line
289 ltrackVel
= _groundspeed_vector
* (-A_air_unit
); // Velocity along line
290 Nu
= atan2f(xtrackVel
,ltrackVel
);
291 _nav_bearing
= atan2f(-A_air_unit
.y
, -A_air_unit
.x
); // bearing (radians) from AC to L1 point
292 } else if (alongTrackDist
> AB_length
+ groundSpeed
*3) {
293 // we have passed point B by 3 seconds. Head towards B
294 // Calc Nu to fly To WP B
295 const Vector2f B_air
= next_WP
.get_distance_NE(_current_loc
);
296 Vector2f B_air_unit
= (B_air
).normalized(); // Unit vector from WP B to aircraft
297 xtrackVel
= _groundspeed_vector
% (-B_air_unit
); // Velocity across line
298 ltrackVel
= _groundspeed_vector
* (-B_air_unit
); // Velocity along line
299 Nu
= atan2f(xtrackVel
,ltrackVel
);
300 _nav_bearing
= atan2f(-B_air_unit
.y
, -B_air_unit
.x
); // bearing (radians) from AC to L1 point
301 } else { // Calc Nu to fly along AB line
303 // Calculate Nu2 angle (angle of velocity vector relative to line connecting waypoints)
304 xtrackVel
= _groundspeed_vector
% AB
; // Velocity cross track
305 ltrackVel
= _groundspeed_vector
* AB
; // Velocity along track
306 float Nu2
= atan2f(xtrackVel
,ltrackVel
);
307 // Calculate Nu1 angle (Angle to L1 reference point)
308 float sine_Nu1
= _crosstrack_error
/MAX(_L1_dist
, 0.1f
);
309 // Limit sine of Nu1 to provide a controlled track capture angle of 45 deg
310 sine_Nu1
= constrain_float(sine_Nu1
, -0.7071f
, 0.7071f
);
311 float Nu1
= asinf(sine_Nu1
);
313 // compute integral error component to converge to a crosstrack of zero when traveling
314 // straight but reset it when disabled or if it changes. That allows for much easier
315 // tuning by having it re-converge each time it changes.
316 if (_L1_xtrack_i_gain
<= 0 || !is_equal(_L1_xtrack_i_gain
.get(), _L1_xtrack_i_gain_prev
)) {
318 _L1_xtrack_i_gain_prev
= _L1_xtrack_i_gain
;
319 } else if (fabsf(Nu1
) < radians(5)) {
320 _L1_xtrack_i
+= Nu1
* _L1_xtrack_i_gain
* dt
;
322 // an AHRS_TRIM_X=0.1 will drift to about 0.08 so 0.1 is a good worst-case to clip at
323 _L1_xtrack_i
= constrain_float(_L1_xtrack_i
, -0.1f
, 0.1f
);
326 // to converge to zero we must push Nu1 harder
330 _nav_bearing
= wrap_PI(atan2f(AB
.y
, AB
.x
) + Nu1
); // bearing (radians) from AC to L1 point
333 _prevent_indecision(Nu
);
336 // Limit Nu to +-(pi/2)
337 Nu
= constrain_float(Nu
, -1.5708f
, +1.5708f
);
338 _latAccDem
= K_L1
* groundSpeed
* groundSpeed
/ _L1_dist
* sinf(Nu
);
340 // Waypoint capture status is always false during waypoint following
342 _last_loiter
.reached_loiter_target_ms
= 0;
344 _bearing_error
= Nu
; // bearing error angle (radians), +ve to left of track
346 _data_is_stale
= false; // status are correctly updated with current waypoint data
349 // update L1 control for loitering
350 void AP_L1_Control::update_loiter(const Location
¢er_WP
, float radius
, int8_t loiter_direction
)
352 const float radius_unscaled
= radius
;
354 Location _current_loc
;
356 // scale loiter radius with square of EAS2TAS to allow us to stay
357 // stable at high altitude
358 radius
= loiter_radius(fabsf(radius
));
360 // Calculate guidance gains used by PD loop (used during circle tracking)
361 float omega
= (6.2832f
/ _L1_period
);
362 float Kx
= omega
* omega
;
363 float Kv
= 2.0f
* _L1_damping
* omega
;
365 // Calculate L1 gain required for specified damping (used during waypoint capture)
366 float K_L1
= 4.0f
* _L1_damping
* _L1_damping
;
368 // Get current position and velocity
369 if (_ahrs
.get_location(_current_loc
) == false) {
370 // if no GPS loc available, maintain last nav/target_bearing
371 _data_is_stale
= true;
375 Vector2f _groundspeed_vector
= _ahrs
.groundspeed_vector();
377 // Calculate groundspeed
378 float groundSpeed
= MAX(_groundspeed_vector
.length() , 1.0f
);
381 // update _target_bearing_cd
382 _target_bearing_cd
= _current_loc
.get_bearing_to(center_WP
);
385 // Calculate time varying control parameters
386 // Calculate the L1 length required for specified period
388 _L1_dist
= 0.3183099f
* _L1_damping
* _L1_period
* groundSpeed
;
390 // Calculate the NE position of the aircraft relative to WP A
391 const Vector2f A_air
= center_WP
.get_distance_NE(_current_loc
);
393 // Calculate the unit vector from WP A to aircraft
394 // protect against being on the waypoint and having zero velocity
395 // if too close to the waypoint, use the velocity vector
396 // if the velocity vector is too small, use the heading vector
398 if (A_air
.length() > 0.1f
) {
399 A_air_unit
= A_air
.normalized();
401 if (_groundspeed_vector
.length() < 0.1f
) {
402 A_air_unit
= Vector2f(cosf(_ahrs
.get_yaw()), sinf(_ahrs
.get_yaw()));
404 A_air_unit
= _groundspeed_vector
.normalized();
408 // Calculate Nu to capture center_WP
409 float xtrackVelCap
= A_air_unit
% _groundspeed_vector
; // Velocity across line - perpendicular to radial inbound to WP
410 float ltrackVelCap
= - (_groundspeed_vector
* A_air_unit
); // Velocity along line - radial inbound to WP
411 float Nu
= atan2f(xtrackVelCap
,ltrackVelCap
);
413 _prevent_indecision(Nu
);
416 Nu
= constrain_float(Nu
, -M_PI_2
, M_PI_2
); // Limit Nu to +- Pi/2
418 // Calculate lat accln demand to capture center_WP (use L1 guidance law)
419 float latAccDemCap
= K_L1
* groundSpeed
* groundSpeed
/ _L1_dist
* sinf(Nu
);
421 // Calculate radial position and velocity errors
422 float xtrackVelCirc
= -ltrackVelCap
; // Radial outbound velocity - reuse previous radial inbound velocity
423 float xtrackErrCirc
= A_air
.length() - radius
; // Radial distance from the loiter circle
425 // keep crosstrack error for reporting
426 _crosstrack_error
= xtrackErrCirc
;
428 // Calculate PD control correction to circle waypoint_ahrs.roll
429 float latAccDemCircPD
= (xtrackErrCirc
* Kx
+ xtrackVelCirc
* Kv
);
431 // Calculate tangential velocity
432 float velTangent
= xtrackVelCap
* float(loiter_direction
);
434 // Prevent PD demand from turning the wrong way by limiting the command when flying the wrong way
435 if (ltrackVelCap
< 0.0f
&& velTangent
< 0.0f
) {
436 latAccDemCircPD
= MAX(latAccDemCircPD
, 0.0f
);
439 // Calculate centripetal acceleration demand
440 float latAccDemCircCtr
= velTangent
* velTangent
/ MAX((0.5f
* radius
), (radius
+ xtrackErrCirc
));
442 // Sum PD control and centripetal acceleration to calculate lateral manoeuvre demand
443 float latAccDemCirc
= loiter_direction
* (latAccDemCircPD
+ latAccDemCircCtr
);
445 // Perform switchover between 'capture' and 'circle' modes at the
446 // point where the commands cross over to achieve a seamless transfer
447 // Only fly 'capture' mode if outside the circle
448 const uint32_t now_ms
= AP_HAL::millis();
449 if (xtrackErrCirc
> 0.0f
&& loiter_direction
* latAccDemCap
< loiter_direction
* latAccDemCirc
) {
450 _latAccDem
= latAccDemCap
;
453 if we were previously on the circle and the target has not
454 changed then keep _WPcircle true. This prevents
455 reached_loiter_target() from going false due to a gust of
456 wind or an unachievable loiter radius
459 _last_loiter
.reached_loiter_target_ms
!= 0 &&
460 now_ms
- _last_loiter
.reached_loiter_target_ms
< 200U &&
461 loiter_direction
== _last_loiter
.direction
&&
462 is_equal(radius_unscaled
, _last_loiter
.radius
) &&
463 center_WP
.same_loc_as(_last_loiter
.center_WP
)) {
464 // same location, within 200ms, keep the _WPcircle status as true
465 _last_loiter
.reached_loiter_target_ms
= now_ms
;
468 _last_loiter
.reached_loiter_target_ms
= 0;
471 _bearing_error
= Nu
; // angle between demanded and achieved velocity vector, +ve to left of track
472 _nav_bearing
= atan2f(-A_air_unit
.y
, -A_air_unit
.x
); // bearing (radians) from AC to L1 point
474 _latAccDem
= latAccDemCirc
;
476 _last_loiter
.reached_loiter_target_ms
= now_ms
;
477 _bearing_error
= 0.0f
; // bearing error (radians), +ve to left of track
478 _nav_bearing
= atan2f(-A_air_unit
.y
, -A_air_unit
.x
); // bearing (radians) from AC to L1 point
481 _last_loiter
.radius
= radius_unscaled
;
482 _last_loiter
.direction
= loiter_direction
;
483 _last_loiter
.center_WP
= center_WP
;
485 _data_is_stale
= false; // status are correctly updated with current waypoint data
489 // update L1 control for heading hold navigation
490 void AP_L1_Control::update_heading_hold(int32_t navigation_heading_cd
)
492 // Calculate normalised frequency for tracking loop
493 const float omegaA
= 4.4428f
/_L1_period
; // sqrt(2)*pi/period
494 // Calculate additional damping gain
499 // copy to _target_bearing_cd and _nav_bearing
500 _target_bearing_cd
= wrap_180_cd(navigation_heading_cd
);
501 _nav_bearing
= radians(navigation_heading_cd
* 0.01f
);
503 Nu_cd
= _target_bearing_cd
- wrap_180_cd(_ahrs
.yaw_sensor
);
504 Nu_cd
= wrap_180_cd(Nu_cd
);
505 Nu
= radians(Nu_cd
* 0.01f
);
507 Vector2f _groundspeed_vector
= _ahrs
.groundspeed_vector();
509 // Calculate groundspeed
510 float groundSpeed
= _groundspeed_vector
.length();
512 // Calculate time varying control parameters
513 _L1_dist
= groundSpeed
/ omegaA
; // L1 distance is adjusted to maintain a constant tracking loop frequency
514 float VomegaA
= groundSpeed
* omegaA
;
516 // Waypoint capture status is always false during heading hold
518 _last_loiter
.reached_loiter_target_ms
= 0;
520 _crosstrack_error
= 0;
522 _bearing_error
= Nu
; // bearing error angle (radians), +ve to left of track
525 Nu
= constrain_float(Nu
, -M_PI_2
, M_PI_2
);
526 _latAccDem
= 2.0f
*sinf(Nu
)*VomegaA
;
528 _data_is_stale
= false; // status are correctly updated with current waypoint data
531 // update L1 control for level flight on current heading
532 void AP_L1_Control::update_level_flight(void)
534 // copy to _target_bearing_cd and _nav_bearing
535 _target_bearing_cd
= _ahrs
.yaw_sensor
;
536 _nav_bearing
= _ahrs
.get_yaw();
538 _crosstrack_error
= 0;
540 // Waypoint capture status is always false during heading hold
542 _last_loiter
.reached_loiter_target_ms
= 0;
546 _data_is_stale
= false; // status are correctly updated with current waypoint data