pub struct MessageInterval {
pub message_id: u16,
pub interval_us: i32,
}Expand description
MAVLink MESSAGE_INTERVAL message.
The minimum supported MAVLink version is MAVLink 1.
§Description
The interval between messages for a particular MAVLink message ID. This message is sent in response to the MAV_CMD_REQUEST_MESSAGE command with param1=244 (this message) and param2=message_id (the id of the message for which the interval is required). It may also be sent in response to MAV_CMD_GET_MESSAGE_INTERVAL. This interface replaces DATA_STREAM.
§Encoding/Decoding
Message encoding/decoding are provided by implementing core::convert::TryFrom<Payload> for
MessageInterval (encoding) and [IntoPayload] (decoding) traits.
These traits are implemented by Message proc macro.
Fields§
§message_id: u16MAVLink field message_id.
The ID of the requested MAVLink message. v1.0 is limited to 254 messages.
interval_us: i32MAVLink field interval_us.
The interval between two messages. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent.
Implementations§
Source§impl MessageInterval
impl MessageInterval
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 MessageInterval
impl Clone for MessageInterval
Source§fn clone(&self) -> MessageInterval
fn clone(&self) -> MessageInterval
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source. Read moreSource§impl Debug for MessageInterval
impl Debug for MessageInterval
Source§impl Default for MessageInterval
impl Default for MessageInterval
Source§impl<'de> Deserialize<'de> for MessageInterval
impl<'de> Deserialize<'de> for MessageInterval
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<MessageInterval> for Common
impl From<MessageInterval> for Common
Source§fn from(value: MessageInterval) -> Self
fn from(value: MessageInterval) -> Self
Source§impl IntoPayload for MessageInterval
impl IntoPayload for MessageInterval
Source§impl MessageSpec for MessageInterval
impl MessageSpec for MessageInterval
Source§impl MessageSpecStatic for MessageInterval
impl MessageSpecStatic for MessageInterval
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 MessageInterval
impl NamedType for MessageInterval
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 MessageInterval
impl PartialEq for MessageInterval
Source§impl Serialize for MessageInterval
impl Serialize for MessageInterval
Source§impl TryFrom<&Payload> for MessageInterval
impl TryFrom<&Payload> for MessageInterval
Source§impl Type for MessageInterval
impl Type for MessageInterval
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.