Browse Source

AP_Common: Added RallyLocation struct.

mission-4.1.18
Michael Day 12 years ago committed by Andrew Tridgell
parent
commit
823a40c203
  1. 11
      libraries/AP_Common/AP_Common.h

11
libraries/AP_Common/AP_Common.h

@ -97,6 +97,17 @@ struct Location { @@ -97,6 +97,17 @@ struct Location {
int32_t lng; ///< param 4 - Longitude * 10**7
};
struct RallyLocation {
int32_t lat; //Latitude * 10^7
int32_t lng; //Longitude * 10^7
int16_t alt; //transit altitude (and loiter altitude) in meters;
int16_t break_alt; //when autolanding, break out of loiter at this alt (meters)
uint16_t land_dir; //when the time comes to auto-land, try to land in this direction (centidegrees)
uint8_t flags; //bit 0 = seek favorable winds when choosing a landing poi
//bit 1 = do auto land after arriving
//all other bits are for future use.
};
//@}
////////////////////////////////////////////////////////////////////////////////

Loading…
Cancel
Save