SET_HOME_POSITION_DATA

Struct SET_HOME_POSITION_DATA 

Source
pub struct SET_HOME_POSITION_DATA {
    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 target_system: u8,
    pub time_usec: u64,
}
๐Ÿ‘ŽDeprecated: The command protocol version (MAV_CMD_DO_SET_HOME) allows a GCS to detect when setting the home position has failed. See MAV_CMD_DO_SET_HOME (Deprecated since 2022-02)
Available on crate feature development only.
Expand description

id: 243 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).

Fieldsยง

ยงlatitude: i32
๐Ÿ‘ŽDeprecated: The command protocol version (MAV_CMD_DO_SET_HOME) allows a GCS to detect when setting the home position has failed. See MAV_CMD_DO_SET_HOME (Deprecated since 2022-02)

Latitude (WGS84)

ยงlongitude: i32
๐Ÿ‘ŽDeprecated: The command protocol version (MAV_CMD_DO_SET_HOME) allows a GCS to detect when setting the home position has failed. See MAV_CMD_DO_SET_HOME (Deprecated since 2022-02)

Longitude (WGS84)

ยงaltitude: i32
๐Ÿ‘ŽDeprecated: The command protocol version (MAV_CMD_DO_SET_HOME) allows a GCS to detect when setting the home position has failed. See MAV_CMD_DO_SET_HOME (Deprecated since 2022-02)

Altitude (MSL). Positive for up.

ยงx: f32
๐Ÿ‘ŽDeprecated: The command protocol version (MAV_CMD_DO_SET_HOME) allows a GCS to detect when setting the home position has failed. See MAV_CMD_DO_SET_HOME (Deprecated since 2022-02)

Local X position of this position in the local coordinate frame (NED)

ยงy: f32
๐Ÿ‘ŽDeprecated: The command protocol version (MAV_CMD_DO_SET_HOME) allows a GCS to detect when setting the home position has failed. See MAV_CMD_DO_SET_HOME (Deprecated since 2022-02)

Local Y position of this position in the local coordinate frame (NED)

ยงz: f32
๐Ÿ‘ŽDeprecated: The command protocol version (MAV_CMD_DO_SET_HOME) allows a GCS to detect when setting the home position has failed. See MAV_CMD_DO_SET_HOME (Deprecated since 2022-02)

Local Z position of this position in the local coordinate frame (NED: positive โ€œdownโ€)

ยงq: [f32; 4]
๐Ÿ‘ŽDeprecated: The command protocol version (MAV_CMD_DO_SET_HOME) allows a GCS to detect when setting the home position has failed. See MAV_CMD_DO_SET_HOME (Deprecated since 2022-02)

World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground

ยงapproach_x: f32
๐Ÿ‘ŽDeprecated: The command protocol version (MAV_CMD_DO_SET_HOME) allows a GCS to detect when setting the home position has failed. See MAV_CMD_DO_SET_HOME (Deprecated since 2022-02)

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: f32
๐Ÿ‘ŽDeprecated: The command protocol version (MAV_CMD_DO_SET_HOME) allows a GCS to detect when setting the home position has failed. See MAV_CMD_DO_SET_HOME (Deprecated since 2022-02)

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: f32
๐Ÿ‘ŽDeprecated: The command protocol version (MAV_CMD_DO_SET_HOME) allows a GCS to detect when setting the home position has failed. See MAV_CMD_DO_SET_HOME (Deprecated since 2022-02)

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.

ยงtarget_system: u8
๐Ÿ‘ŽDeprecated: The command protocol version (MAV_CMD_DO_SET_HOME) allows a GCS to detect when setting the home position has failed. See MAV_CMD_DO_SET_HOME (Deprecated since 2022-02)

System ID.

ยงtime_usec: u64
๐Ÿ‘ŽDeprecated: The command protocol version (MAV_CMD_DO_SET_HOME) allows a GCS to detect when setting the home position has failed. See MAV_CMD_DO_SET_HOME (Deprecated since 2022-02)

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ยง

Trait Implementationsยง

Sourceยง

impl Clone for SET_HOME_POSITION_DATA

Sourceยง

fn clone(&self) -> SET_HOME_POSITION_DATA

Returns a duplicate of the value. Read more
1.0.0 ยท Sourceยง

fn clone_from(&mut self, source: &Self)

Performs copy-assignment from source. Read more
Sourceยง

impl Debug for SET_HOME_POSITION_DATA

Sourceยง

fn fmt(&self, f: &mut Formatter<'_>) -> Result

Formats the value using the given formatter. Read more
Sourceยง

impl Default for SET_HOME_POSITION_DATA

Sourceยง

fn default() -> Self

Returns the โ€œdefault valueโ€ for a type. Read more
Sourceยง

impl<'de> Deserialize<'de> for SET_HOME_POSITION_DATA

Sourceยง

fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>
where __D: Deserializer<'de>,

Deserialize this value from the given Serde deserializer. Read more
Sourceยง

impl MessageData for SET_HOME_POSITION_DATA

Sourceยง

const ID: u32 = 243u32

Sourceยง

const NAME: &'static str = "SET_HOME_POSITION"

Sourceยง

const EXTRA_CRC: u8 = 85u8

Sourceยง

const ENCODED_LEN: usize = 61usize

Sourceยง

type Message = MavMessage

Sourceยง

fn deser(_version: MavlinkVersion, __input: &[u8]) -> Result<Self, ParserError>

Sourceยง

fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize

Sourceยง

impl PartialEq for SET_HOME_POSITION_DATA

Sourceยง

fn eq(&self, other: &SET_HOME_POSITION_DATA) -> bool

Tests for self and other values to be equal, and is used by ==.
1.0.0 ยท Sourceยง

fn ne(&self, other: &Rhs) -> bool

Tests for !=. The default implementation is almost always sufficient, and should not be overridden without very good reason.
Sourceยง

impl Serialize for SET_HOME_POSITION_DATA

Sourceยง

fn serialize<__S>(&self, __serializer: __S) -> Result<__S::Ok, __S::Error>
where __S: Serializer,

Serialize this value into the given Serde serializer. Read more
Sourceยง

impl StructuralPartialEq for SET_HOME_POSITION_DATA

Auto Trait Implementationsยง

Blanket Implementationsยง

Sourceยง

impl<T> Any for T
where T: 'static + ?Sized,

Sourceยง

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
Sourceยง

impl<T> Borrow<T> for T
where T: ?Sized,

Sourceยง

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
Sourceยง

impl<T> BorrowMut<T> for T
where T: ?Sized,

Sourceยง

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
Sourceยง

impl<T> CloneToUninit for T
where T: Clone,

Sourceยง

unsafe fn clone_to_uninit(&self, dest: *mut u8)

๐Ÿ”ฌThis is a nightly-only experimental API. (clone_to_uninit)
Performs copy-assignment from self to dest. Read more
Sourceยง

impl<T> From<T> for T

Sourceยง

fn from(t: T) -> T

Returns the argument unchanged.

Sourceยง

impl<T, U> Into<U> for T
where U: From<T>,

Sourceยง

fn into(self) -> U

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

Sourceยง

impl<T> Same for T

Sourceยง

type Output = T

Should always be Self
Sourceยง

impl<T> ToOwned for T
where T: Clone,

Sourceยง

type Owned = T

The resulting type after obtaining ownership.
Sourceยง

fn to_owned(&self) -> T

Creates owned data from borrowed data, usually by cloning. Read more
Sourceยง

fn clone_into(&self, target: &mut T)

Uses borrowed data to replace owned data, usually by cloning. Read more
Sourceยง

impl<T, U> TryFrom<U> for T
where U: Into<T>,

Sourceยง

type Error = Infallible

The type returned in the event of a conversion error.
Sourceยง

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
Sourceยง

impl<T, U> TryInto<U> for T
where U: TryFrom<T>,

Sourceยง

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.
Sourceยง

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.
Sourceยง

impl<T> DeserializeOwned for T
where T: for<'de> Deserialize<'de>,