pub struct COMMAND_INT_DATA {}
uavionix
only.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
impl COMMAND_INT_DATA
pub const ENCODED_LEN: usize = 35usize
pub const DEFAULT: Self
Trait Implementations§
Source§impl Clone for COMMAND_INT_DATA
impl Clone for COMMAND_INT_DATA
Source§fn clone(&self) -> COMMAND_INT_DATA
fn clone(&self) -> COMMAND_INT_DATA
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source
. Read more