mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: set loiter.direction for GUIDED mode
This commit is contained in:
parent
94d4ecef11
commit
e446f375a7
@ -204,6 +204,12 @@ static void set_next_WP(const struct Location *wp)
|
|||||||
|
|
||||||
static void set_guided_WP(void)
|
static void set_guided_WP(void)
|
||||||
{
|
{
|
||||||
|
if (g.loiter_radius < 0) {
|
||||||
|
loiter.direction = -1;
|
||||||
|
} else {
|
||||||
|
loiter.direction = 1;
|
||||||
|
}
|
||||||
|
|
||||||
// copy the current location into the OldWP slot
|
// copy the current location into the OldWP slot
|
||||||
// ---------------------------------------
|
// ---------------------------------------
|
||||||
prev_WP = current_loc;
|
prev_WP = current_loc;
|
||||||
|
Loading…
Reference in New Issue
Block a user