Heartbeat

Struct Heartbeat 

Source
pub struct Heartbeat {
    pub type_: MavType,
    pub autopilot: MavAutopilot,
    pub base_mode: MavModeFlag,
    pub custom_mode: u32,
    pub system_status: MavState,
    pub mavlink_version: u8,
}
Expand description

MAVLink HEARTBEAT message.

The minimum supported MAVLink version is MAVLink 1.

§Description

The heartbeat message shows that a system or component is present and responding. The type and autopilot fields (along with the message component id), allow the receiving system to treat further messages from this system appropriately (e.g. by laying out the user interface based on the autopilot). This microservice is documented at https://mavlink.io/en/services/heartbeat.html

§Encoding/Decoding

Message encoding/decoding are provided by implementing core::convert::TryFrom<Payload> for Heartbeat (encoding) and [IntoPayload] (decoding) traits. These traits are implemented by Message proc macro.

Fields§

§type_: MavType

MAVLink field type.

Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type.

§autopilot: MavAutopilot

MAVLink field autopilot.

Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.

§base_mode: MavModeFlag

MAVLink field base_mode.

System mode bitmap.

§custom_mode: u32

MAVLink field custom_mode.

A bitfield for use for autopilot-specific flags

§system_status: MavState

MAVLink field system_status.

System status flag.

§mavlink_version: u8

MAVLink field mavlink_version.

MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version

Implementations§

Source§

impl Heartbeat

Source

pub const ID: u32 = 0u32

MavLink message ID.

Source

pub const fn spec() -> MessageInfo

Returns specification for this message.

Source

pub const fn message_id() -> u32

Message ID.

Source

pub const fn crc_extra() -> u8

Message CRC_EXTRA.

Minimum supported MAVLink version for this message.

Trait Implementations§

Source§

impl Clone for Heartbeat

Source§

fn clone(&self) -> Heartbeat

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 Heartbeat

Source§

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

Formats the value using the given formatter. Read more
Source§

impl Default for Heartbeat

Source§

fn default() -> Heartbeat

Returns the “default value” for a type. Read more
Source§

impl<'de> Deserialize<'de> for Heartbeat

Source§

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

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

impl From<Heartbeat> for Minimal

Source§

fn from(value: Heartbeat) -> Minimal

Converts to this type from the input type.
Source§

impl IntoPayload for Heartbeat

Source§

fn encode(&self, version: MavLinkVersion) -> Result<Payload, SpecError>

Encodes message into MAVLink payload. Read more
Source§

impl MessageSpec for Heartbeat

Source§

fn id(&self) -> u32

MAVLink message ID. Read more
Minimum supported MAVLink protocol version. Read more
Source§

fn crc_extra(&self) -> u8

Message EXTRA_CRC calculated from message XML definition. Read more
Source§

impl MessageSpecStatic for Heartbeat

Source§

fn spec() -> MessageInfo

Returns specification for this message.
Source§

fn message_id() -> u32

Message ID.
Source§

fn crc_extra() -> u8

Message CRC_EXTRA.
Minimum supported MAVLink version for this message.
Source§

impl NamedType for Heartbeat

Source§

fn sid() -> SpectaID

Source§

fn named_data_type( type_map: &mut TypeCollection, generics: &[DataType], ) -> NamedDataType

this is equivalent to Type::inline but returns a NamedDataType instead.
Source§

fn definition_named_data_type(type_map: &mut TypeCollection) -> NamedDataType

this is equivalent to [Type::definition] but returns a NamedDataType instead.
Source§

impl PartialEq for Heartbeat

Source§

fn eq(&self, other: &Heartbeat) -> 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 Heartbeat

Source§

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

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

impl TryFrom<&Payload> for Heartbeat

Source§

type Error = SpecError

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

fn try_from( value: &Payload, ) -> Result<Heartbeat, <Heartbeat as TryFrom<&Payload>>::Error>

Performs the conversion.
Source§

impl Type for Heartbeat

Source§

fn inline(type_map: &mut TypeCollection, generics: Generics<'_>) -> DataType

Returns the definition of a type using the provided generics. Read more
Source§

fn reference(type_map: &mut TypeCollection, generics: &[DataType]) -> Reference

Generates a datatype corresponding to a reference to this type, as determined by its category. Getting a reference to a type implies that it should belong in the type map (since it has to be referenced from somewhere), so the output of definition will be put into the type map.
Source§

impl Flatten for Heartbeat

Source§

impl Message for Heartbeat

Source§

impl StructuralPartialEq for Heartbeat

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> 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>,