PX4-Autopilot/msg/versioned/HomePosition.msg
Julian Oes 6855aa57c4
commander: publish full home attitude, not only yaw (#19717)
According to the mavlink spec we should be publishing the home attitude
as a quaternion rather than just the yaw/heading.

Additionally, this allows setting the landing roll and pitch angle using
DO_SET_HOME (this yet needs to go into the MAVLink spec though).
2025-07-09 14:43:31 -08:00

26 lines
799 B
Plaintext

# GPS home position in WGS84 coordinates.
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
float64 lat # Latitude in degrees
float64 lon # Longitude in degrees
float32 alt # Altitude in meters (AMSL)
float32 x # X coordinate in meters
float32 y # Y coordinate in meters
float32 z # Z coordinate in meters
float32 roll # Pitch angle in radians
float32 pitch # Roll angle in radians
float32 yaw # Yaw angle in radians
bool valid_alt # true when the altitude has been set
bool valid_hpos # true when the latitude and longitude have been set
bool valid_lpos # true when the local position (xyz) has been set
bool manual_home # true when home position was set manually
uint32 update_count # update counter of the home position