AP_Common: make alt in Location 24 bit

this allows for up to 83km mission altitudes, while allowing for 1
more byte in the command structure, making p1 16 bits
This commit is contained in:
Andrew Tridgell 2014-03-20 16:55:38 +11:00
parent 428dcdb817
commit 959cafef8d

View File

@ -101,7 +101,11 @@ struct PACKED Location {
Location_Option_Flags flags; ///< options bitmask (1<<0 = relative altitude)
uint8_t options; /// allows writing all flags to eeprom as one byte
};
int32_t alt; ///< param 2 - Altitude in centimeters (meters * 100)
// by making alt 24 bit we can make p1 in a command 16 bit,
// allowing an accurate angle in centi-degrees. This keeps the
// storage cost per mission item at 15 bytes, and allows mission
// altitudes of up to +/- 83km
int32_t alt:24; ///< param 2 - Altitude in centimeters (meters * 100)
int32_t lat; ///< param 3 - Lattitude * 10**7
int32_t lng; ///< param 4 - Longitude * 10**7
};