pub struct OrbitExecutionStatus {
pub time_usec: u64,
pub radius: f32,
pub frame: MavFrame,
pub x: i32,
pub y: i32,
pub z: f32,
}
Expand description
MAVLink ORBIT_EXECUTION_STATUS
message.
The minimum supported MAVLink version is MAVLink 2
.
§Description
Vehicle status report that is sent out while orbit execution is in progress (see MAV_CMD_DO_ORBIT).
§Encoding/Decoding
Message encoding/decoding are provided by implementing core::convert::TryFrom<Payload>
for
OrbitExecutionStatus
(encoding) and [IntoPayload
] (decoding) traits.
These traits are implemented by Message
proc macro.
Fields§
§time_usec: u64
MAVLink field time_usec
.
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.
radius: f32
MAVLink field radius
.
Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise.
frame: MavFrame
MAVLink field frame
.
The coordinate system of the fields: x, y, z.
x: i32
MAVLink field x
.
X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.
y: i32
MAVLink field y
.
Y coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.
z: f32
MAVLink field z
.
Altitude of center point. Coordinate system depends on frame field.
Implementations§
Source§impl OrbitExecutionStatus
impl OrbitExecutionStatus
Sourcepub const fn spec() -> MessageInfo
pub const fn spec() -> MessageInfo
Returns specification for this message.
Sourcepub const fn message_id() -> u32
pub const fn message_id() -> u32
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 OrbitExecutionStatus
impl Clone for OrbitExecutionStatus
Source§fn clone(&self) -> OrbitExecutionStatus
fn clone(&self) -> OrbitExecutionStatus
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source
. Read moreSource§impl Debug for OrbitExecutionStatus
impl Debug for OrbitExecutionStatus
Source§impl Default for OrbitExecutionStatus
impl Default for OrbitExecutionStatus
Source§fn default() -> OrbitExecutionStatus
fn default() -> OrbitExecutionStatus
Source§impl<'de> Deserialize<'de> for OrbitExecutionStatus
impl<'de> Deserialize<'de> for OrbitExecutionStatus
Source§fn deserialize<__D>(
__deserializer: __D,
) -> Result<OrbitExecutionStatus, <__D as Deserializer<'de>>::Error>where
__D: Deserializer<'de>,
fn deserialize<__D>(
__deserializer: __D,
) -> Result<OrbitExecutionStatus, <__D as Deserializer<'de>>::Error>where
__D: Deserializer<'de>,
Source§impl From<OrbitExecutionStatus> for Common
impl From<OrbitExecutionStatus> for Common
Source§fn from(value: OrbitExecutionStatus) -> Common
fn from(value: OrbitExecutionStatus) -> Common
Source§impl IntoPayload for OrbitExecutionStatus
impl IntoPayload for OrbitExecutionStatus
Source§impl MessageSpec for OrbitExecutionStatus
impl MessageSpec for OrbitExecutionStatus
Source§impl MessageSpecStatic for OrbitExecutionStatus
impl MessageSpecStatic for OrbitExecutionStatus
Source§fn spec() -> MessageInfo
fn spec() -> MessageInfo
Source§fn message_id() -> u32
fn message_id() -> u32
ID
.Source§fn min_supported_mavlink_version() -> MavLinkVersion
fn min_supported_mavlink_version() -> MavLinkVersion
Source§impl NamedType for OrbitExecutionStatus
impl NamedType for OrbitExecutionStatus
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 OrbitExecutionStatus
impl PartialEq for OrbitExecutionStatus
Source§impl Serialize for OrbitExecutionStatus
impl Serialize for OrbitExecutionStatus
Source§fn serialize<__S>(
&self,
__serializer: __S,
) -> Result<<__S as Serializer>::Ok, <__S as Serializer>::Error>where
__S: Serializer,
fn serialize<__S>(
&self,
__serializer: __S,
) -> Result<<__S as Serializer>::Ok, <__S as Serializer>::Error>where
__S: Serializer,
Source§impl TryFrom<&Payload> for OrbitExecutionStatus
impl TryFrom<&Payload> for OrbitExecutionStatus
Source§impl Type for OrbitExecutionStatus
impl Type for OrbitExecutionStatus
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.