Struct mavlink::common::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,
}
Available on crate feature common 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

Latitude (WGS84).

§longitude: i32

Longitude (WGS84).

§altitude: i32

Altitude (MSL). Positive for up..

§x: f32

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

§y: f32

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

§z: f32

Local Z position of this position in the local coordinate frame (NED: positive “down”).

§q: [f32; 4]

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

§approach_x: f32

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

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

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

System ID..

§time_usec: u64

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 SET_HOME_POSITION_DATA

source

pub const ENCODED_LEN: usize = 61usize

source

pub const DEFAULT: Self = _

Trait Implementations§

source§

impl Clone for SET_HOME_POSITION_DATA

source§

fn clone(&self) -> SET_HOME_POSITION_DATA

Returns a copy 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, dst: *mut T)

🔬This is a nightly-only experimental API. (clone_to_uninit)
Performs copy-assignment from self to dst. 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>,