mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-28 19:48:31 -04:00
AP_Common: 1of3 add loiter_xtrack option flag for post-loiter navigation
0 to crosstrack from center of waypoint, 1 to crosstrack from tangent exit location
This commit is contained in:
parent
2246343ec7
commit
02eeb2d4f0
@ -76,7 +76,7 @@ char (&_ARRAY_SIZE_HELPER(T (&_arr)[0]))[0];
|
|||||||
/// bit 2: Direction of loiter command 0: Clockwise 1: Counter-Clockwise
|
/// bit 2: Direction of loiter command 0: Clockwise 1: Counter-Clockwise
|
||||||
/// bit 3: Req.to hit WP.alt to continue 0: No, 1: Yes
|
/// bit 3: Req.to hit WP.alt to continue 0: No, 1: Yes
|
||||||
/// bit 4: Relative to Home 0: No, 1: Yes
|
/// bit 4: Relative to Home 0: No, 1: Yes
|
||||||
/// bit 5:
|
/// bit 5: Loiter crosstrack reference 0: WP center 1: Tangent exit point
|
||||||
/// bit 6:
|
/// bit 6:
|
||||||
/// bit 7: Move to next Command 0: YES, 1: Loiter until commanded
|
/// bit 7: Move to next Command 0: YES, 1: Loiter until commanded
|
||||||
|
|
||||||
@ -88,6 +88,7 @@ struct PACKED Location_Option_Flags {
|
|||||||
uint8_t loiter_ccw : 1; // 0 if clockwise, 1 if counter clockwise
|
uint8_t loiter_ccw : 1; // 0 if clockwise, 1 if counter clockwise
|
||||||
uint8_t terrain_alt : 1; // this altitude is above terrain
|
uint8_t terrain_alt : 1; // this altitude is above terrain
|
||||||
uint8_t origin_alt : 1; // this altitude is above ekf origin
|
uint8_t origin_alt : 1; // this altitude is above ekf origin
|
||||||
|
uint8_t loiter_xtrack : 1; // 0 to crosstrack from center of waypoint, 1 to crosstrack from tangent exit location
|
||||||
};
|
};
|
||||||
|
|
||||||
struct PACKED Location {
|
struct PACKED Location {
|
||||||
|
Loading…
Reference in New Issue
Block a user