pub struct COMMAND_INT_DATA {
Show 13 fields pub param1: f32, pub param2: f32, pub param3: f32, pub param4: f32, pub x: i32, pub y: i32, pub z: f32, pub command: MavCmd, pub target_system: u8, pub target_component: u8, pub frame: MavFrame, pub current: u8, pub autocontinue: u8,
}
Expand description

id: 75 Send a command with up to seven parameters to the MAV, where params 5 and 6 are integers and the other values are floats. This is preferred over COMMAND_LONG when sending positional data in params 5 and 6, as it allows for greater precision when sending latitudes/longitudes. Param 5 and 6 encode positional data as scaled integers, where the scaling depends on the actual command value. NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component’s current latitude, yaw rather than a specific value). The command microservice is documented at https://mavlink.io/en/services/command.html.

Fields§

§param1: f32

PARAM1, see MAV_CMD enum.

§param2: f32

PARAM2, see MAV_CMD enum.

§param3: f32

PARAM3, see MAV_CMD enum.

§param4: f32

PARAM4, see MAV_CMD enum.

§x: i32

PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7.

§y: i32

PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7.

§z: f32

PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame)..

§command: MavCmd

The scheduled action for the mission item..

§target_system: u8

System ID.

§target_component: u8

Component ID.

§frame: MavFrame

The coordinate system of the COMMAND..

§current: u8

Not used..

§autocontinue: u8

Not used (set 0)..

Implementations§

source§

impl COMMAND_INT_DATA

source

pub const ENCODED_LEN: usize = 35usize

source

pub const DEFAULT: Self = _

Trait Implementations§

source§

impl Clone for COMMAND_INT_DATA

source§

fn clone(&self) -> COMMAND_INT_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 COMMAND_INT_DATA

source§

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

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

impl Default for COMMAND_INT_DATA

source§

fn default() -> Self

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

impl<'de> Deserialize<'de> for COMMAND_INT_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 COMMAND_INT_DATA

§

type Message = MavMessage

source§

const ID: u32 = 75u32

source§

const NAME: &'static str = "COMMAND_INT"

source§

const EXTRA_CRC: u8 = 158u8

source§

const ENCODED_LEN: usize = 35usize

source§

fn deser(_version: MavlinkVersion, __input: &[u8]) -> Result<Self, ParserError>

source§

fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize

source§

impl PartialEq for COMMAND_INT_DATA

source§

fn eq(&self, other: &COMMAND_INT_DATA) -> bool

This method tests for self and other values to be equal, and is used by ==.
1.0.0 · source§

fn ne(&self, other: &Rhs) -> bool

This method tests for !=. The default implementation is almost always sufficient, and should not be overridden without very good reason.
source§

impl Serialize for COMMAND_INT_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 COMMAND_INT_DATA

Auto Trait Implementations§

Blanket Implementations§

source§

impl<T> Any for Twhere T: 'static + ?Sized,

source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
source§

impl<T> Borrow<T> for Twhere T: ?Sized,

source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
source§

impl<T> BorrowMut<T> for Twhere T: ?Sized,

source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. 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 Twhere 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 Twhere T: Clone,

§

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 Twhere U: Into<T>,

§

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 Twhere U: TryFrom<T>,

§

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 Twhere T: for<'de> Deserialize<'de>,