mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_Common: added terrain_alt flag to Location
signifies that the altitude is a above terrain altitude
This commit is contained in:
parent
5e2077185b
commit
8a48f06d18
@ -96,6 +96,7 @@ struct PACKED Location_Option_Flags {
|
|||||||
uint8_t relative_alt : 1; // 1 if altitude is relateive to home
|
uint8_t relative_alt : 1; // 1 if altitude is relateive to home
|
||||||
uint8_t unused1 : 1; // unused flag (defined so that loiter_ccw uses the correct bit)
|
uint8_t unused1 : 1; // unused flag (defined so that loiter_ccw uses the correct bit)
|
||||||
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
|
||||||
};
|
};
|
||||||
|
|
||||||
struct PACKED Location {
|
struct PACKED Location {
|
||||||
|
Loading…
Reference in New Issue
Block a user