pub struct SetHomePosition {
pub target_system: u8,
pub latitude: i32,
pub longitude: i32,
pub altitude: i32,
pub x: f32,
pub y: f32,
pub z: f32,
pub q: [f32; 4],
pub approach_x: f32,
pub approach_y: f32,
pub approach_z: f32,
pub time_usec: u64,
}Expand description
MAVLink SET_HOME_POSITION message.
Minimum supported MAVLink version is MAVLink 1.
§Description
Sets the home position. The home position is the default position that the system will return to and land on. The position is set automatically by the system during the takeoff (and may also be set using this message). The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. Note: the current home position may be emitted in a HOME_POSITION message on request (using MAV_CMD_REQUEST_MESSAGE with param1=242).
§Encoding/Decoding
Message encoding/decoding are provided by implementing core::convert::TryFrom<Payload> for
SetHomePosition (encoding) and [IntoPayload] (decoding) traits.
These traits are implemented by Message proc macro.
Fields§
§target_system: u8MAVLink field target_system.
System ID.
latitude: i32MAVLink field latitude.
Latitude (WGS84)
longitude: i32MAVLink field longitude.
Longitude (WGS84)
altitude: i32MAVLink field altitude.
Altitude (MSL). Positive for up.
x: f32MAVLink field x.
Local X position of this position in the local coordinate frame (NED)
y: f32MAVLink field y.
Local Y position of this position in the local coordinate frame (NED)
z: f32MAVLink field z.
Local Z position of this position in the local coordinate frame (NED: positive “down”)
q: [f32; 4]MAVLink field q.
World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground
approach_x: f32MAVLink field approach_x.
Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
approach_y: f32MAVLink field approach_y.
Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
approach_z: f32MAVLink field approach_z.
Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
time_usec: u64MAVLink field time_usec.
Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
Implementations§
Source§impl SetHomePosition
impl SetHomePosition
Sourcepub const fn spec() -> MessageInfo
pub const fn spec() -> MessageInfo
Returns specification for this message.
Sourcepub const fn message_id() -> MessageId
pub const fn message_id() -> MessageId
Message ID.
Sourcepub const fn min_supported_mavlink_version() -> MavLinkVersion
pub const fn min_supported_mavlink_version() -> MavLinkVersion
Minimum supported MAVLink version for this message.
Trait Implementations§
Source§impl Clone for SetHomePosition
impl Clone for SetHomePosition
Source§fn clone(&self) -> SetHomePosition
fn clone(&self) -> SetHomePosition
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source. Read moreSource§impl Debug for SetHomePosition
impl Debug for SetHomePosition
Source§impl Default for SetHomePosition
impl Default for SetHomePosition
Source§impl<'de> Deserialize<'de> for SetHomePosition
impl<'de> Deserialize<'de> for SetHomePosition
Source§fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>where
__D: Deserializer<'de>,
fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>where
__D: Deserializer<'de>,
Source§impl From<SetHomePosition> for Common
impl From<SetHomePosition> for Common
Source§fn from(value: SetHomePosition) -> Self
fn from(value: SetHomePosition) -> Self
Source§impl IntoPayload for SetHomePosition
impl IntoPayload for SetHomePosition
Source§impl MessageSpec for SetHomePosition
impl MessageSpec for SetHomePosition
Source§impl MessageSpecStatic for SetHomePosition
impl MessageSpecStatic for SetHomePosition
Source§fn spec() -> MessageInfo
fn spec() -> MessageInfo
Source§fn message_id() -> MessageId
fn message_id() -> MessageId
ID.Source§fn min_supported_mavlink_version() -> MavLinkVersion
fn min_supported_mavlink_version() -> MavLinkVersion
Source§impl NamedType for SetHomePosition
impl NamedType for SetHomePosition
fn sid() -> SpectaID
Source§fn named_data_type(
type_map: &mut TypeCollection,
generics: &[DataType],
) -> NamedDataType
fn named_data_type( type_map: &mut TypeCollection, generics: &[DataType], ) -> NamedDataType
Source§fn definition_named_data_type(type_map: &mut TypeCollection) -> NamedDataType
fn definition_named_data_type(type_map: &mut TypeCollection) -> NamedDataType
Source§impl PartialEq for SetHomePosition
impl PartialEq for SetHomePosition
Source§impl Serialize for SetHomePosition
impl Serialize for SetHomePosition
Source§impl TryFrom<&Payload> for SetHomePosition
impl TryFrom<&Payload> for SetHomePosition
Source§impl Type for SetHomePosition
impl Type for SetHomePosition
Source§fn inline(type_map: &mut TypeCollection, generics: Generics<'_>) -> DataType
fn inline(type_map: &mut TypeCollection, generics: Generics<'_>) -> DataType
Source§fn reference(type_map: &mut TypeCollection, generics: &[DataType]) -> Reference
fn reference(type_map: &mut TypeCollection, generics: &[DataType]) -> Reference
definition will be put into the type map.