pub struct TimeEstimateToTarget {
pub safe_return: i32,
pub land: i32,
pub mission_next_item: i32,
pub mission_end: i32,
pub commanded_action: i32,
}Expand description
MAVLink TIME_ESTIMATE_TO_TARGET message.
The minimum supported MAVLink version is MAVLink 2.
§Description
Time/duration estimates for various events and actions given the current vehicle state and position.
§Encoding/Decoding
Message encoding/decoding are provided by implementing core::convert::TryFrom<Payload> for
TimeEstimateToTarget (encoding) and [IntoPayload] (decoding) traits.
These traits are implemented by Message proc macro.
Fields§
§safe_return: i32MAVLink field safe_return.
Estimated time to complete the vehicle’s configured “safe return” action from its current position (e.g. RTL, Smart RTL, etc.). -1 indicates that the vehicle is landed, or that no time estimate available.
land: i32MAVLink field land.
Estimated time for vehicle to complete the LAND action from its current position. -1 indicates that the vehicle is landed, or that no time estimate available.
mission_next_item: i32MAVLink field mission_next_item.
Estimated time for reaching/completing the currently active mission item. -1 means no time estimate available.
mission_end: i32MAVLink field mission_end.
Estimated time for completing the current mission. -1 means no mission active and/or no estimate available.
commanded_action: i32MAVLink field commanded_action.
Estimated time for completing the current commanded action (i.e. Go To, Takeoff, Land, etc.). -1 means no action active and/or no estimate available.
Implementations§
Source§impl TimeEstimateToTarget
impl TimeEstimateToTarget
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 TimeEstimateToTarget
impl Clone for TimeEstimateToTarget
Source§fn clone(&self) -> TimeEstimateToTarget
fn clone(&self) -> TimeEstimateToTarget
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source. Read moreSource§impl Debug for TimeEstimateToTarget
impl Debug for TimeEstimateToTarget
Source§impl Default for TimeEstimateToTarget
impl Default for TimeEstimateToTarget
Source§impl<'de> Deserialize<'de> for TimeEstimateToTarget
impl<'de> Deserialize<'de> for TimeEstimateToTarget
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<TimeEstimateToTarget> for Common
impl From<TimeEstimateToTarget> for Common
Source§fn from(value: TimeEstimateToTarget) -> Self
fn from(value: TimeEstimateToTarget) -> Self
Source§impl IntoPayload for TimeEstimateToTarget
impl IntoPayload for TimeEstimateToTarget
Source§impl MessageSpec for TimeEstimateToTarget
impl MessageSpec for TimeEstimateToTarget
Source§impl MessageSpecStatic for TimeEstimateToTarget
impl MessageSpecStatic for TimeEstimateToTarget
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 TimeEstimateToTarget
impl NamedType for TimeEstimateToTarget
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 TimeEstimateToTarget
impl PartialEq for TimeEstimateToTarget
Source§impl Serialize for TimeEstimateToTarget
impl Serialize for TimeEstimateToTarget
Source§impl TryFrom<&Payload> for TimeEstimateToTarget
impl TryFrom<&Payload> for TimeEstimateToTarget
Source§impl Type for TimeEstimateToTarget
impl Type for TimeEstimateToTarget
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.