mirror of https://github.com/ArduPilot/ardupilot
AP_L1_Control: fixed waypoint approach logic
this could cause the RTL approach to not break off onto the circle correctly
This commit is contained in:
parent
80def01fbe
commit
1393ed58d0
|
@ -260,7 +260,8 @@ void AP_L1_Control::update_loiter(const struct Location ¢er_WP, float radius
|
|||
|
||||
// Perform switchover between 'capture' and 'circle' modes at the point where the commands cross over to achieve a seamless transfer
|
||||
// Only fly 'capture' mode if outside the circle
|
||||
if ((latAccDemCap < latAccDemCirc && loiter_direction > 0 && xtrackErrCirc > 0.0f) | (latAccDemCap > latAccDemCirc && loiter_direction < 0 && xtrackErrCirc > 0.0f)) {
|
||||
if ((latAccDemCap < latAccDemCirc && loiter_direction > 0 && xtrackErrCirc > 0.0f) ||
|
||||
(latAccDemCap > latAccDemCirc && loiter_direction < 0 && xtrackErrCirc > 0.0f)) {
|
||||
_latAccDem = latAccDemCap;
|
||||
_WPcircle = false;
|
||||
_bearing_error = Nu; // angle between demanded and achieved velocity vector, +ve to left of track
|
||||
|
|
Loading…
Reference in New Issue