#![doc = "This file was automatically generated, do not edit"]
use crate::MavlinkVersion;
use crate::{bytes::Bytes, bytes_mut::BytesMut, error::*, Message};
#[allow(unused_imports)]
use bitflags::bitflags;
#[allow(unused_imports)]
use heapless::Vec;
#[allow(unused_imports)]
use num_derive::FromPrimitive;
#[allow(unused_imports)]
use num_derive::ToPrimitive;
#[allow(unused_imports)]
use num_traits::FromPrimitive;
#[allow(unused_imports)]
use num_traits::ToPrimitive;
#[cfg(feature = "serde")]
use serde::{Deserialize, Serialize};
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum GoproCaptureMode {
#[doc = "Video mode."]
GOPRO_CAPTURE_MODE_VIDEO = 0,
#[doc = "Photo mode."]
GOPRO_CAPTURE_MODE_PHOTO = 1,
#[doc = "Burst mode, Hero 3+ only."]
GOPRO_CAPTURE_MODE_BURST = 2,
#[doc = "Time lapse mode, Hero 3+ only."]
GOPRO_CAPTURE_MODE_TIME_LAPSE = 3,
#[doc = "Multi shot mode, Hero 4 only."]
GOPRO_CAPTURE_MODE_MULTI_SHOT = 4,
#[doc = "Playback mode, Hero 4 only, silver only except when LCD or HDMI is connected to black."]
GOPRO_CAPTURE_MODE_PLAYBACK = 5,
#[doc = "Playback mode, Hero 4 only."]
GOPRO_CAPTURE_MODE_SETUP = 6,
#[doc = "Mode not yet known."]
GOPRO_CAPTURE_MODE_UNKNOWN = 255,
}
impl Default for GoproCaptureMode {
fn default() -> Self {
Self::GOPRO_CAPTURE_MODE_VIDEO
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "A mapping of sub flight modes for custom_mode field of heartbeat."]
pub enum SubMode {
SUB_MODE_STABILIZE = 0,
SUB_MODE_ACRO = 1,
SUB_MODE_ALT_HOLD = 2,
SUB_MODE_AUTO = 3,
SUB_MODE_GUIDED = 4,
SUB_MODE_CIRCLE = 7,
SUB_MODE_SURFACE = 9,
SUB_MODE_POSHOLD = 16,
SUB_MODE_MANUAL = 19,
}
impl Default for SubMode {
fn default() -> Self {
Self::SUB_MODE_STABILIZE
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "State flags for ADS-B transponder dynamic report"] pub struct UavionixAdsbOutDynamicState : u16 { const UAVIONIX_ADSB_OUT_DYNAMIC_STATE_INTENT_CHANGE = 1 ; const UAVIONIX_ADSB_OUT_DYNAMIC_STATE_AUTOPILOT_ENABLED = 2 ; const UAVIONIX_ADSB_OUT_DYNAMIC_STATE_NICBARO_CROSSCHECKED = 4 ; const UAVIONIX_ADSB_OUT_DYNAMIC_STATE_ON_GROUND = 8 ; const UAVIONIX_ADSB_OUT_DYNAMIC_STATE_IDENT = 16 ; } }
impl Default for UavionixAdsbOutDynamicState {
fn default() -> Self {
Self::UAVIONIX_ADSB_OUT_DYNAMIC_STATE_INTENT_CHANGE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Actuator output function. Values greater or equal to 1000 are autopilot-specific."]
pub enum ActuatorOutputFunction {
#[doc = "No function (disabled)."]
ACTUATOR_OUTPUT_FUNCTION_NONE = 0,
#[doc = "Motor 1"]
ACTUATOR_OUTPUT_FUNCTION_MOTOR1 = 1,
#[doc = "Motor 2"]
ACTUATOR_OUTPUT_FUNCTION_MOTOR2 = 2,
#[doc = "Motor 3"]
ACTUATOR_OUTPUT_FUNCTION_MOTOR3 = 3,
#[doc = "Motor 4"]
ACTUATOR_OUTPUT_FUNCTION_MOTOR4 = 4,
#[doc = "Motor 5"]
ACTUATOR_OUTPUT_FUNCTION_MOTOR5 = 5,
#[doc = "Motor 6"]
ACTUATOR_OUTPUT_FUNCTION_MOTOR6 = 6,
#[doc = "Motor 7"]
ACTUATOR_OUTPUT_FUNCTION_MOTOR7 = 7,
#[doc = "Motor 8"]
ACTUATOR_OUTPUT_FUNCTION_MOTOR8 = 8,
#[doc = "Motor 9"]
ACTUATOR_OUTPUT_FUNCTION_MOTOR9 = 9,
#[doc = "Motor 10"]
ACTUATOR_OUTPUT_FUNCTION_MOTOR10 = 10,
#[doc = "Motor 11"]
ACTUATOR_OUTPUT_FUNCTION_MOTOR11 = 11,
#[doc = "Motor 12"]
ACTUATOR_OUTPUT_FUNCTION_MOTOR12 = 12,
#[doc = "Motor 13"]
ACTUATOR_OUTPUT_FUNCTION_MOTOR13 = 13,
#[doc = "Motor 14"]
ACTUATOR_OUTPUT_FUNCTION_MOTOR14 = 14,
#[doc = "Motor 15"]
ACTUATOR_OUTPUT_FUNCTION_MOTOR15 = 15,
#[doc = "Motor 16"]
ACTUATOR_OUTPUT_FUNCTION_MOTOR16 = 16,
#[doc = "Servo 1"]
ACTUATOR_OUTPUT_FUNCTION_SERVO1 = 33,
#[doc = "Servo 2"]
ACTUATOR_OUTPUT_FUNCTION_SERVO2 = 34,
#[doc = "Servo 3"]
ACTUATOR_OUTPUT_FUNCTION_SERVO3 = 35,
#[doc = "Servo 4"]
ACTUATOR_OUTPUT_FUNCTION_SERVO4 = 36,
#[doc = "Servo 5"]
ACTUATOR_OUTPUT_FUNCTION_SERVO5 = 37,
#[doc = "Servo 6"]
ACTUATOR_OUTPUT_FUNCTION_SERVO6 = 38,
#[doc = "Servo 7"]
ACTUATOR_OUTPUT_FUNCTION_SERVO7 = 39,
#[doc = "Servo 8"]
ACTUATOR_OUTPUT_FUNCTION_SERVO8 = 40,
#[doc = "Servo 9"]
ACTUATOR_OUTPUT_FUNCTION_SERVO9 = 41,
#[doc = "Servo 10"]
ACTUATOR_OUTPUT_FUNCTION_SERVO10 = 42,
#[doc = "Servo 11"]
ACTUATOR_OUTPUT_FUNCTION_SERVO11 = 43,
#[doc = "Servo 12"]
ACTUATOR_OUTPUT_FUNCTION_SERVO12 = 44,
#[doc = "Servo 13"]
ACTUATOR_OUTPUT_FUNCTION_SERVO13 = 45,
#[doc = "Servo 14"]
ACTUATOR_OUTPUT_FUNCTION_SERVO14 = 46,
#[doc = "Servo 15"]
ACTUATOR_OUTPUT_FUNCTION_SERVO15 = 47,
#[doc = "Servo 16"]
ACTUATOR_OUTPUT_FUNCTION_SERVO16 = 48,
}
impl Default for ActuatorOutputFunction {
fn default() -> Self {
Self::ACTUATOR_OUTPUT_FUNCTION_NONE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum HeadingType {
HEADING_TYPE_COURSE_OVER_GROUND = 0,
HEADING_TYPE_HEADING = 1,
}
impl Default for HeadingType {
fn default() -> Self {
Self::HEADING_TYPE_COURSE_OVER_GROUND
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Generalized UAVCAN node mode"]
pub enum UavcanNodeMode {
#[doc = "The node is performing its primary functions."]
UAVCAN_NODE_MODE_OPERATIONAL = 0,
#[doc = "The node is initializing; this mode is entered immediately after startup."]
UAVCAN_NODE_MODE_INITIALIZATION = 1,
#[doc = "The node is under maintenance."]
UAVCAN_NODE_MODE_MAINTENANCE = 2,
#[doc = "The node is in the process of updating its software."]
UAVCAN_NODE_MODE_SOFTWARE_UPDATE = 3,
#[doc = "The node is no longer available online."]
UAVCAN_NODE_MODE_OFFLINE = 7,
}
impl Default for UavcanNodeMode {
fn default() -> Self {
Self::UAVCAN_NODE_MODE_OPERATIONAL
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum MavlinkDataStreamType {
MAVLINK_DATA_STREAM_IMG_JPEG = 0,
MAVLINK_DATA_STREAM_IMG_BMP = 1,
MAVLINK_DATA_STREAM_IMG_RAW8U = 2,
MAVLINK_DATA_STREAM_IMG_RAW32U = 3,
MAVLINK_DATA_STREAM_IMG_PGM = 4,
MAVLINK_DATA_STREAM_IMG_PNG = 5,
}
impl Default for MavlinkDataStreamType {
fn default() -> Self {
Self::MAVLINK_DATA_STREAM_IMG_JPEG
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Emergency status encoding"]
pub enum UavionixAdsbEmergencyStatus {
UAVIONIX_ADSB_OUT_NO_EMERGENCY = 0,
UAVIONIX_ADSB_OUT_GENERAL_EMERGENCY = 1,
UAVIONIX_ADSB_OUT_LIFEGUARD_EMERGENCY = 2,
UAVIONIX_ADSB_OUT_MINIMUM_FUEL_EMERGENCY = 3,
UAVIONIX_ADSB_OUT_NO_COMM_EMERGENCY = 4,
UAVIONIX_ADSB_OUT_UNLAWFUL_INTERFERANCE_EMERGENCY = 5,
UAVIONIX_ADSB_OUT_DOWNED_AIRCRAFT_EMERGENCY = 6,
UAVIONIX_ADSB_OUT_RESERVED = 7,
}
impl Default for UavionixAdsbEmergencyStatus {
fn default() -> Self {
Self::UAVIONIX_ADSB_OUT_NO_EMERGENCY
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Stream status flags (Bitmap)"]
pub enum VideoStreamStatusFlags {
#[doc = "Stream is active (running)"]
VIDEO_STREAM_STATUS_FLAGS_RUNNING = 1,
#[doc = "Stream is thermal imaging"]
VIDEO_STREAM_STATUS_FLAGS_THERMAL = 2,
}
impl Default for VideoStreamStatusFlags {
fn default() -> Self {
Self::VIDEO_STREAM_STATUS_FLAGS_RUNNING
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "Flags in RALLY_POINT message."] pub struct RallyFlags : u8 { # [doc = "Flag set when requiring favorable winds for landing."] const FAVORABLE_WIND = 1 ; # [doc = "Flag set when plane is to immediately descend to break altitude and land without GCS intervention. Flag not set when plane is to loiter at Rally point until commanded to land."] const LAND_IMMEDIATELY = 2 ; } }
impl Default for RallyFlags {
fn default() -> Self {
Self::FAVORABLE_WIND
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum LedControlPattern {
#[doc = "LED patterns off (return control to regular vehicle control)."]
LED_CONTROL_PATTERN_OFF = 0,
#[doc = "LEDs show pattern during firmware update."]
LED_CONTROL_PATTERN_FIRMWAREUPDATE = 1,
#[doc = "Custom Pattern using custom bytes fields."]
LED_CONTROL_PATTERN_CUSTOM = 255,
}
impl Default for LedControlPattern {
fn default() -> Self {
Self::LED_CONTROL_PATTERN_OFF
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Direction of VTOL transition"]
pub enum VtolTransitionHeading {
#[doc = "Respect the heading configuration of the vehicle."]
VTOL_TRANSITION_HEADING_VEHICLE_DEFAULT = 0,
#[doc = "Use the heading pointing towards the next waypoint."]
VTOL_TRANSITION_HEADING_NEXT_WAYPOINT = 1,
#[doc = "Use the heading on takeoff (while sitting on the ground)."]
VTOL_TRANSITION_HEADING_TAKEOFF = 2,
#[doc = "Use the specified heading in parameter 4."]
VTOL_TRANSITION_HEADING_SPECIFIED = 3,
#[doc = "Use the current heading when reaching takeoff altitude (potentially facing the wind when weather-vaning is active)."]
VTOL_TRANSITION_HEADING_ANY = 4,
}
impl Default for VtolTransitionHeading {
fn default() -> Self {
Self::VTOL_TRANSITION_HEADING_VEHICLE_DEFAULT
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "Bitmask of (optional) autopilot capabilities (64 bit). If a bit is set, the autopilot supports this capability."] pub struct MavProtocolCapability : u64 { # [doc = "Autopilot supports the MISSION_ITEM float message type. Note that MISSION_ITEM is deprecated, and autopilots should use MISSION_INT instead."] const MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT = 1 ; # [doc = "Autopilot supports the new param float message type."] const MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT = 2 ; # [doc = "Autopilot supports MISSION_ITEM_INT scaled integer message type. Note that this flag must always be set if missions are supported, because missions must always use MISSION_ITEM_INT (rather than MISSION_ITEM, which is deprecated)."] const MAV_PROTOCOL_CAPABILITY_MISSION_INT = 4 ; # [doc = "Autopilot supports COMMAND_INT scaled integer message type."] const MAV_PROTOCOL_CAPABILITY_COMMAND_INT = 8 ; # [doc = "Parameter protocol uses byte-wise encoding of parameter values into param_value (float) fields: https://mavlink.io/en/services/parameter.html#parameter-encoding. Note that either this flag or MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_C_CAST should be set if the parameter protocol is supported."] const MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_BYTEWISE = 16 ; # [doc = "Autopilot supports the File Transfer Protocol v1: https://mavlink.io/en/services/ftp.html."] const MAV_PROTOCOL_CAPABILITY_FTP = 32 ; # [doc = "Autopilot supports commanding attitude offboard."] const MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET = 64 ; # [doc = "Autopilot supports commanding position and velocity targets in local NED frame."] const MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED = 128 ; # [doc = "Autopilot supports commanding position and velocity targets in global scaled integers."] const MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT = 256 ; # [doc = "Autopilot supports terrain protocol / data handling."] const MAV_PROTOCOL_CAPABILITY_TERRAIN = 512 ; # [doc = "Autopilot supports direct actuator control."] const MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET = 1024 ; # [doc = "Autopilot supports the MAV_CMD_DO_FLIGHTTERMINATION command (flight termination)."] const MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION = 2048 ; # [doc = "Autopilot supports onboard compass calibration."] const MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION = 4096 ; # [doc = "Autopilot supports MAVLink version 2."] const MAV_PROTOCOL_CAPABILITY_MAVLINK2 = 8192 ; # [doc = "Autopilot supports mission fence protocol."] const MAV_PROTOCOL_CAPABILITY_MISSION_FENCE = 16384 ; # [doc = "Autopilot supports mission rally point protocol."] const MAV_PROTOCOL_CAPABILITY_MISSION_RALLY = 32768 ; # [doc = "Reserved for future use."] const MAV_PROTOCOL_CAPABILITY_RESERVED2 = 65536 ; # [doc = "Parameter protocol uses C-cast of parameter values to set the param_value (float) fields: https://mavlink.io/en/services/parameter.html#parameter-encoding. Note that either this flag or MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_BYTEWISE should be set if the parameter protocol is supported."] const MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_C_CAST = 131072 ; } }
impl Default for MavProtocolCapability {
fn default() -> Self {
Self::MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Type of landing target"]
pub enum LandingTargetType {
#[doc = "Landing target signaled by light beacon (ex: IR-LOCK)"]
LANDING_TARGET_TYPE_LIGHT_BEACON = 0,
#[doc = "Landing target signaled by radio beacon (ex: ILS, NDB)"]
LANDING_TARGET_TYPE_RADIO_BEACON = 1,
#[doc = "Landing target represented by a fiducial marker (ex: ARTag)"]
LANDING_TARGET_TYPE_VISION_FIDUCIAL = 2,
#[doc = "Landing target represented by a pre-defined visual shape/feature (ex: X-marker, H-marker, square)"]
LANDING_TARGET_TYPE_VISION_OTHER = 3,
}
impl Default for LandingTargetType {
fn default() -> Self {
Self::LANDING_TARGET_TYPE_LIGHT_BEACON
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Enumeration of battery functions"]
pub enum MavBatteryFunction {
#[doc = "Battery function is unknown"]
MAV_BATTERY_FUNCTION_UNKNOWN = 0,
#[doc = "Battery supports all flight systems"]
MAV_BATTERY_FUNCTION_ALL = 1,
#[doc = "Battery for the propulsion system"]
MAV_BATTERY_FUNCTION_PROPULSION = 2,
#[doc = "Avionics battery"]
MAV_BATTERY_FUNCTION_AVIONICS = 3,
#[doc = "Payload battery"]
MAV_BATTERY_FUNCTION_PAYLOAD = 4,
}
impl Default for MavBatteryFunction {
fn default() -> Self {
Self::MAV_BATTERY_FUNCTION_UNKNOWN
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "Transceiver RF control flags for ADS-B transponder dynamic reports"] pub struct UavionixAdsbOutRfSelect : u8 { const UAVIONIX_ADSB_OUT_RF_SELECT_STANDBY = 0 ; const UAVIONIX_ADSB_OUT_RF_SELECT_RX_ENABLED = 1 ; const UAVIONIX_ADSB_OUT_RF_SELECT_TX_ENABLED = 2 ; } }
impl Default for UavionixAdsbOutRfSelect {
fn default() -> Self {
Self::UAVIONIX_ADSB_OUT_RF_SELECT_STANDBY
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum MavOdidClassEu {
#[doc = "The class for the UA, according to the EU specification, is undeclared."]
MAV_ODID_CLASS_EU_UNDECLARED = 0,
#[doc = "The class for the UA, according to the EU specification, is Class 0."]
MAV_ODID_CLASS_EU_CLASS_0 = 1,
#[doc = "The class for the UA, according to the EU specification, is Class 1."]
MAV_ODID_CLASS_EU_CLASS_1 = 2,
#[doc = "The class for the UA, according to the EU specification, is Class 2."]
MAV_ODID_CLASS_EU_CLASS_2 = 3,
#[doc = "The class for the UA, according to the EU specification, is Class 3."]
MAV_ODID_CLASS_EU_CLASS_3 = 4,
#[doc = "The class for the UA, according to the EU specification, is Class 4."]
MAV_ODID_CLASS_EU_CLASS_4 = 5,
#[doc = "The class for the UA, according to the EU specification, is Class 5."]
MAV_ODID_CLASS_EU_CLASS_5 = 6,
#[doc = "The class for the UA, according to the EU specification, is Class 6."]
MAV_ODID_CLASS_EU_CLASS_6 = 7,
}
impl Default for MavOdidClassEu {
fn default() -> Self {
Self::MAV_ODID_CLASS_EU_UNDECLARED
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum MavOdidAuthType {
#[doc = "No authentication type is specified."]
MAV_ODID_AUTH_TYPE_NONE = 0,
#[doc = "Signature for the UAS (Unmanned Aircraft System) ID."]
MAV_ODID_AUTH_TYPE_UAS_ID_SIGNATURE = 1,
#[doc = "Signature for the Operator ID."]
MAV_ODID_AUTH_TYPE_OPERATOR_ID_SIGNATURE = 2,
#[doc = "Signature for the entire message set."]
MAV_ODID_AUTH_TYPE_MESSAGE_SET_SIGNATURE = 3,
#[doc = "Authentication is provided by Network Remote ID."]
MAV_ODID_AUTH_TYPE_NETWORK_REMOTE_ID = 4,
#[doc = "The exact authentication type is indicated by the first byte of authentication_data and these type values are managed by ICAO."]
MAV_ODID_AUTH_TYPE_SPECIFIC_AUTHENTICATION = 5,
}
impl Default for MavOdidAuthType {
fn default() -> Self {
Self::MAV_ODID_AUTH_TYPE_NONE
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "Flags in the HIL_SENSOR message indicate which fields have updated since the last message"] pub struct HilSensorUpdatedFlags : u32 { # [doc = "None of the fields in HIL_SENSOR have been updated"] const HIL_SENSOR_UPDATED_NONE = 0 ; # [doc = "The value in the xacc field has been updated"] const HIL_SENSOR_UPDATED_XACC = 1 ; # [doc = "The value in the yacc field has been updated"] const HIL_SENSOR_UPDATED_YACC = 2 ; # [doc = "The value in the zacc field has been updated"] const HIL_SENSOR_UPDATED_ZACC = 4 ; # [doc = "The value in the xgyro field has been updated"] const HIL_SENSOR_UPDATED_XGYRO = 8 ; # [doc = "The value in the ygyro field has been updated"] const HIL_SENSOR_UPDATED_YGYRO = 16 ; # [doc = "The value in the zgyro field has been updated"] const HIL_SENSOR_UPDATED_ZGYRO = 32 ; # [doc = "The value in the xmag field has been updated"] const HIL_SENSOR_UPDATED_XMAG = 64 ; # [doc = "The value in the ymag field has been updated"] const HIL_SENSOR_UPDATED_YMAG = 128 ; # [doc = "The value in the zmag field has been updated"] const HIL_SENSOR_UPDATED_ZMAG = 256 ; # [doc = "The value in the abs_pressure field has been updated"] const HIL_SENSOR_UPDATED_ABS_PRESSURE = 512 ; # [doc = "The value in the diff_pressure field has been updated"] const HIL_SENSOR_UPDATED_DIFF_PRESSURE = 1024 ; # [doc = "The value in the pressure_alt field has been updated"] const HIL_SENSOR_UPDATED_PRESSURE_ALT = 2048 ; # [doc = "The value in the temperature field has been updated"] const HIL_SENSOR_UPDATED_TEMPERATURE = 4096 ; # [doc = "Full reset of attitude/position/velocities/etc was performed in sim (Bit 31)."] const HIL_SENSOR_UPDATED_RESET = 2147483648 ; } }
impl Default for HilSensorUpdatedFlags {
fn default() -> Self {
Self::HIL_SENSOR_UPDATED_NONE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "RTK GPS baseline coordinate system, used for RTK corrections"]
pub enum RtkBaselineCoordinateSystem {
#[doc = "Earth-centered, Earth-fixed"]
RTK_BASELINE_COORDINATE_SYSTEM_ECEF = 0,
#[doc = "RTK basestation centered, north, east, down"]
RTK_BASELINE_COORDINATE_SYSTEM_NED = 1,
}
impl Default for RtkBaselineCoordinateSystem {
fn default() -> Self {
Self::RTK_BASELINE_COORDINATE_SYSTEM_ECEF
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum ScriptingCmd {
#[doc = "Start a REPL session."]
SCRIPTING_CMD_REPL_START = 0,
#[doc = "End a REPL session."]
SCRIPTING_CMD_REPL_STOP = 1,
#[doc = "Stop execution of scripts."]
SCRIPTING_CMD_STOP = 2,
#[doc = "Stop execution of scripts and restart."]
SCRIPTING_CMD_STOP_AND_RESTART = 3,
}
impl Default for ScriptingCmd {
fn default() -> Self {
Self::SCRIPTING_CMD_REPL_START
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "These flags indicate status such as data validity of each data source. Set = data valid"] pub struct AdsbFlags : u16 { const ADSB_FLAGS_VALID_COORDS = 1 ; const ADSB_FLAGS_VALID_ALTITUDE = 2 ; const ADSB_FLAGS_VALID_HEADING = 4 ; const ADSB_FLAGS_VALID_VELOCITY = 8 ; const ADSB_FLAGS_VALID_CALLSIGN = 16 ; const ADSB_FLAGS_VALID_SQUAWK = 32 ; const ADSB_FLAGS_SIMULATED = 64 ; const ADSB_FLAGS_VERTICAL_VELOCITY_VALID = 128 ; const ADSB_FLAGS_BARO_VALID = 256 ; const ADSB_FLAGS_SOURCE_UAT = 32768 ; } }
impl Default for AdsbFlags {
fn default() -> Self {
Self::ADSB_FLAGS_VALID_COORDS
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum MavOdidVerAcc {
#[doc = "The vertical accuracy is unknown."]
MAV_ODID_VER_ACC_UNKNOWN = 0,
#[doc = "The vertical accuracy is smaller than 150 meter."]
MAV_ODID_VER_ACC_150_METER = 1,
#[doc = "The vertical accuracy is smaller than 45 meter."]
MAV_ODID_VER_ACC_45_METER = 2,
#[doc = "The vertical accuracy is smaller than 25 meter."]
MAV_ODID_VER_ACC_25_METER = 3,
#[doc = "The vertical accuracy is smaller than 10 meter."]
MAV_ODID_VER_ACC_10_METER = 4,
#[doc = "The vertical accuracy is smaller than 3 meter."]
MAV_ODID_VER_ACC_3_METER = 5,
#[doc = "The vertical accuracy is smaller than 1 meter."]
MAV_ODID_VER_ACC_1_METER = 6,
}
impl Default for MavOdidVerAcc {
fn default() -> Self {
Self::MAV_ODID_VER_ACC_UNKNOWN
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Actions for reading/writing parameters between persistent and volatile storage when using MAV_CMD_PREFLIGHT_STORAGE. (Commonly parameters are loaded from persistent storage (flash/EEPROM) into volatile storage (RAM) on startup and written back when they are changed.)"]
pub enum PreflightStorageParameterAction {
#[doc = "Read all parameters from persistent storage. Replaces values in volatile storage."]
PARAM_READ_PERSISTENT = 0,
#[doc = "Write all parameter values to persistent storage (flash/EEPROM)"]
PARAM_WRITE_PERSISTENT = 1,
#[doc = "Reset all user configurable parameters to their default value (including airframe selection, sensor calibration data, safety settings, and so on). Does not reset values that contain operation counters and vehicle computed statistics."]
PARAM_RESET_CONFIG_DEFAULT = 2,
#[doc = "Reset only sensor calibration parameters to factory defaults (or firmware default if not available)"]
PARAM_RESET_SENSOR_DEFAULT = 3,
#[doc = "Reset all parameters, including operation counters, to default values"]
PARAM_RESET_ALL_DEFAULT = 4,
}
impl Default for PreflightStorageParameterAction {
fn default() -> Self {
Self::PARAM_READ_PERSISTENT
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Parachute actions. Trigger release and enable/disable auto-release."]
pub enum ParachuteAction {
#[doc = "Disable auto-release of parachute (i.e. release triggered by crash detectors)."]
PARACHUTE_DISABLE = 0,
#[doc = "Enable auto-release of parachute."]
PARACHUTE_ENABLE = 1,
#[doc = "Release parachute and kill motors."]
PARACHUTE_RELEASE = 2,
}
impl Default for ParachuteAction {
fn default() -> Self {
Self::PARACHUTE_DISABLE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Camera tracking modes"]
pub enum CameraTrackingMode {
#[doc = "Not tracking"]
CAMERA_TRACKING_MODE_NONE = 0,
#[doc = "Target is a point"]
CAMERA_TRACKING_MODE_POINT = 1,
#[doc = "Target is a rectangle"]
CAMERA_TRACKING_MODE_RECTANGLE = 2,
}
impl Default for CameraTrackingMode {
fn default() -> Self {
Self::CAMERA_TRACKING_MODE_NONE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Camera Modes."]
pub enum CameraMode {
#[doc = "Camera is in image/photo capture mode."]
CAMERA_MODE_IMAGE = 0,
#[doc = "Camera is in video capture mode."]
CAMERA_MODE_VIDEO = 1,
#[doc = "Camera is in image survey capture mode. It allows for camera controller to do specific settings for surveys."]
CAMERA_MODE_IMAGE_SURVEY = 2,
}
impl Default for CameraMode {
fn default() -> Self {
Self::CAMERA_MODE_IMAGE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Supported component metadata types. These are used in the \"general\" metadata file returned by COMPONENT_METADATA to provide information about supported metadata types. The types are not used directly in MAVLink messages."]
pub enum CompMetadataType {
#[doc = "General information about the component. General metadata includes information about other metadata types supported by the component. Files of this type must be supported, and must be downloadable from vehicle using a MAVLink FTP URI."]
COMP_METADATA_TYPE_GENERAL = 0,
#[doc = "Parameter meta data."]
COMP_METADATA_TYPE_PARAMETER = 1,
#[doc = "Meta data that specifies which commands and command parameters the vehicle supports. (WIP)"]
COMP_METADATA_TYPE_COMMANDS = 2,
#[doc = "Meta data that specifies external non-MAVLink peripherals."]
COMP_METADATA_TYPE_PERIPHERALS = 3,
#[doc = "Meta data for the events interface."]
COMP_METADATA_TYPE_EVENTS = 4,
#[doc = "Meta data for actuator configuration (motors, servos and vehicle geometry) and testing."]
COMP_METADATA_TYPE_ACTUATORS = 5,
}
impl Default for CompMetadataType {
fn default() -> Self {
Self::COMP_METADATA_TYPE_GENERAL
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "The ROI (region of interest) for the vehicle. This can be be used by the vehicle for camera/vehicle attitude alignment (see MAV_CMD_NAV_ROI)."]
pub enum MavRoi {
#[doc = "No region of interest."]
MAV_ROI_NONE = 0,
#[doc = "Point toward next waypoint, with optional pitch/roll/yaw offset."]
MAV_ROI_WPNEXT = 1,
#[doc = "Point toward given waypoint."]
MAV_ROI_WPINDEX = 2,
#[doc = "Point toward fixed location."]
MAV_ROI_LOCATION = 3,
#[doc = "Point toward of given id."]
MAV_ROI_TARGET = 4,
}
impl Default for MavRoi {
fn default() -> Self {
Self::MAV_ROI_NONE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Result from PARAM_EXT_SET message (or a PARAM_SET within a transaction)."]
pub enum ParamAck {
#[doc = "Parameter value ACCEPTED and SET"]
PARAM_ACK_ACCEPTED = 0,
#[doc = "Parameter value UNKNOWN/UNSUPPORTED"]
PARAM_ACK_VALUE_UNSUPPORTED = 1,
#[doc = "Parameter failed to set"]
PARAM_ACK_FAILED = 2,
#[doc = "Parameter value received but not yet set/accepted. A subsequent PARAM_ACK_TRANSACTION or PARAM_EXT_ACK with the final result will follow once operation is completed. This is returned immediately for parameters that take longer to set, indicating that the the parameter was received and does not need to be resent."]
PARAM_ACK_IN_PROGRESS = 3,
}
impl Default for ParamAck {
fn default() -> Self {
Self::PARAM_ACK_ACCEPTED
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Micro air vehicle / autopilot classes. This identifies the individual model."]
pub enum MavAutopilot {
#[doc = "Generic autopilot, full support for everything"]
MAV_AUTOPILOT_GENERIC = 0,
#[doc = "Reserved for future use."]
MAV_AUTOPILOT_RESERVED = 1,
#[doc = "SLUGS autopilot, http://slugsuav.soe.ucsc.edu"]
MAV_AUTOPILOT_SLUGS = 2,
#[doc = "ArduPilot - Plane/Copter/Rover/Sub/Tracker, https://ardupilot.org"]
MAV_AUTOPILOT_ARDUPILOTMEGA = 3,
#[doc = "OpenPilot, http://openpilot.org"]
MAV_AUTOPILOT_OPENPILOT = 4,
#[doc = "Generic autopilot only supporting simple waypoints"]
MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY = 5,
#[doc = "Generic autopilot supporting waypoints and other simple navigation commands"]
MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY = 6,
#[doc = "Generic autopilot supporting the full mission command set"]
MAV_AUTOPILOT_GENERIC_MISSION_FULL = 7,
#[doc = "No valid autopilot, e.g. a GCS or other MAVLink component"]
MAV_AUTOPILOT_INVALID = 8,
#[doc = "PPZ UAV - http://nongnu.org/paparazzi"]
MAV_AUTOPILOT_PPZ = 9,
#[doc = "UAV Dev Board"]
MAV_AUTOPILOT_UDB = 10,
#[doc = "FlexiPilot"]
MAV_AUTOPILOT_FP = 11,
#[doc = "PX4 Autopilot - http://px4.io/"]
MAV_AUTOPILOT_PX4 = 12,
#[doc = "SMACCMPilot - http://smaccmpilot.org"]
MAV_AUTOPILOT_SMACCMPILOT = 13,
#[doc = "AutoQuad -- http://autoquad.org"]
MAV_AUTOPILOT_AUTOQUAD = 14,
#[doc = "Armazila -- http://armazila.com"]
MAV_AUTOPILOT_ARMAZILA = 15,
#[doc = "Aerob -- http://aerob.ru"]
MAV_AUTOPILOT_AEROB = 16,
#[doc = "ASLUAV autopilot -- http://www.asl.ethz.ch"]
MAV_AUTOPILOT_ASLUAV = 17,
#[doc = "SmartAP Autopilot - http://sky-drones.com"]
MAV_AUTOPILOT_SMARTAP = 18,
#[doc = "AirRails - http://uaventure.com"]
MAV_AUTOPILOT_AIRRAILS = 19,
#[doc = "Fusion Reflex - https://fusion.engineering"]
MAV_AUTOPILOT_REFLEX = 20,
}
impl Default for MavAutopilot {
fn default() -> Self {
Self::MAV_AUTOPILOT_GENERIC
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "These flags are used in the AIS_VESSEL.fields bitmask to indicate validity of data in the other message fields. When set, the data is valid."] pub struct AisFlags : u16 { # [doc = "1 = Position accuracy less than 10m, 0 = position accuracy greater than 10m."] const AIS_FLAGS_POSITION_ACCURACY = 1 ; const AIS_FLAGS_VALID_COG = 2 ; const AIS_FLAGS_VALID_VELOCITY = 4 ; # [doc = "1 = Velocity over 52.5765m/s (102.2 knots)"] const AIS_FLAGS_HIGH_VELOCITY = 8 ; const AIS_FLAGS_VALID_TURN_RATE = 16 ; # [doc = "Only the sign of the returned turn rate value is valid, either greater than 5deg/30s or less than -5deg/30s"] const AIS_FLAGS_TURN_RATE_SIGN_ONLY = 32 ; const AIS_FLAGS_VALID_DIMENSIONS = 64 ; # [doc = "Distance to bow is larger than 511m"] const AIS_FLAGS_LARGE_BOW_DIMENSION = 128 ; # [doc = "Distance to stern is larger than 511m"] const AIS_FLAGS_LARGE_STERN_DIMENSION = 256 ; # [doc = "Distance to port side is larger than 63m"] const AIS_FLAGS_LARGE_PORT_DIMENSION = 512 ; # [doc = "Distance to starboard side is larger than 63m"] const AIS_FLAGS_LARGE_STARBOARD_DIMENSION = 1024 ; const AIS_FLAGS_VALID_CALLSIGN = 2048 ; const AIS_FLAGS_VALID_NAME = 4096 ; } }
impl Default for AisFlags {
fn default() -> Self {
Self::AIS_FLAGS_POSITION_ACCURACY
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum NavVtolLandOptions {
#[doc = "Default autopilot landing behaviour."]
NAV_VTOL_LAND_OPTIONS_DEFAULT = 0,
#[doc = "Descend in fixed wing mode, transitioning to multicopter mode for vertical landing when close to the ground. The fixed wing descent pattern is at the discretion of the vehicle (e.g. transition altitude, loiter direction, radius, and speed, etc.)."]
NAV_VTOL_LAND_OPTIONS_FW_DESCENT = 1,
#[doc = "Land in multicopter mode on reaching the landing coordinates (the whole landing is by \"hover descent\")."]
NAV_VTOL_LAND_OPTIONS_HOVER_DESCENT = 2,
}
impl Default for NavVtolLandOptions {
fn default() -> Self {
Self::NAV_VTOL_LAND_OPTIONS_DEFAULT
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "GPS lataral offset encoding"]
pub enum UavionixAdsbOutCfgGpsOffsetLat {
UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_NO_DATA = 0,
UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_LEFT_2M = 1,
UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_LEFT_4M = 2,
UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_LEFT_6M = 3,
UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_0M = 4,
UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_2M = 5,
UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_4M = 6,
UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_6M = 7,
}
impl Default for UavionixAdsbOutCfgGpsOffsetLat {
fn default() -> Self {
Self::UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_NO_DATA
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Navigational status of AIS vessel, enum duplicated from AIS standard, https://gpsd.gitlab.io/gpsd/AIVDM.html"]
pub enum AisNavStatus {
#[doc = "Under way using engine."]
UNDER_WAY = 0,
AIS_NAV_ANCHORED = 1,
AIS_NAV_UN_COMMANDED = 2,
AIS_NAV_RESTRICTED_MANOEUVERABILITY = 3,
AIS_NAV_DRAUGHT_CONSTRAINED = 4,
AIS_NAV_MOORED = 5,
AIS_NAV_AGROUND = 6,
AIS_NAV_FISHING = 7,
AIS_NAV_SAILING = 8,
AIS_NAV_RESERVED_HSC = 9,
AIS_NAV_RESERVED_WIG = 10,
AIS_NAV_RESERVED_1 = 11,
AIS_NAV_RESERVED_2 = 12,
AIS_NAV_RESERVED_3 = 13,
#[doc = "Search And Rescue Transponder."]
AIS_NAV_AIS_SART = 14,
#[doc = "Not available (default)."]
AIS_NAV_UNKNOWN = 15,
}
impl Default for AisNavStatus {
fn default() -> Self {
Self::UNDER_WAY
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum GoproRequestStatus {
#[doc = "The write message with ID indicated succeeded."]
GOPRO_REQUEST_SUCCESS = 0,
#[doc = "The write message with ID indicated failed."]
GOPRO_REQUEST_FAILED = 1,
}
impl Default for GoproRequestStatus {
fn default() -> Self {
Self::GOPRO_REQUEST_SUCCESS
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum GoproFieldOfView {
#[doc = "0x00: Wide."]
GOPRO_FIELD_OF_VIEW_WIDE = 0,
#[doc = "0x01: Medium."]
GOPRO_FIELD_OF_VIEW_MEDIUM = 1,
#[doc = "0x02: Narrow."]
GOPRO_FIELD_OF_VIEW_NARROW = 2,
}
impl Default for GoproFieldOfView {
fn default() -> Self {
Self::GOPRO_FIELD_OF_VIEW_WIDE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum MavCmdDoAuxFunctionSwitchLevel {
#[doc = "Switch Low."]
MAV_CMD_DO_AUX_FUNCTION_SWITCH_LEVEL_LOW = 0,
#[doc = "Switch Middle."]
MAV_CMD_DO_AUX_FUNCTION_SWITCH_LEVEL_MIDDLE = 1,
#[doc = "Switch High."]
MAV_CMD_DO_AUX_FUNCTION_SWITCH_LEVEL_HIGH = 2,
}
impl Default for MavCmdDoAuxFunctionSwitchLevel {
fn default() -> Self {
Self::MAV_CMD_DO_AUX_FUNCTION_SWITCH_LEVEL_LOW
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Video stream types"]
pub enum VideoStreamType {
#[doc = "Stream is RTSP"]
VIDEO_STREAM_TYPE_RTSP = 0,
#[doc = "Stream is RTP UDP (URI gives the port number)"]
VIDEO_STREAM_TYPE_RTPUDP = 1,
#[doc = "Stream is MPEG on TCP"]
VIDEO_STREAM_TYPE_TCP_MPEG = 2,
#[doc = "Stream is h.264 on MPEG TS (URI gives the port number)"]
VIDEO_STREAM_TYPE_MPEG_TS_H264 = 3,
}
impl Default for VideoStreamType {
fn default() -> Self {
Self::VIDEO_STREAM_TYPE_RTSP
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum PidTuningAxis {
PID_TUNING_ROLL = 1,
PID_TUNING_PITCH = 2,
PID_TUNING_YAW = 3,
PID_TUNING_ACCZ = 4,
PID_TUNING_STEER = 5,
PID_TUNING_LANDING = 6,
}
impl Default for PidTuningAxis {
fn default() -> Self {
Self::PID_TUNING_ROLL
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum MavOdidHeightRef {
#[doc = "The height field is relative to the take-off location."]
MAV_ODID_HEIGHT_REF_OVER_TAKEOFF = 0,
#[doc = "The height field is relative to ground."]
MAV_ODID_HEIGHT_REF_OVER_GROUND = 1,
}
impl Default for MavOdidHeightRef {
fn default() -> Self {
Self::MAV_ODID_HEIGHT_REF_OVER_TAKEOFF
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "Winch status flags used in WINCH_STATUS"] pub struct MavWinchStatusFlag : u32 { # [doc = "Winch is healthy"] const MAV_WINCH_STATUS_HEALTHY = 1 ; # [doc = "Winch line is fully retracted"] const MAV_WINCH_STATUS_FULLY_RETRACTED = 2 ; # [doc = "Winch motor is moving"] const MAV_WINCH_STATUS_MOVING = 4 ; # [doc = "Winch clutch is engaged allowing motor to move freely."] const MAV_WINCH_STATUS_CLUTCH_ENGAGED = 8 ; # [doc = "Winch is locked by locking mechanism."] const MAV_WINCH_STATUS_LOCKED = 16 ; # [doc = "Winch is gravity dropping payload."] const MAV_WINCH_STATUS_DROPPING = 32 ; # [doc = "Winch is arresting payload descent."] const MAV_WINCH_STATUS_ARRESTING = 64 ; # [doc = "Winch is using torque measurements to sense the ground."] const MAV_WINCH_STATUS_GROUND_SENSE = 128 ; # [doc = "Winch is returning to the fully retracted position."] const MAV_WINCH_STATUS_RETRACTING = 256 ; # [doc = "Winch is redelivering the payload. This is a failover state if the line tension goes above a threshold during RETRACTING."] const MAV_WINCH_STATUS_REDELIVER = 512 ; # [doc = "Winch is abandoning the line and possibly payload. Winch unspools the entire calculated line length. This is a failover state from REDELIVER if the number of attempts exceeds a threshold."] const MAV_WINCH_STATUS_ABANDON_LINE = 1024 ; # [doc = "Winch is engaging the locking mechanism."] const MAV_WINCH_STATUS_LOCKING = 2048 ; # [doc = "Winch is spooling on line."] const MAV_WINCH_STATUS_LOAD_LINE = 4096 ; # [doc = "Winch is loading a payload."] const MAV_WINCH_STATUS_LOAD_PAYLOAD = 8192 ; } }
impl Default for MavWinchStatusFlag {
fn default() -> Self {
Self::MAV_WINCH_STATUS_HEALTHY
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Actuator configuration, used to change a setting on an actuator. Component information metadata can be used to know which outputs support which commands."]
pub enum ActuatorConfiguration {
#[doc = "Do nothing."]
ACTUATOR_CONFIGURATION_NONE = 0,
#[doc = "Command the actuator to beep now."]
ACTUATOR_CONFIGURATION_BEEP = 1,
#[doc = "Permanently set the actuator (ESC) to 3D mode (reversible thrust)."]
ACTUATOR_CONFIGURATION_3D_MODE_ON = 2,
#[doc = "Permanently set the actuator (ESC) to non 3D mode (non-reversible thrust)."]
ACTUATOR_CONFIGURATION_3D_MODE_OFF = 3,
#[doc = "Permanently set the actuator (ESC) to spin direction 1 (which can be clockwise or counter-clockwise)."]
ACTUATOR_CONFIGURATION_SPIN_DIRECTION1 = 4,
#[doc = "Permanently set the actuator (ESC) to spin direction 2 (opposite of direction 1)."]
ACTUATOR_CONFIGURATION_SPIN_DIRECTION2 = 5,
}
impl Default for ActuatorConfiguration {
fn default() -> Self {
Self::ACTUATOR_CONFIGURATION_NONE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Possible remote log data block statuses."]
pub enum MavRemoteLogDataBlockStatuses {
#[doc = "This block has NOT been received."]
MAV_REMOTE_LOG_DATA_BLOCK_NACK = 0,
#[doc = "This block has been received."]
MAV_REMOTE_LOG_DATA_BLOCK_ACK = 1,
}
impl Default for MavRemoteLogDataBlockStatuses {
fn default() -> Self {
Self::MAV_REMOTE_LOG_DATA_BLOCK_NACK
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Bus types for device operations."]
pub enum DeviceOpBustype {
#[doc = "I2C Device operation."]
DEVICE_OP_BUSTYPE_I2C = 0,
#[doc = "SPI Device operation."]
DEVICE_OP_BUSTYPE_SPI = 1,
}
impl Default for DeviceOpBustype {
fn default() -> Self {
Self::DEVICE_OP_BUSTYPE_I2C
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "Gimbal manager high level capability flags (bitmap). The first 16 bits are identical to the GIMBAL_DEVICE_CAP_FLAGS. However, the gimbal manager does not need to copy the flags from the gimbal but can also enhance the capabilities and thus add flags."] pub struct GimbalManagerCapFlags : u32 { # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT = 1 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_NEUTRAL = 2 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_AXIS = 4 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_FOLLOW = 8 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_LOCK = 16 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_AXIS = 32 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_FOLLOW = 64 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_LOCK = 128 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_AXIS = 256 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_FOLLOW = 512 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_LOCK = 1024 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW."] const GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_INFINITE_YAW = 2048 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME."] const GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME = 4096 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_RC_INPUTS = 8192 ; # [doc = "Gimbal manager supports to point to a local position."] const GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_LOCAL = 65536 ; # [doc = "Gimbal manager supports to point to a global latitude, longitude, altitude position."] const GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_GLOBAL = 131072 ; } }
impl Default for GimbalManagerCapFlags {
fn default() -> Self {
Self::GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "Flags to report ESC failures."] pub struct EscFailureFlags : u16 { # [doc = "No ESC failure."] const ESC_FAILURE_NONE = 0 ; # [doc = "Over current failure."] const ESC_FAILURE_OVER_CURRENT = 1 ; # [doc = "Over voltage failure."] const ESC_FAILURE_OVER_VOLTAGE = 2 ; # [doc = "Over temperature failure."] const ESC_FAILURE_OVER_TEMPERATURE = 4 ; # [doc = "Over RPM failure."] const ESC_FAILURE_OVER_RPM = 8 ; # [doc = "Inconsistent command failure i.e. out of bounds."] const ESC_FAILURE_INCONSISTENT_CMD = 16 ; # [doc = "Motor stuck failure."] const ESC_FAILURE_MOTOR_STUCK = 32 ; # [doc = "Generic ESC failure."] const ESC_FAILURE_GENERIC = 64 ; } }
impl Default for EscFailureFlags {
fn default() -> Self {
Self::ESC_FAILURE_NONE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Source of information about this collision."]
pub enum MavCollisionSrc {
#[doc = "ID field references ADSB_VEHICLE packets"]
MAV_COLLISION_SRC_ADSB = 0,
#[doc = "ID field references MAVLink SRC ID"]
MAV_COLLISION_SRC_MAVLINK_GPS_GLOBAL_INT = 1,
}
impl Default for MavCollisionSrc {
fn default() -> Self {
Self::MAV_COLLISION_SRC_ADSB
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "SERIAL_CONTROL flags (bitmask)"] pub struct SerialControlFlag : u8 { # [doc = "Set if this is a reply"] const SERIAL_CONTROL_FLAG_REPLY = 1 ; # [doc = "Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message"] const SERIAL_CONTROL_FLAG_RESPOND = 2 ; # [doc = "Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set"] const SERIAL_CONTROL_FLAG_EXCLUSIVE = 4 ; # [doc = "Block on writes to the serial port"] const SERIAL_CONTROL_FLAG_BLOCKING = 8 ; # [doc = "Send multiple replies until port is drained"] const SERIAL_CONTROL_FLAG_MULTI = 16 ; } }
impl Default for SerialControlFlag {
fn default() -> Self {
Self::SERIAL_CONTROL_FLAG_REPLY
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "Flags for CURRENT_EVENT_SEQUENCE."] pub struct MavEventCurrentSequenceFlags : u8 { # [doc = "A sequence reset has happened (e.g. vehicle reboot)."] const MAV_EVENT_CURRENT_SEQUENCE_FLAGS_RESET = 1 ; } }
impl Default for MavEventCurrentSequenceFlags {
fn default() -> Self {
Self::MAV_EVENT_CURRENT_SEQUENCE_FLAGS_RESET
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum MavOdidCategoryEu {
#[doc = "The category for the UA, according to the EU specification, is undeclared."]
MAV_ODID_CATEGORY_EU_UNDECLARED = 0,
#[doc = "The category for the UA, according to the EU specification, is the Open category."]
MAV_ODID_CATEGORY_EU_OPEN = 1,
#[doc = "The category for the UA, according to the EU specification, is the Specific category."]
MAV_ODID_CATEGORY_EU_SPECIFIC = 2,
#[doc = "The category for the UA, according to the EU specification, is the Certified category."]
MAV_ODID_CATEGORY_EU_CERTIFIED = 3,
}
impl Default for MavOdidCategoryEu {
fn default() -> Self {
Self::MAV_ODID_CATEGORY_EU_UNDECLARED
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Yaw behaviour during orbit flight."]
pub enum OrbitYawBehaviour {
#[doc = "Vehicle front points to the center (default)."]
ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER = 0,
#[doc = "Vehicle front holds heading when message received."]
ORBIT_YAW_BEHAVIOUR_HOLD_INITIAL_HEADING = 1,
#[doc = "Yaw uncontrolled."]
ORBIT_YAW_BEHAVIOUR_UNCONTROLLED = 2,
#[doc = "Vehicle front follows flight path (tangential to circle)."]
ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TANGENT_TO_CIRCLE = 3,
#[doc = "Yaw controlled by RC input."]
ORBIT_YAW_BEHAVIOUR_RC_CONTROLLED = 4,
}
impl Default for OrbitYawBehaviour {
fn default() -> Self {
Self::ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum MavTunnelPayloadType {
#[doc = "Encoding of payload unknown."]
MAV_TUNNEL_PAYLOAD_TYPE_UNKNOWN = 0,
#[doc = "Registered for STorM32 gimbal controller."]
MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED0 = 200,
#[doc = "Registered for STorM32 gimbal controller."]
MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED1 = 201,
#[doc = "Registered for STorM32 gimbal controller."]
MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED2 = 202,
#[doc = "Registered for STorM32 gimbal controller."]
MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED3 = 203,
#[doc = "Registered for STorM32 gimbal controller."]
MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED4 = 204,
#[doc = "Registered for STorM32 gimbal controller."]
MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED5 = 205,
#[doc = "Registered for STorM32 gimbal controller."]
MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED6 = 206,
#[doc = "Registered for STorM32 gimbal controller."]
MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED7 = 207,
#[doc = "Registered for STorM32 gimbal controller."]
MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED8 = 208,
#[doc = "Registered for STorM32 gimbal controller."]
MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED9 = 209,
}
impl Default for MavTunnelPayloadType {
fn default() -> Self {
Self::MAV_TUNNEL_PAYLOAD_TYPE_UNKNOWN
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "List of possible units where failures can be injected."]
pub enum FailureUnit {
FAILURE_UNIT_SENSOR_GYRO = 0,
FAILURE_UNIT_SENSOR_ACCEL = 1,
FAILURE_UNIT_SENSOR_MAG = 2,
FAILURE_UNIT_SENSOR_BARO = 3,
FAILURE_UNIT_SENSOR_GPS = 4,
FAILURE_UNIT_SENSOR_OPTICAL_FLOW = 5,
FAILURE_UNIT_SENSOR_VIO = 6,
FAILURE_UNIT_SENSOR_DISTANCE_SENSOR = 7,
FAILURE_UNIT_SENSOR_AIRSPEED = 8,
FAILURE_UNIT_SYSTEM_BATTERY = 100,
FAILURE_UNIT_SYSTEM_MOTOR = 101,
FAILURE_UNIT_SYSTEM_SERVO = 102,
FAILURE_UNIT_SYSTEM_AVOIDANCE = 103,
FAILURE_UNIT_SYSTEM_RC_SIGNAL = 104,
FAILURE_UNIT_SYSTEM_MAVLINK_SIGNAL = 105,
}
impl Default for FailureUnit {
fn default() -> Self {
Self::FAILURE_UNIT_SENSOR_GYRO
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Camera tracking status flags"]
pub enum CameraTrackingStatusFlags {
#[doc = "Camera is not tracking"]
CAMERA_TRACKING_STATUS_FLAGS_IDLE = 0,
#[doc = "Camera is tracking"]
CAMERA_TRACKING_STATUS_FLAGS_ACTIVE = 1,
#[doc = "Camera tracking in error state"]
CAMERA_TRACKING_STATUS_FLAGS_ERROR = 2,
}
impl Default for CameraTrackingStatusFlags {
fn default() -> Self {
Self::CAMERA_TRACKING_STATUS_FLAGS_IDLE
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "These encode the sensors whose status is sent as part of the SYS_STATUS message."] pub struct MavSysStatusSensor : u32 { # [doc = "0x01 3D gyro"] const MAV_SYS_STATUS_SENSOR_3D_GYRO = 1 ; # [doc = "0x02 3D accelerometer"] const MAV_SYS_STATUS_SENSOR_3D_ACCEL = 2 ; # [doc = "0x04 3D magnetometer"] const MAV_SYS_STATUS_SENSOR_3D_MAG = 4 ; # [doc = "0x08 absolute pressure"] const MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE = 8 ; # [doc = "0x10 differential pressure"] const MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE = 16 ; # [doc = "0x20 GPS"] const MAV_SYS_STATUS_SENSOR_GPS = 32 ; # [doc = "0x40 optical flow"] const MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW = 64 ; # [doc = "0x80 computer vision position"] const MAV_SYS_STATUS_SENSOR_VISION_POSITION = 128 ; # [doc = "0x100 laser based position"] const MAV_SYS_STATUS_SENSOR_LASER_POSITION = 256 ; # [doc = "0x200 external ground truth (Vicon or Leica)"] const MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH = 512 ; # [doc = "0x400 3D angular rate control"] const MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL = 1024 ; # [doc = "0x800 attitude stabilization"] const MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION = 2048 ; # [doc = "0x1000 yaw position"] const MAV_SYS_STATUS_SENSOR_YAW_POSITION = 4096 ; # [doc = "0x2000 z/altitude control"] const MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL = 8192 ; # [doc = "0x4000 x/y position control"] const MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL = 16384 ; # [doc = "0x8000 motor outputs / control"] const MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS = 32768 ; # [doc = "0x10000 rc receiver"] const MAV_SYS_STATUS_SENSOR_RC_RECEIVER = 65536 ; # [doc = "0x20000 2nd 3D gyro"] const MAV_SYS_STATUS_SENSOR_3D_GYRO2 = 131072 ; # [doc = "0x40000 2nd 3D accelerometer"] const MAV_SYS_STATUS_SENSOR_3D_ACCEL2 = 262144 ; # [doc = "0x80000 2nd 3D magnetometer"] const MAV_SYS_STATUS_SENSOR_3D_MAG2 = 524288 ; # [doc = "0x100000 geofence"] const MAV_SYS_STATUS_GEOFENCE = 1048576 ; # [doc = "0x200000 AHRS subsystem health"] const MAV_SYS_STATUS_AHRS = 2097152 ; # [doc = "0x400000 Terrain subsystem health"] const MAV_SYS_STATUS_TERRAIN = 4194304 ; # [doc = "0x800000 Motors are reversed"] const MAV_SYS_STATUS_REVERSE_MOTOR = 8388608 ; # [doc = "0x1000000 Logging"] const MAV_SYS_STATUS_LOGGING = 16777216 ; # [doc = "0x2000000 Battery"] const MAV_SYS_STATUS_SENSOR_BATTERY = 33554432 ; # [doc = "0x4000000 Proximity"] const MAV_SYS_STATUS_SENSOR_PROXIMITY = 67108864 ; # [doc = "0x8000000 Satellite Communication"] const MAV_SYS_STATUS_SENSOR_SATCOM = 134217728 ; # [doc = "0x10000000 pre-arm check status. Always healthy when armed"] const MAV_SYS_STATUS_PREARM_CHECK = 268435456 ; # [doc = "0x20000000 Avoidance/collision prevention"] const MAV_SYS_STATUS_OBSTACLE_AVOIDANCE = 536870912 ; # [doc = "0x40000000 propulsion (actuator, esc, motor or propellor)"] const MAV_SYS_STATUS_SENSOR_PROPULSION = 1073741824 ; # [doc = "0x80000000 Extended bit-field are used for further sensor status bits (needs to be set in onboard_control_sensors_present only)"] const MAV_SYS_STATUS_EXTENSION_USED = 2147483648 ; } }
impl Default for MavSysStatusSensor {
fn default() -> Self {
Self::MAV_SYS_STATUS_SENSOR_3D_GYRO
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "Flags for the global position report."] pub struct UtmDataAvailFlags : u8 { # [doc = "The field time contains valid data."] const UTM_DATA_AVAIL_FLAGS_TIME_VALID = 1 ; # [doc = "The field uas_id contains valid data."] const UTM_DATA_AVAIL_FLAGS_UAS_ID_AVAILABLE = 2 ; # [doc = "The fields lat, lon and h_acc contain valid data."] const UTM_DATA_AVAIL_FLAGS_POSITION_AVAILABLE = 4 ; # [doc = "The fields alt and v_acc contain valid data."] const UTM_DATA_AVAIL_FLAGS_ALTITUDE_AVAILABLE = 8 ; # [doc = "The field relative_alt contains valid data."] const UTM_DATA_AVAIL_FLAGS_RELATIVE_ALTITUDE_AVAILABLE = 16 ; # [doc = "The fields vx and vy contain valid data."] const UTM_DATA_AVAIL_FLAGS_HORIZONTAL_VELO_AVAILABLE = 32 ; # [doc = "The field vz contains valid data."] const UTM_DATA_AVAIL_FLAGS_VERTICAL_VELO_AVAILABLE = 64 ; # [doc = "The fields next_lat, next_lon and next_alt contain valid data."] const UTM_DATA_AVAIL_FLAGS_NEXT_WAYPOINT_AVAILABLE = 128 ; } }
impl Default for UtmDataAvailFlags {
fn default() -> Self {
Self::UTM_DATA_AVAIL_FLAGS_TIME_VALID
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "Power supply status flags (bitmask)"] pub struct MavPowerStatus : u16 { # [doc = "main brick power supply valid"] const MAV_POWER_STATUS_BRICK_VALID = 1 ; # [doc = "main servo power supply valid for FMU"] const MAV_POWER_STATUS_SERVO_VALID = 2 ; # [doc = "USB power is connected"] const MAV_POWER_STATUS_USB_CONNECTED = 4 ; # [doc = "peripheral supply is in over-current state"] const MAV_POWER_STATUS_PERIPH_OVERCURRENT = 8 ; # [doc = "hi-power peripheral supply is in over-current state"] const MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT = 16 ; # [doc = "Power status has changed since boot"] const MAV_POWER_STATUS_CHANGED = 32 ; } }
impl Default for MavPowerStatus {
fn default() -> Self {
Self::MAV_POWER_STATUS_BRICK_VALID
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum MavOdidTimeAcc {
#[doc = "The timestamp accuracy is unknown."]
MAV_ODID_TIME_ACC_UNKNOWN = 0,
#[doc = "The timestamp accuracy is smaller than or equal to 0.1 second."]
MAV_ODID_TIME_ACC_0_1_SECOND = 1,
#[doc = "The timestamp accuracy is smaller than or equal to 0.2 second."]
MAV_ODID_TIME_ACC_0_2_SECOND = 2,
#[doc = "The timestamp accuracy is smaller than or equal to 0.3 second."]
MAV_ODID_TIME_ACC_0_3_SECOND = 3,
#[doc = "The timestamp accuracy is smaller than or equal to 0.4 second."]
MAV_ODID_TIME_ACC_0_4_SECOND = 4,
#[doc = "The timestamp accuracy is smaller than or equal to 0.5 second."]
MAV_ODID_TIME_ACC_0_5_SECOND = 5,
#[doc = "The timestamp accuracy is smaller than or equal to 0.6 second."]
MAV_ODID_TIME_ACC_0_6_SECOND = 6,
#[doc = "The timestamp accuracy is smaller than or equal to 0.7 second."]
MAV_ODID_TIME_ACC_0_7_SECOND = 7,
#[doc = "The timestamp accuracy is smaller than or equal to 0.8 second."]
MAV_ODID_TIME_ACC_0_8_SECOND = 8,
#[doc = "The timestamp accuracy is smaller than or equal to 0.9 second."]
MAV_ODID_TIME_ACC_0_9_SECOND = 9,
#[doc = "The timestamp accuracy is smaller than or equal to 1.0 second."]
MAV_ODID_TIME_ACC_1_0_SECOND = 10,
#[doc = "The timestamp accuracy is smaller than or equal to 1.1 second."]
MAV_ODID_TIME_ACC_1_1_SECOND = 11,
#[doc = "The timestamp accuracy is smaller than or equal to 1.2 second."]
MAV_ODID_TIME_ACC_1_2_SECOND = 12,
#[doc = "The timestamp accuracy is smaller than or equal to 1.3 second."]
MAV_ODID_TIME_ACC_1_3_SECOND = 13,
#[doc = "The timestamp accuracy is smaller than or equal to 1.4 second."]
MAV_ODID_TIME_ACC_1_4_SECOND = 14,
#[doc = "The timestamp accuracy is smaller than or equal to 1.5 second."]
MAV_ODID_TIME_ACC_1_5_SECOND = 15,
}
impl Default for MavOdidTimeAcc {
fn default() -> Self {
Self::MAV_ODID_TIME_ACC_UNKNOWN
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission."]
pub enum MavCmdAck {
#[doc = "Command / mission item is ok."]
MAV_CMD_ACK_OK = 0,
#[doc = "Generic error message if none of the other reasons fails or if no detailed error reporting is implemented."]
MAV_CMD_ACK_ERR_FAIL = 1,
#[doc = "The system is refusing to accept this command from this source / communication partner."]
MAV_CMD_ACK_ERR_ACCESS_DENIED = 2,
#[doc = "Command or mission item is not supported, other commands would be accepted."]
MAV_CMD_ACK_ERR_NOT_SUPPORTED = 3,
#[doc = "The coordinate frame of this command / mission item is not supported."]
MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED = 4,
#[doc = "The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible."]
MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE = 5,
#[doc = "The X or latitude value is out of range."]
MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE = 6,
#[doc = "The Y or longitude value is out of range."]
MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE = 7,
#[doc = "The Z or altitude value is out of range."]
MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE = 8,
}
impl Default for MavCmdAck {
fn default() -> Self {
Self::MAV_CMD_ACK_OK
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "GPS longitudinal offset encoding"]
pub enum UavionixAdsbOutCfgGpsOffsetLon {
UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON_NO_DATA = 0,
UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON_APPLIED_BY_SENSOR = 1,
}
impl Default for UavionixAdsbOutCfgGpsOffsetLon {
fn default() -> Self {
Self::UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON_NO_DATA
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] pub struct GoproHeartbeatFlags : u8 { # [doc = "GoPro is currently recording."] const GOPRO_FLAG_RECORDING = 1 ; } }
impl Default for GoproHeartbeatFlags {
fn default() -> Self {
Self::GOPRO_FLAG_RECORDING
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum GoproCommand {
#[doc = "(Get/Set)."]
GOPRO_COMMAND_POWER = 0,
#[doc = "(Get/Set)."]
GOPRO_COMMAND_CAPTURE_MODE = 1,
#[doc = "(___/Set)."]
GOPRO_COMMAND_SHUTTER = 2,
#[doc = "(Get/___)."]
GOPRO_COMMAND_BATTERY = 3,
#[doc = "(Get/___)."]
GOPRO_COMMAND_MODEL = 4,
#[doc = "(Get/Set)."]
GOPRO_COMMAND_VIDEO_SETTINGS = 5,
#[doc = "(Get/Set)."]
GOPRO_COMMAND_LOW_LIGHT = 6,
#[doc = "(Get/Set)."]
GOPRO_COMMAND_PHOTO_RESOLUTION = 7,
#[doc = "(Get/Set)."]
GOPRO_COMMAND_PHOTO_BURST_RATE = 8,
#[doc = "(Get/Set)."]
GOPRO_COMMAND_PROTUNE = 9,
#[doc = "(Get/Set) Hero 3+ Only."]
GOPRO_COMMAND_PROTUNE_WHITE_BALANCE = 10,
#[doc = "(Get/Set) Hero 3+ Only."]
GOPRO_COMMAND_PROTUNE_COLOUR = 11,
#[doc = "(Get/Set) Hero 3+ Only."]
GOPRO_COMMAND_PROTUNE_GAIN = 12,
#[doc = "(Get/Set) Hero 3+ Only."]
GOPRO_COMMAND_PROTUNE_SHARPNESS = 13,
#[doc = "(Get/Set) Hero 3+ Only."]
GOPRO_COMMAND_PROTUNE_EXPOSURE = 14,
#[doc = "(Get/Set)."]
GOPRO_COMMAND_TIME = 15,
#[doc = "(Get/Set)."]
GOPRO_COMMAND_CHARGING = 16,
}
impl Default for GoproCommand {
fn default() -> Self {
Self::GOPRO_COMMAND_POWER
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum GoproProtuneSharpness {
#[doc = "Low Sharpness."]
GOPRO_PROTUNE_SHARPNESS_LOW = 0,
#[doc = "Medium Sharpness."]
GOPRO_PROTUNE_SHARPNESS_MEDIUM = 1,
#[doc = "High Sharpness."]
GOPRO_PROTUNE_SHARPNESS_HIGH = 2,
}
impl Default for GoproProtuneSharpness {
fn default() -> Self {
Self::GOPRO_PROTUNE_SHARPNESS_LOW
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "List of possible failure type to inject."]
pub enum FailureType {
#[doc = "No failure injected, used to reset a previous failure."]
FAILURE_TYPE_OK = 0,
#[doc = "Sets unit off, so completely non-responsive."]
FAILURE_TYPE_OFF = 1,
#[doc = "Unit is stuck e.g. keeps reporting the same value."]
FAILURE_TYPE_STUCK = 2,
#[doc = "Unit is reporting complete garbage."]
FAILURE_TYPE_GARBAGE = 3,
#[doc = "Unit is consistently wrong."]
FAILURE_TYPE_WRONG = 4,
#[doc = "Unit is slow, so e.g. reporting at slower than expected rate."]
FAILURE_TYPE_SLOW = 5,
#[doc = "Data of unit is delayed in time."]
FAILURE_TYPE_DELAYED = 6,
#[doc = "Unit is sometimes working, sometimes not."]
FAILURE_TYPE_INTERMITTENT = 7,
}
impl Default for FailureType {
fn default() -> Self {
Self::FAILURE_TYPE_OK
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum MavOdidHorAcc {
#[doc = "The horizontal accuracy is unknown."]
MAV_ODID_HOR_ACC_UNKNOWN = 0,
#[doc = "The horizontal accuracy is smaller than 10 Nautical Miles. 18.52 km."]
MAV_ODID_HOR_ACC_10NM = 1,
#[doc = "The horizontal accuracy is smaller than 4 Nautical Miles. 7.408 km."]
MAV_ODID_HOR_ACC_4NM = 2,
#[doc = "The horizontal accuracy is smaller than 2 Nautical Miles. 3.704 km."]
MAV_ODID_HOR_ACC_2NM = 3,
#[doc = "The horizontal accuracy is smaller than 1 Nautical Miles. 1.852 km."]
MAV_ODID_HOR_ACC_1NM = 4,
#[doc = "The horizontal accuracy is smaller than 0.5 Nautical Miles. 926 m."]
MAV_ODID_HOR_ACC_0_5NM = 5,
#[doc = "The horizontal accuracy is smaller than 0.3 Nautical Miles. 555.6 m."]
MAV_ODID_HOR_ACC_0_3NM = 6,
#[doc = "The horizontal accuracy is smaller than 0.1 Nautical Miles. 185.2 m."]
MAV_ODID_HOR_ACC_0_1NM = 7,
#[doc = "The horizontal accuracy is smaller than 0.05 Nautical Miles. 92.6 m."]
MAV_ODID_HOR_ACC_0_05NM = 8,
#[doc = "The horizontal accuracy is smaller than 30 meter."]
MAV_ODID_HOR_ACC_30_METER = 9,
#[doc = "The horizontal accuracy is smaller than 10 meter."]
MAV_ODID_HOR_ACC_10_METER = 10,
#[doc = "The horizontal accuracy is smaller than 3 meter."]
MAV_ODID_HOR_ACC_3_METER = 11,
#[doc = "The horizontal accuracy is smaller than 1 meter."]
MAV_ODID_HOR_ACC_1_METER = 12,
}
impl Default for MavOdidHorAcc {
fn default() -> Self {
Self::MAV_ODID_HOR_ACC_UNKNOWN
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "A mapping of rover flight modes for custom_mode field of heartbeat."]
pub enum RoverMode {
ROVER_MODE_MANUAL = 0,
ROVER_MODE_ACRO = 1,
ROVER_MODE_STEERING = 3,
ROVER_MODE_HOLD = 4,
ROVER_MODE_LOITER = 5,
ROVER_MODE_FOLLOW = 6,
ROVER_MODE_SIMPLE = 7,
ROVER_MODE_AUTO = 10,
ROVER_MODE_RTL = 11,
ROVER_MODE_SMART_RTL = 12,
ROVER_MODE_GUIDED = 15,
ROVER_MODE_INITIALIZING = 16,
}
impl Default for RoverMode {
fn default() -> Self {
Self::ROVER_MODE_MANUAL
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum CameraStatusTypes {
#[doc = "Camera heartbeat, announce camera component ID at 1Hz."]
CAMERA_STATUS_TYPE_HEARTBEAT = 0,
#[doc = "Camera image triggered."]
CAMERA_STATUS_TYPE_TRIGGER = 1,
#[doc = "Camera connection lost."]
CAMERA_STATUS_TYPE_DISCONNECT = 2,
#[doc = "Camera unknown error."]
CAMERA_STATUS_TYPE_ERROR = 3,
#[doc = "Camera battery low. Parameter p1 shows reported voltage."]
CAMERA_STATUS_TYPE_LOWBATT = 4,
#[doc = "Camera storage low. Parameter p1 shows reported shots remaining."]
CAMERA_STATUS_TYPE_LOWSTORE = 5,
#[doc = "Camera storage low. Parameter p1 shows reported video minutes remaining."]
CAMERA_STATUS_TYPE_LOWSTOREV = 6,
}
impl Default for CameraStatusTypes {
fn default() -> Self {
Self::CAMERA_STATUS_TYPE_HEARTBEAT
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum MavOdidStatus {
#[doc = "The status of the (UA) Unmanned Aircraft is undefined."]
MAV_ODID_STATUS_UNDECLARED = 0,
#[doc = "The UA is on the ground."]
MAV_ODID_STATUS_GROUND = 1,
#[doc = "The UA is in the air."]
MAV_ODID_STATUS_AIRBORNE = 2,
#[doc = "The UA is having an emergency."]
MAV_ODID_STATUS_EMERGENCY = 3,
#[doc = "The remote ID system is failing or unreliable in some way."]
MAV_ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE = 4,
}
impl Default for MavOdidStatus {
fn default() -> Self {
Self::MAV_ODID_STATUS_UNDECLARED
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "A mapping of antenna tracker flight modes for custom_mode field of heartbeat."]
pub enum TrackerMode {
TRACKER_MODE_MANUAL = 0,
TRACKER_MODE_STOP = 1,
TRACKER_MODE_SCAN = 2,
TRACKER_MODE_SERVO_TEST = 3,
TRACKER_MODE_AUTO = 10,
TRACKER_MODE_INITIALIZING = 16,
}
impl Default for TrackerMode {
fn default() -> Self {
Self::TRACKER_MODE_MANUAL
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "The error type for the OSD parameter editor."]
pub enum OsdParamConfigError {
OSD_PARAM_SUCCESS = 0,
OSD_PARAM_INVALID_SCREEN = 1,
OSD_PARAM_INVALID_PARAMETER_INDEX = 2,
OSD_PARAM_INVALID_PARAMETER = 3,
}
impl Default for OsdParamConfigError {
fn default() -> Self {
Self::OSD_PARAM_SUCCESS
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Flags to indicate the type of storage."]
pub enum StorageType {
#[doc = "Storage type is not known."]
STORAGE_TYPE_UNKNOWN = 0,
#[doc = "Storage type is USB device."]
STORAGE_TYPE_USB_STICK = 1,
#[doc = "Storage type is SD card."]
STORAGE_TYPE_SD = 2,
#[doc = "Storage type is microSD card."]
STORAGE_TYPE_MICROSD = 3,
#[doc = "Storage type is CFast."]
STORAGE_TYPE_CF = 4,
#[doc = "Storage type is CFexpress."]
STORAGE_TYPE_CFE = 5,
#[doc = "Storage type is XQD."]
STORAGE_TYPE_XQD = 6,
#[doc = "Storage type is HD mass storage type."]
STORAGE_TYPE_HD = 7,
#[doc = "Storage type is other, not listed type."]
STORAGE_TYPE_OTHER = 254,
}
impl Default for StorageType {
fn default() -> Self {
Self::STORAGE_TYPE_UNKNOWN
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Possible responses from a CELLULAR_CONFIG message."]
pub enum CellularConfigResponse {
#[doc = "Changes accepted."]
CELLULAR_CONFIG_RESPONSE_ACCEPTED = 0,
#[doc = "Invalid APN."]
CELLULAR_CONFIG_RESPONSE_APN_ERROR = 1,
#[doc = "Invalid PIN."]
CELLULAR_CONFIG_RESPONSE_PIN_ERROR = 2,
#[doc = "Changes rejected."]
CELLULAR_CONFIG_RESPONSE_REJECTED = 3,
#[doc = "PUK is required to unblock SIM card."]
CELLULAR_CONFIG_BLOCKED_PUK_REQUIRED = 4,
}
impl Default for CellularConfigResponse {
fn default() -> Self {
Self::CELLULAR_CONFIG_RESPONSE_ACCEPTED
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum IcarousFmsState {
ICAROUS_FMS_STATE_IDLE = 0,
ICAROUS_FMS_STATE_TAKEOFF = 1,
ICAROUS_FMS_STATE_CLIMB = 2,
ICAROUS_FMS_STATE_CRUISE = 3,
ICAROUS_FMS_STATE_APPROACH = 4,
ICAROUS_FMS_STATE_LAND = 5,
}
impl Default for IcarousFmsState {
fn default() -> Self {
Self::ICAROUS_FMS_STATE_IDLE
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "These encode the sensors whose status is sent as part of the SYS_STATUS message in the extended fields."] pub struct MavSysStatusSensorExtended : u32 { # [doc = "0x01 Recovery system (parachute, balloon, retracts etc)"] const MAV_SYS_STATUS_RECOVERY_SYSTEM = 1 ; } }
impl Default for MavSysStatusSensorExtended {
fn default() -> Self {
Self::MAV_SYS_STATUS_RECOVERY_SYSTEM
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "Flags in the HIGHRES_IMU message indicate which fields have updated since the last message"] pub struct HighresImuUpdatedFlags : u16 { # [doc = "None of the fields in HIGHRES_IMU have been updated"] const HIGHRES_IMU_UPDATED_NONE = 0 ; # [doc = "The value in the xacc field has been updated"] const HIGHRES_IMU_UPDATED_XACC = 1 ; # [doc = "The value in the yacc field has been updated"] const HIGHRES_IMU_UPDATED_YACC = 2 ; # [doc = "The value in the zacc field has been updated since"] const HIGHRES_IMU_UPDATED_ZACC = 4 ; # [doc = "The value in the xgyro field has been updated"] const HIGHRES_IMU_UPDATED_XGYRO = 8 ; # [doc = "The value in the ygyro field has been updated"] const HIGHRES_IMU_UPDATED_YGYRO = 16 ; # [doc = "The value in the zgyro field has been updated"] const HIGHRES_IMU_UPDATED_ZGYRO = 32 ; # [doc = "The value in the xmag field has been updated"] const HIGHRES_IMU_UPDATED_XMAG = 64 ; # [doc = "The value in the ymag field has been updated"] const HIGHRES_IMU_UPDATED_YMAG = 128 ; # [doc = "The value in the zmag field has been updated"] const HIGHRES_IMU_UPDATED_ZMAG = 256 ; # [doc = "The value in the abs_pressure field has been updated"] const HIGHRES_IMU_UPDATED_ABS_PRESSURE = 512 ; # [doc = "The value in the diff_pressure field has been updated"] const HIGHRES_IMU_UPDATED_DIFF_PRESSURE = 1024 ; # [doc = "The value in the pressure_alt field has been updated"] const HIGHRES_IMU_UPDATED_PRESSURE_ALT = 2048 ; # [doc = "The value in the temperature field has been updated"] const HIGHRES_IMU_UPDATED_TEMPERATURE = 4096 ; # [doc = "All fields in HIGHRES_IMU have been updated."] const HIGHRES_IMU_UPDATED_ALL = 65535 ; } }
impl Default for HighresImuUpdatedFlags {
fn default() -> Self {
Self::HIGHRES_IMU_UPDATED_NONE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum GoproBurstRate {
#[doc = "3 Shots / 1 Second."]
GOPRO_BURST_RATE_3_IN_1_SECOND = 0,
#[doc = "5 Shots / 1 Second."]
GOPRO_BURST_RATE_5_IN_1_SECOND = 1,
#[doc = "10 Shots / 1 Second."]
GOPRO_BURST_RATE_10_IN_1_SECOND = 2,
#[doc = "10 Shots / 2 Second."]
GOPRO_BURST_RATE_10_IN_2_SECOND = 3,
#[doc = "10 Shots / 3 Second (Hero 4 Only)."]
GOPRO_BURST_RATE_10_IN_3_SECOND = 4,
#[doc = "30 Shots / 1 Second."]
GOPRO_BURST_RATE_30_IN_1_SECOND = 5,
#[doc = "30 Shots / 2 Second."]
GOPRO_BURST_RATE_30_IN_2_SECOND = 6,
#[doc = "30 Shots / 3 Second."]
GOPRO_BURST_RATE_30_IN_3_SECOND = 7,
#[doc = "30 Shots / 6 Second."]
GOPRO_BURST_RATE_30_IN_6_SECOND = 8,
}
impl Default for GoproBurstRate {
fn default() -> Self {
Self::GOPRO_BURST_RATE_3_IN_1_SECOND
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Flags to indicate the status of camera storage."]
pub enum StorageStatus {
#[doc = "Storage is missing (no microSD card loaded for example.)"]
STORAGE_STATUS_EMPTY = 0,
#[doc = "Storage present but unformatted."]
STORAGE_STATUS_UNFORMATTED = 1,
#[doc = "Storage present and ready."]
STORAGE_STATUS_READY = 2,
#[doc = "Camera does not supply storage status information. Capacity information in STORAGE_INFORMATION fields will be ignored."]
STORAGE_STATUS_NOT_SUPPORTED = 3,
}
impl Default for StorageStatus {
fn default() -> Self {
Self::STORAGE_STATUS_EMPTY
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "These flags encode the MAV mode."] pub struct MavModeFlag : u8 { # [doc = "0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. Additional note: this flag is to be ignore when sent in the command MAV_CMD_DO_SET_MODE and MAV_CMD_COMPONENT_ARM_DISARM shall be used instead. The flag can still be used to report the armed state."] const MAV_MODE_FLAG_SAFETY_ARMED = 128 ; # [doc = "0b01000000 remote control input is enabled."] const MAV_MODE_FLAG_MANUAL_INPUT_ENABLED = 64 ; # [doc = "0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational."] const MAV_MODE_FLAG_HIL_ENABLED = 32 ; # [doc = "0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around."] const MAV_MODE_FLAG_STABILIZE_ENABLED = 16 ; # [doc = "0b00001000 guided mode enabled, system flies waypoints / mission items."] const MAV_MODE_FLAG_GUIDED_ENABLED = 8 ; # [doc = "0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation."] const MAV_MODE_FLAG_AUTO_ENABLED = 4 ; # [doc = "0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations."] const MAV_MODE_FLAG_TEST_ENABLED = 2 ; # [doc = "0b00000001 Reserved for future use."] const MAV_MODE_FLAG_CUSTOM_MODE_ENABLED = 1 ; } }
impl Default for MavModeFlag {
fn default() -> Self {
Self::MAV_MODE_FLAG_SAFETY_ARMED
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum GoproPhotoResolution {
#[doc = "5MP Medium."]
GOPRO_PHOTO_RESOLUTION_5MP_MEDIUM = 0,
#[doc = "7MP Medium."]
GOPRO_PHOTO_RESOLUTION_7MP_MEDIUM = 1,
#[doc = "7MP Wide."]
GOPRO_PHOTO_RESOLUTION_7MP_WIDE = 2,
#[doc = "10MP Wide."]
GOPRO_PHOTO_RESOLUTION_10MP_WIDE = 3,
#[doc = "12MP Wide."]
GOPRO_PHOTO_RESOLUTION_12MP_WIDE = 4,
}
impl Default for GoproPhotoResolution {
fn default() -> Self {
Self::GOPRO_PHOTO_RESOLUTION_5MP_MEDIUM
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Defines how throttle value is represented in MAV_CMD_DO_MOTOR_TEST."]
pub enum MotorTestThrottleType {
#[doc = "Throttle as a percentage (0 ~ 100)"]
MOTOR_TEST_THROTTLE_PERCENT = 0,
#[doc = "Throttle as an absolute PWM value (normally in range of 1000~2000)."]
MOTOR_TEST_THROTTLE_PWM = 1,
#[doc = "Throttle pass-through from pilot's transmitter."]
MOTOR_TEST_THROTTLE_PILOT = 2,
#[doc = "Per-motor compass calibration test."]
MOTOR_TEST_COMPASS_CAL = 3,
}
impl Default for MotorTestThrottleType {
fn default() -> Self {
Self::MOTOR_TEST_THROTTLE_PERCENT
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum GoproProtuneWhiteBalance {
#[doc = "Auto."]
GOPRO_PROTUNE_WHITE_BALANCE_AUTO = 0,
#[doc = "3000K."]
GOPRO_PROTUNE_WHITE_BALANCE_3000K = 1,
#[doc = "5500K."]
GOPRO_PROTUNE_WHITE_BALANCE_5500K = 2,
#[doc = "6500K."]
GOPRO_PROTUNE_WHITE_BALANCE_6500K = 3,
#[doc = "Camera Raw."]
GOPRO_PROTUNE_WHITE_BALANCE_RAW = 4,
}
impl Default for GoproProtuneWhiteBalance {
fn default() -> Self {
Self::GOPRO_PROTUNE_WHITE_BALANCE_AUTO
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Flags to indicate usage for a particular storage (see STORAGE_INFORMATION.storage_usage and MAV_CMD_SET_STORAGE_USAGE)."]
pub enum StorageUsageFlag {
#[doc = "Always set to 1 (indicates STORAGE_INFORMATION.storage_usage is supported)."]
STORAGE_USAGE_FLAG_SET = 1,
#[doc = "Storage for saving photos."]
STORAGE_USAGE_FLAG_PHOTO = 2,
#[doc = "Storage for saving videos."]
STORAGE_USAGE_FLAG_VIDEO = 4,
#[doc = "Storage for saving logs."]
STORAGE_USAGE_FLAG_LOGS = 8,
}
impl Default for StorageUsageFlag {
fn default() -> Self {
Self::STORAGE_USAGE_FLAG_SET
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Enumeration of estimator types"]
pub enum MavEstimatorType {
#[doc = "Unknown type of the estimator."]
MAV_ESTIMATOR_TYPE_UNKNOWN = 0,
#[doc = "This is a naive estimator without any real covariance feedback."]
MAV_ESTIMATOR_TYPE_NAIVE = 1,
#[doc = "Computer vision based estimate. Might be up to scale."]
MAV_ESTIMATOR_TYPE_VISION = 2,
#[doc = "Visual-inertial estimate."]
MAV_ESTIMATOR_TYPE_VIO = 3,
#[doc = "Plain GPS estimate."]
MAV_ESTIMATOR_TYPE_GPS = 4,
#[doc = "Estimator integrating GPS and inertial sensing."]
MAV_ESTIMATOR_TYPE_GPS_INS = 5,
#[doc = "Estimate from external motion capturing system."]
MAV_ESTIMATOR_TYPE_MOCAP = 6,
#[doc = "Estimator based on lidar sensor input."]
MAV_ESTIMATOR_TYPE_LIDAR = 7,
#[doc = "Estimator on autopilot."]
MAV_ESTIMATOR_TYPE_AUTOPILOT = 8,
}
impl Default for MavEstimatorType {
fn default() -> Self {
Self::MAV_ESTIMATOR_TYPE_UNKNOWN
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Sequence that motors are tested when using MAV_CMD_DO_MOTOR_TEST."]
pub enum MotorTestOrder {
#[doc = "Default autopilot motor test method."]
MOTOR_TEST_ORDER_DEFAULT = 0,
#[doc = "Motor numbers are specified as their index in a predefined vehicle-specific sequence."]
MOTOR_TEST_ORDER_SEQUENCE = 1,
#[doc = "Motor numbers are specified as the output as labeled on the board."]
MOTOR_TEST_ORDER_BOARD = 2,
}
impl Default for MotorTestOrder {
fn default() -> Self {
Self::MOTOR_TEST_ORDER_DEFAULT
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Bitmap of options for the MAV_CMD_DO_REPOSITION"]
pub enum MavDoRepositionFlags {
#[doc = "The aircraft should immediately transition into guided. This should not be set for follow me applications"]
MAV_DO_REPOSITION_FLAGS_CHANGE_MODE = 1,
}
impl Default for MavDoRepositionFlags {
fn default() -> Self {
Self::MAV_DO_REPOSITION_FLAGS_CHANGE_MODE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum GoproProtuneExposure {
#[doc = "-5.0 EV (Hero 3+ Only)."]
GOPRO_PROTUNE_EXPOSURE_NEG_5_0 = 0,
#[doc = "-4.5 EV (Hero 3+ Only)."]
GOPRO_PROTUNE_EXPOSURE_NEG_4_5 = 1,
#[doc = "-4.0 EV (Hero 3+ Only)."]
GOPRO_PROTUNE_EXPOSURE_NEG_4_0 = 2,
#[doc = "-3.5 EV (Hero 3+ Only)."]
GOPRO_PROTUNE_EXPOSURE_NEG_3_5 = 3,
#[doc = "-3.0 EV (Hero 3+ Only)."]
GOPRO_PROTUNE_EXPOSURE_NEG_3_0 = 4,
#[doc = "-2.5 EV (Hero 3+ Only)."]
GOPRO_PROTUNE_EXPOSURE_NEG_2_5 = 5,
#[doc = "-2.0 EV."]
GOPRO_PROTUNE_EXPOSURE_NEG_2_0 = 6,
#[doc = "-1.5 EV."]
GOPRO_PROTUNE_EXPOSURE_NEG_1_5 = 7,
#[doc = "-1.0 EV."]
GOPRO_PROTUNE_EXPOSURE_NEG_1_0 = 8,
#[doc = "-0.5 EV."]
GOPRO_PROTUNE_EXPOSURE_NEG_0_5 = 9,
#[doc = "0.0 EV."]
GOPRO_PROTUNE_EXPOSURE_ZERO = 10,
#[doc = "+0.5 EV."]
GOPRO_PROTUNE_EXPOSURE_POS_0_5 = 11,
#[doc = "+1.0 EV."]
GOPRO_PROTUNE_EXPOSURE_POS_1_0 = 12,
#[doc = "+1.5 EV."]
GOPRO_PROTUNE_EXPOSURE_POS_1_5 = 13,
#[doc = "+2.0 EV."]
GOPRO_PROTUNE_EXPOSURE_POS_2_0 = 14,
#[doc = "+2.5 EV (Hero 3+ Only)."]
GOPRO_PROTUNE_EXPOSURE_POS_2_5 = 15,
#[doc = "+3.0 EV (Hero 3+ Only)."]
GOPRO_PROTUNE_EXPOSURE_POS_3_0 = 16,
#[doc = "+3.5 EV (Hero 3+ Only)."]
GOPRO_PROTUNE_EXPOSURE_POS_3_5 = 17,
#[doc = "+4.0 EV (Hero 3+ Only)."]
GOPRO_PROTUNE_EXPOSURE_POS_4_0 = 18,
#[doc = "+4.5 EV (Hero 3+ Only)."]
GOPRO_PROTUNE_EXPOSURE_POS_4_5 = 19,
#[doc = "+5.0 EV (Hero 3+ Only)."]
GOPRO_PROTUNE_EXPOSURE_POS_5_0 = 20,
}
impl Default for GoproProtuneExposure {
fn default() -> Self {
Self::GOPRO_PROTUNE_EXPOSURE_NEG_5_0
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Generalized UAVCAN node health"]
pub enum UavcanNodeHealth {
#[doc = "The node is functioning properly."]
UAVCAN_NODE_HEALTH_OK = 0,
#[doc = "A critical parameter went out of range or the node has encountered a minor failure."]
UAVCAN_NODE_HEALTH_WARNING = 1,
#[doc = "The node has encountered a major failure."]
UAVCAN_NODE_HEALTH_ERROR = 2,
#[doc = "The node has suffered a fatal malfunction."]
UAVCAN_NODE_HEALTH_CRITICAL = 3,
}
impl Default for UavcanNodeHealth {
fn default() -> Self {
Self::UAVCAN_NODE_HEALTH_OK
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Specifies the datatype of a MAVLink parameter."]
pub enum MavParamType {
#[doc = "8-bit unsigned integer"]
MAV_PARAM_TYPE_UINT8 = 1,
#[doc = "8-bit signed integer"]
MAV_PARAM_TYPE_INT8 = 2,
#[doc = "16-bit unsigned integer"]
MAV_PARAM_TYPE_UINT16 = 3,
#[doc = "16-bit signed integer"]
MAV_PARAM_TYPE_INT16 = 4,
#[doc = "32-bit unsigned integer"]
MAV_PARAM_TYPE_UINT32 = 5,
#[doc = "32-bit signed integer"]
MAV_PARAM_TYPE_INT32 = 6,
#[doc = "64-bit unsigned integer"]
MAV_PARAM_TYPE_UINT64 = 7,
#[doc = "64-bit signed integer"]
MAV_PARAM_TYPE_INT64 = 8,
#[doc = "32-bit floating-point"]
MAV_PARAM_TYPE_REAL32 = 9,
#[doc = "64-bit floating-point"]
MAV_PARAM_TYPE_REAL64 = 10,
}
impl Default for MavParamType {
fn default() -> Self {
Self::MAV_PARAM_TYPE_UINT8
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "Gimbal device (low level) capability flags (bitmap)."] pub struct GimbalDeviceCapFlags : u16 { # [doc = "Gimbal device supports a retracted position."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT = 1 ; # [doc = "Gimbal device supports a horizontal, forward looking position, stabilized."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL = 2 ; # [doc = "Gimbal device supports rotating around roll axis."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS = 4 ; # [doc = "Gimbal device supports to follow a roll angle relative to the vehicle."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW = 8 ; # [doc = "Gimbal device supports locking to a roll angle (generally that's the default with roll stabilized)."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK = 16 ; # [doc = "Gimbal device supports rotating around pitch axis."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS = 32 ; # [doc = "Gimbal device supports to follow a pitch angle relative to the vehicle."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW = 64 ; # [doc = "Gimbal device supports locking to a pitch angle (generally that's the default with pitch stabilized)."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK = 128 ; # [doc = "Gimbal device supports rotating around yaw axis."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS = 256 ; # [doc = "Gimbal device supports to follow a yaw angle relative to the vehicle (generally that's the default)."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW = 512 ; # [doc = "Gimbal device supports locking to an absolute heading, i.e., yaw angle relative to North (earth frame, often this is an option available)."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK = 1024 ; # [doc = "Gimbal device supports yawing/panning infinetely (e.g. using slip disk)."] const GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW = 2048 ; # [doc = "Gimbal device supports yaw angles and angular velocities relative to North (earth frame). This usually requires support by an autopilot via AUTOPILOT_STATE_FOR_GIMBAL_DEVICE. Support can go on and off during runtime, which is reported by the flag GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_IN_EARTH_FRAME."] const GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME = 4096 ; # [doc = "Gimbal device supports radio control inputs as an alternative input for controlling the gimbal orientation."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS = 8192 ; } }
impl Default for GimbalDeviceCapFlags {
fn default() -> Self {
Self::GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Enumeration of distance sensor types"]
pub enum MavDistanceSensor {
#[doc = "Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units"]
MAV_DISTANCE_SENSOR_LASER = 0,
#[doc = "Ultrasound rangefinder, e.g. MaxBotix units"]
MAV_DISTANCE_SENSOR_ULTRASOUND = 1,
#[doc = "Infrared rangefinder, e.g. Sharp units"]
MAV_DISTANCE_SENSOR_INFRARED = 2,
#[doc = "Radar type, e.g. uLanding units"]
MAV_DISTANCE_SENSOR_RADAR = 3,
#[doc = "Broken or unknown type, e.g. analog units"]
MAV_DISTANCE_SENSOR_UNKNOWN = 4,
}
impl Default for MavDistanceSensor {
fn default() -> Self {
Self::MAV_DISTANCE_SENSOR_LASER
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "MAV FTP opcodes: https://mavlink.io/en/services/ftp.html"]
pub enum MavFtpOpcode {
#[doc = "None. Ignored, always ACKed"]
MAV_FTP_OPCODE_NONE = 0,
#[doc = "TerminateSession: Terminates open Read session"]
MAV_FTP_OPCODE_TERMINATESESSION = 1,
#[doc = "ResetSessions: Terminates all open read sessions"]
MAV_FTP_OPCODE_RESETSESSION = 2,
#[doc = "ListDirectory. List files and directories in path from offset"]
MAV_FTP_OPCODE_LISTDIRECTORY = 3,
#[doc = "OpenFileRO: Opens file at path for reading, returns session"]
MAV_FTP_OPCODE_OPENFILERO = 4,
#[doc = "ReadFile: Reads size bytes from offset in session"]
MAV_FTP_OPCODE_READFILE = 5,
#[doc = "CreateFile: Creates file at path for writing, returns session"]
MAV_FTP_OPCODE_CREATEFILE = 6,
#[doc = "WriteFile: Writes size bytes to offset in session"]
MAV_FTP_OPCODE_WRITEFILE = 7,
#[doc = "RemoveFile: Remove file at path"]
MAV_FTP_OPCODE_REMOVEFILE = 8,
#[doc = "CreateDirectory: Creates directory at path"]
MAV_FTP_OPCODE_CREATEDIRECTORY = 9,
#[doc = "RemoveDirectory: Removes directory at path. The directory must be empty."]
MAV_FTP_OPCODE_REMOVEDIRECTORY = 10,
#[doc = "OpenFileWO: Opens file at path for writing, returns session"]
MAV_FTP_OPCODE_OPENFILEWO = 11,
#[doc = "TruncateFile: Truncate file at path to offset length"]
MAV_FTP_OPCODE_TRUNCATEFILE = 12,
#[doc = "Rename: Rename path1 to path2"]
MAV_FTP_OPCODE_RENAME = 13,
#[doc = "CalcFileCRC32: Calculate CRC32 for file at path"]
MAV_FTP_OPCODE_CALCFILECRC = 14,
#[doc = "BurstReadFile: Burst download session file"]
MAV_FTP_OPCODE_BURSTREADFILE = 15,
#[doc = "ACK: ACK response"]
MAV_FTP_OPCODE_ACK = 128,
#[doc = "NAK: NAK response"]
MAV_FTP_OPCODE_NAK = 129,
}
impl Default for MavFtpOpcode {
fn default() -> Self {
Self::MAV_FTP_OPCODE_NONE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum MavOdidClassificationType {
#[doc = "The classification type for the UA is undeclared."]
MAV_ODID_CLASSIFICATION_TYPE_UNDECLARED = 0,
#[doc = "The classification type for the UA follows EU (European Union) specifications."]
MAV_ODID_CLASSIFICATION_TYPE_EU = 1,
}
impl Default for MavOdidClassificationType {
fn default() -> Self {
Self::MAV_ODID_CLASSIFICATION_TYPE_UNDECLARED
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum FenceBreach {
#[doc = "No last fence breach"]
FENCE_BREACH_NONE = 0,
#[doc = "Breached minimum altitude"]
FENCE_BREACH_MINALT = 1,
#[doc = "Breached maximum altitude"]
FENCE_BREACH_MAXALT = 2,
#[doc = "Breached fence boundary"]
FENCE_BREACH_BOUNDARY = 3,
}
impl Default for FenceBreach {
fn default() -> Self {
Self::FENCE_BREACH_NONE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not."]
pub enum MavModeFlagDecodePosition {
#[doc = "First bit: 10000000"]
MAV_MODE_FLAG_DECODE_POSITION_SAFETY = 128,
#[doc = "Second bit: 01000000"]
MAV_MODE_FLAG_DECODE_POSITION_MANUAL = 64,
#[doc = "Third bit: 00100000"]
MAV_MODE_FLAG_DECODE_POSITION_HIL = 32,
#[doc = "Fourth bit: 00010000"]
MAV_MODE_FLAG_DECODE_POSITION_STABILIZE = 16,
#[doc = "Fifth bit: 00001000"]
MAV_MODE_FLAG_DECODE_POSITION_GUIDED = 8,
#[doc = "Sixth bit: 00000100"]
MAV_MODE_FLAG_DECODE_POSITION_AUTO = 4,
#[doc = "Seventh bit: 00000010"]
MAV_MODE_FLAG_DECODE_POSITION_TEST = 2,
#[doc = "Eighth bit: 00000001"]
MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE = 1,
}
impl Default for MavModeFlagDecodePosition {
fn default() -> Self {
Self::MAV_MODE_FLAG_DECODE_POSITION_SAFETY
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Winch actions."]
pub enum WinchActions {
#[doc = "Allow motor to freewheel."]
WINCH_RELAXED = 0,
#[doc = "Wind or unwind specified length of line, optionally using specified rate."]
WINCH_RELATIVE_LENGTH_CONTROL = 1,
#[doc = "Wind or unwind line at specified rate."]
WINCH_RATE_CONTROL = 2,
#[doc = "Perform the locking sequence to relieve motor while in the fully retracted position. Only action and instance command parameters are used, others are ignored."]
WINCH_LOCK = 3,
#[doc = "Sequence of drop, slow down, touch down, reel up, lock. Only action and instance command parameters are used, others are ignored."]
WINCH_DELIVER = 4,
#[doc = "Engage motor and hold current position. Only action and instance command parameters are used, others are ignored."]
WINCH_HOLD = 5,
#[doc = "Return the reel to the fully retracted position. Only action and instance command parameters are used, others are ignored."]
WINCH_RETRACT = 6,
#[doc = "Load the reel with line. The winch will calculate the total loaded length and stop when the tension exceeds a threshold. Only action and instance command parameters are used, others are ignored."]
WINCH_LOAD_LINE = 7,
#[doc = "Spool out the entire length of the line. Only action and instance command parameters are used, others are ignored."]
WINCH_ABANDON_LINE = 8,
#[doc = "Spools out just enough to present the hook to the user to load the payload. Only action and instance command parameters are used, others are ignored"]
WINCH_LOAD_PAYLOAD = 9,
}
impl Default for WinchActions {
fn default() -> Self {
Self::WINCH_RELAXED
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum GoproProtuneGain {
#[doc = "ISO 400."]
GOPRO_PROTUNE_GAIN_400 = 0,
#[doc = "ISO 800 (Only Hero 4)."]
GOPRO_PROTUNE_GAIN_800 = 1,
#[doc = "ISO 1600."]
GOPRO_PROTUNE_GAIN_1600 = 2,
#[doc = "ISO 3200 (Only Hero 4)."]
GOPRO_PROTUNE_GAIN_3200 = 3,
#[doc = "ISO 6400."]
GOPRO_PROTUNE_GAIN_6400 = 4,
}
impl Default for GoproProtuneGain {
fn default() -> Self {
Self::GOPRO_PROTUNE_GAIN_400
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "The type of parameter for the OSD parameter editor."]
pub enum OsdParamConfigType {
OSD_PARAM_NONE = 0,
OSD_PARAM_SERIAL_PROTOCOL = 1,
OSD_PARAM_SERVO_FUNCTION = 2,
OSD_PARAM_AUX_FUNCTION = 3,
OSD_PARAM_FLIGHT_MODE = 4,
OSD_PARAM_FAILSAFE_ACTION = 5,
OSD_PARAM_FAILSAFE_ACTION_1 = 6,
OSD_PARAM_FAILSAFE_ACTION_2 = 7,
OSD_PARAM_NUM_TYPES = 8,
}
impl Default for OsdParamConfigType {
fn default() -> Self {
Self::OSD_PARAM_NONE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Focus types for MAV_CMD_SET_CAMERA_FOCUS"]
pub enum SetFocusType {
#[doc = "Focus one step increment (-1 for focusing in, 1 for focusing out towards infinity)."]
FOCUS_TYPE_STEP = 0,
#[doc = "Continuous focus up/down until stopped (-1 for focusing in, 1 for focusing out towards infinity, 0 to stop focusing)"]
FOCUS_TYPE_CONTINUOUS = 1,
#[doc = "Focus value as proportion of full camera focus range (a value between 0.0 and 100.0)"]
FOCUS_TYPE_RANGE = 2,
#[doc = "Focus value in metres. Note that there is no message to get the valid focus range of the camera, so this can type can only be used for cameras where the range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera)."]
FOCUS_TYPE_METERS = 3,
#[doc = "Focus automatically."]
FOCUS_TYPE_AUTO = 4,
#[doc = "Single auto focus. Mainly used for still pictures. Usually abbreviated as AF-S."]
FOCUS_TYPE_AUTO_SINGLE = 5,
#[doc = "Continuous auto focus. Mainly used for dynamic scenes. Abbreviated as AF-C."]
FOCUS_TYPE_AUTO_CONTINUOUS = 6,
}
impl Default for SetFocusType {
fn default() -> Self {
Self::FOCUS_TYPE_STEP
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum MavOdidOperatorLocationType {
#[doc = "The location/altitude of the operator is the same as the take-off location."]
MAV_ODID_OPERATOR_LOCATION_TYPE_TAKEOFF = 0,
#[doc = "The location/altitude of the operator is dynamic. E.g. based on live GNSS data."]
MAV_ODID_OPERATOR_LOCATION_TYPE_LIVE_GNSS = 1,
#[doc = "The location/altitude of the operator are fixed values."]
MAV_ODID_OPERATOR_LOCATION_TYPE_FIXED = 2,
}
impl Default for MavOdidOperatorLocationType {
fn default() -> Self {
Self::MAV_ODID_OPERATOR_LOCATION_TYPE_TAKEOFF
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Aircraft-rated danger from this threat."]
pub enum MavCollisionThreatLevel {
#[doc = "Not a threat"]
MAV_COLLISION_THREAT_LEVEL_NONE = 0,
#[doc = "Craft is mildly concerned about this threat"]
MAV_COLLISION_THREAT_LEVEL_LOW = 1,
#[doc = "Craft is panicking, and may take actions to avoid threat"]
MAV_COLLISION_THREAT_LEVEL_HIGH = 2,
}
impl Default for MavCollisionThreatLevel {
fn default() -> Self {
Self::MAV_COLLISION_THREAT_LEVEL_NONE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum IcarousTrackBandTypes {
ICAROUS_TRACK_BAND_TYPE_NONE = 0,
ICAROUS_TRACK_BAND_TYPE_NEAR = 1,
ICAROUS_TRACK_BAND_TYPE_RECOVERY = 2,
}
impl Default for IcarousTrackBandTypes {
fn default() -> Self {
Self::ICAROUS_TRACK_BAND_TYPE_NONE
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "Smart battery supply status/fault flags (bitmask) for health indication. The battery must also report either MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY if any of these are set."] pub struct MavBatteryFault : u32 { # [doc = "Battery has deep discharged."] const MAV_BATTERY_FAULT_DEEP_DISCHARGE = 1 ; # [doc = "Voltage spikes."] const MAV_BATTERY_FAULT_SPIKES = 2 ; # [doc = "One or more cells have failed. Battery should also report MAV_BATTERY_CHARGE_STATE_FAILE (and should not be used)."] const MAV_BATTERY_FAULT_CELL_FAIL = 4 ; # [doc = "Over-current fault."] const MAV_BATTERY_FAULT_OVER_CURRENT = 8 ; # [doc = "Over-temperature fault."] const MAV_BATTERY_FAULT_OVER_TEMPERATURE = 16 ; # [doc = "Under-temperature fault."] const MAV_BATTERY_FAULT_UNDER_TEMPERATURE = 32 ; # [doc = "Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage)."] const MAV_BATTERY_FAULT_INCOMPATIBLE_VOLTAGE = 64 ; # [doc = "Battery firmware is not compatible with current autopilot firmware."] const MAV_BATTERY_FAULT_INCOMPATIBLE_FIRMWARE = 128 ; # [doc = "Battery is not compatible due to cell configuration (e.g. 5s1p when vehicle requires 6s)."] const BATTERY_FAULT_INCOMPATIBLE_CELLS_CONFIGURATION = 256 ; } }
impl Default for MavBatteryFault {
fn default() -> Self {
Self::MAV_BATTERY_FAULT_DEEP_DISCHARGE
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "Gimbal device (low level) error flags (bitmap, 0 means no error)"] pub struct GimbalDeviceErrorFlags : u32 { # [doc = "Gimbal device is limited by hardware roll limit."] const GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT = 1 ; # [doc = "Gimbal device is limited by hardware pitch limit."] const GIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT = 2 ; # [doc = "Gimbal device is limited by hardware yaw limit."] const GIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT = 4 ; # [doc = "There is an error with the gimbal encoders."] const GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR = 8 ; # [doc = "There is an error with the gimbal power source."] const GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR = 16 ; # [doc = "There is an error with the gimbal motors."] const GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR = 32 ; # [doc = "There is an error with the gimbal's software."] const GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR = 64 ; # [doc = "There is an error with the gimbal's communication."] const GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR = 128 ; # [doc = "Gimbal device is currently calibrating."] const GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING = 256 ; # [doc = "Gimbal device is not assigned to a gimbal manager."] const GIMBAL_DEVICE_ERROR_FLAGS_NO_MANAGER = 512 ; } }
impl Default for GimbalDeviceErrorFlags {
fn default() -> Self {
Self::GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "RC type"]
pub enum RcType {
#[doc = "Spektrum DSM2"]
RC_TYPE_SPEKTRUM_DSM2 = 0,
#[doc = "Spektrum DSMX"]
RC_TYPE_SPEKTRUM_DSMX = 1,
}
impl Default for RcType {
fn default() -> Self {
Self::RC_TYPE_SPEKTRUM_DSM2
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "Flags to report failure cases over the high latency telemtry."] pub struct HlFailureFlag : u16 { # [doc = "GPS failure."] const HL_FAILURE_FLAG_GPS = 1 ; # [doc = "Differential pressure sensor failure."] const HL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE = 2 ; # [doc = "Absolute pressure sensor failure."] const HL_FAILURE_FLAG_ABSOLUTE_PRESSURE = 4 ; # [doc = "Accelerometer sensor failure."] const HL_FAILURE_FLAG_3D_ACCEL = 8 ; # [doc = "Gyroscope sensor failure."] const HL_FAILURE_FLAG_3D_GYRO = 16 ; # [doc = "Magnetometer sensor failure."] const HL_FAILURE_FLAG_3D_MAG = 32 ; # [doc = "Terrain subsystem failure."] const HL_FAILURE_FLAG_TERRAIN = 64 ; # [doc = "Battery failure/critical low battery."] const HL_FAILURE_FLAG_BATTERY = 128 ; # [doc = "RC receiver failure/no rc connection."] const HL_FAILURE_FLAG_RC_RECEIVER = 256 ; # [doc = "Offboard link failure."] const HL_FAILURE_FLAG_OFFBOARD_LINK = 512 ; # [doc = "Engine failure."] const HL_FAILURE_FLAG_ENGINE = 1024 ; # [doc = "Geofence violation."] const HL_FAILURE_FLAG_GEOFENCE = 2048 ; # [doc = "Estimator failure, for example measurement rejection or large variances."] const HL_FAILURE_FLAG_ESTIMATOR = 4096 ; # [doc = "Mission failure."] const HL_FAILURE_FLAG_MISSION = 8192 ; } }
impl Default for HlFailureFlag {
fn default() -> Self {
Self::HL_FAILURE_FLAG_GPS
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum MavState {
#[doc = "Uninitialized system, state is unknown."]
MAV_STATE_UNINIT = 0,
#[doc = "System is booting up."]
MAV_STATE_BOOT = 1,
#[doc = "System is calibrating and not flight-ready."]
MAV_STATE_CALIBRATING = 2,
#[doc = "System is grounded and on standby. It can be launched any time."]
MAV_STATE_STANDBY = 3,
#[doc = "System is active and might be already airborne. Motors are engaged."]
MAV_STATE_ACTIVE = 4,
#[doc = "System is in a non-normal flight mode. It can however still navigate."]
MAV_STATE_CRITICAL = 5,
#[doc = "System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down."]
MAV_STATE_EMERGENCY = 6,
#[doc = "System just initialized its power-down sequence, will shut down now."]
MAV_STATE_POWEROFF = 7,
#[doc = "System is terminating itself."]
MAV_STATE_FLIGHT_TERMINATION = 8,
}
impl Default for MavState {
fn default() -> Self {
Self::MAV_STATE_UNINIT
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "Flags in ESTIMATOR_STATUS message"] pub struct EstimatorStatusFlags : u16 { # [doc = "True if the attitude estimate is good"] const ESTIMATOR_ATTITUDE = 1 ; # [doc = "True if the horizontal velocity estimate is good"] const ESTIMATOR_VELOCITY_HORIZ = 2 ; # [doc = "True if the vertical velocity estimate is good"] const ESTIMATOR_VELOCITY_VERT = 4 ; # [doc = "True if the horizontal position (relative) estimate is good"] const ESTIMATOR_POS_HORIZ_REL = 8 ; # [doc = "True if the horizontal position (absolute) estimate is good"] const ESTIMATOR_POS_HORIZ_ABS = 16 ; # [doc = "True if the vertical position (absolute) estimate is good"] const ESTIMATOR_POS_VERT_ABS = 32 ; # [doc = "True if the vertical position (above ground) estimate is good"] const ESTIMATOR_POS_VERT_AGL = 64 ; # [doc = "True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow)"] const ESTIMATOR_CONST_POS_MODE = 128 ; # [doc = "True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate"] const ESTIMATOR_PRED_POS_HORIZ_REL = 256 ; # [doc = "True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate"] const ESTIMATOR_PRED_POS_HORIZ_ABS = 512 ; # [doc = "True if the EKF has detected a GPS glitch"] const ESTIMATOR_GPS_GLITCH = 1024 ; # [doc = "True if the EKF has detected bad accelerometer data"] const ESTIMATOR_ACCEL_ERROR = 2048 ; } }
impl Default for EstimatorStatusFlags {
fn default() -> Self {
Self::ESTIMATOR_ATTITUDE
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] pub struct GpsInputIgnoreFlags : u16 { # [doc = "ignore altitude field"] const GPS_INPUT_IGNORE_FLAG_ALT = 1 ; # [doc = "ignore hdop field"] const GPS_INPUT_IGNORE_FLAG_HDOP = 2 ; # [doc = "ignore vdop field"] const GPS_INPUT_IGNORE_FLAG_VDOP = 4 ; # [doc = "ignore horizontal velocity field (vn and ve)"] const GPS_INPUT_IGNORE_FLAG_VEL_HORIZ = 8 ; # [doc = "ignore vertical velocity field (vd)"] const GPS_INPUT_IGNORE_FLAG_VEL_VERT = 16 ; # [doc = "ignore speed accuracy field"] const GPS_INPUT_IGNORE_FLAG_SPEED_ACCURACY = 32 ; # [doc = "ignore horizontal accuracy field"] const GPS_INPUT_IGNORE_FLAG_HORIZONTAL_ACCURACY = 64 ; # [doc = "ignore vertical accuracy field"] const GPS_INPUT_IGNORE_FLAG_VERTICAL_ACCURACY = 128 ; } }
impl Default for GpsInputIgnoreFlags {
fn default() -> Self {
Self::GPS_INPUT_IGNORE_FLAG_ALT
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Enumeration for battery charge states."]
pub enum MavBatteryChargeState {
#[doc = "Low battery state is not provided"]
MAV_BATTERY_CHARGE_STATE_UNDEFINED = 0,
#[doc = "Battery is not in low state. Normal operation."]
MAV_BATTERY_CHARGE_STATE_OK = 1,
#[doc = "Battery state is low, warn and monitor close."]
MAV_BATTERY_CHARGE_STATE_LOW = 2,
#[doc = "Battery state is critical, return or abort immediately."]
MAV_BATTERY_CHARGE_STATE_CRITICAL = 3,
#[doc = "Battery state is too low for ordinary abort sequence. Perform fastest possible emergency stop to prevent damage."]
MAV_BATTERY_CHARGE_STATE_EMERGENCY = 4,
#[doc = "Battery failed, damage unavoidable. Possible causes (faults) are listed in MAV_BATTERY_FAULT."]
MAV_BATTERY_CHARGE_STATE_FAILED = 5,
#[doc = "Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in MAV_BATTERY_FAULT."]
MAV_BATTERY_CHARGE_STATE_UNHEALTHY = 6,
#[doc = "Battery is charging."]
MAV_BATTERY_CHARGE_STATE_CHARGING = 7,
}
impl Default for MavBatteryChargeState {
fn default() -> Self {
Self::MAV_BATTERY_CHARGE_STATE_UNDEFINED
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "Status flags for ADS-B transponder dynamic output"] pub struct UavionixAdsbRfHealth : u8 { const UAVIONIX_ADSB_RF_HEALTH_INITIALIZING = 0 ; const UAVIONIX_ADSB_RF_HEALTH_OK = 1 ; const UAVIONIX_ADSB_RF_HEALTH_FAIL_TX = 2 ; const UAVIONIX_ADSB_RF_HEALTH_FAIL_RX = 16 ; } }
impl Default for UavionixAdsbRfHealth {
fn default() -> Self {
Self::UAVIONIX_ADSB_RF_HEALTH_INITIALIZING
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum GoproHeartbeatStatus {
#[doc = "No GoPro connected."]
GOPRO_HEARTBEAT_STATUS_DISCONNECTED = 0,
#[doc = "The detected GoPro is not HeroBus compatible."]
GOPRO_HEARTBEAT_STATUS_INCOMPATIBLE = 1,
#[doc = "A HeroBus compatible GoPro is connected."]
GOPRO_HEARTBEAT_STATUS_CONNECTED = 2,
#[doc = "An unrecoverable error was encountered with the connected GoPro, it may require a power cycle."]
GOPRO_HEARTBEAT_STATUS_ERROR = 3,
}
impl Default for GoproHeartbeatStatus {
fn default() -> Self {
Self::GOPRO_HEARTBEAT_STATUS_DISCONNECTED
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum GoproCharging {
#[doc = "Charging disabled."]
GOPRO_CHARGING_DISABLED = 0,
#[doc = "Charging enabled."]
GOPRO_CHARGING_ENABLED = 1,
}
impl Default for GoproCharging {
fn default() -> Self {
Self::GOPRO_CHARGING_DISABLED
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Type of GPS fix"]
pub enum GpsFixType {
#[doc = "No GPS connected"]
GPS_FIX_TYPE_NO_GPS = 0,
#[doc = "No position information, GPS is connected"]
GPS_FIX_TYPE_NO_FIX = 1,
#[doc = "2D position"]
GPS_FIX_TYPE_2D_FIX = 2,
#[doc = "3D position"]
GPS_FIX_TYPE_3D_FIX = 3,
#[doc = "DGPS/SBAS aided 3D position"]
GPS_FIX_TYPE_DGPS = 4,
#[doc = "RTK float, 3D position"]
GPS_FIX_TYPE_RTK_FLOAT = 5,
#[doc = "RTK Fixed, 3D position"]
GPS_FIX_TYPE_RTK_FIXED = 6,
#[doc = "Static fixed, typically used for base stations"]
GPS_FIX_TYPE_STATIC = 7,
#[doc = "PPP, 3D position."]
GPS_FIX_TYPE_PPP = 8,
}
impl Default for GpsFixType {
fn default() -> Self {
Self::GPS_FIX_TYPE_NO_GPS
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "MAVLINK component type reported in HEARTBEAT message. Flight controllers must report the type of the vehicle on which they are mounted (e.g. MAV_TYPE_OCTOROTOR). All other components must report a value appropriate for their type (e.g. a camera must use MAV_TYPE_CAMERA)."]
pub enum MavType {
#[doc = "Generic micro air vehicle"]
MAV_TYPE_GENERIC = 0,
#[doc = "Fixed wing aircraft."]
MAV_TYPE_FIXED_WING = 1,
#[doc = "Quadrotor"]
MAV_TYPE_QUADROTOR = 2,
#[doc = "Coaxial helicopter"]
MAV_TYPE_COAXIAL = 3,
#[doc = "Normal helicopter with tail rotor."]
MAV_TYPE_HELICOPTER = 4,
#[doc = "Ground installation"]
MAV_TYPE_ANTENNA_TRACKER = 5,
#[doc = "Operator control unit / ground control station"]
MAV_TYPE_GCS = 6,
#[doc = "Airship, controlled"]
MAV_TYPE_AIRSHIP = 7,
#[doc = "Free balloon, uncontrolled"]
MAV_TYPE_FREE_BALLOON = 8,
#[doc = "Rocket"]
MAV_TYPE_ROCKET = 9,
#[doc = "Ground rover"]
MAV_TYPE_GROUND_ROVER = 10,
#[doc = "Surface vessel, boat, ship"]
MAV_TYPE_SURFACE_BOAT = 11,
#[doc = "Submarine"]
MAV_TYPE_SUBMARINE = 12,
#[doc = "Hexarotor"]
MAV_TYPE_HEXAROTOR = 13,
#[doc = "Octorotor"]
MAV_TYPE_OCTOROTOR = 14,
#[doc = "Tricopter"]
MAV_TYPE_TRICOPTER = 15,
#[doc = "Flapping wing"]
MAV_TYPE_FLAPPING_WING = 16,
#[doc = "Kite"]
MAV_TYPE_KITE = 17,
#[doc = "Onboard companion controller"]
MAV_TYPE_ONBOARD_CONTROLLER = 18,
#[doc = "Two-rotor Tailsitter VTOL that additionally uses control surfaces in vertical operation. Note, value previously named MAV_TYPE_VTOL_DUOROTOR."]
MAV_TYPE_VTOL_TAILSITTER_DUOROTOR = 19,
#[doc = "Quad-rotor Tailsitter VTOL using a V-shaped quad config in vertical operation. Note: value previously named MAV_TYPE_VTOL_QUADROTOR."]
MAV_TYPE_VTOL_TAILSITTER_QUADROTOR = 20,
#[doc = "Tiltrotor VTOL. Fuselage and wings stay (nominally) horizontal in all flight phases. It able to tilt (some) rotors to provide thrust in cruise flight."]
MAV_TYPE_VTOL_TILTROTOR = 21,
#[doc = "VTOL with separate fixed rotors for hover and cruise flight. Fuselage and wings stay (nominally) horizontal in all flight phases."]
MAV_TYPE_VTOL_FIXEDROTOR = 22,
#[doc = "Tailsitter VTOL. Fuselage and wings orientation changes depending on flight phase: vertical for hover, horizontal for cruise. Use more specific VTOL MAV_TYPE_VTOL_DUOROTOR or MAV_TYPE_VTOL_QUADROTOR if appropriate."]
MAV_TYPE_VTOL_TAILSITTER = 23,
#[doc = "Tiltwing VTOL. Fuselage stays horizontal in all flight phases. The whole wing, along with any attached engine, can tilt between vertical and horizontal mode."]
MAV_TYPE_VTOL_TILTWING = 24,
#[doc = "VTOL reserved 5"]
MAV_TYPE_VTOL_RESERVED5 = 25,
#[doc = "Gimbal"]
MAV_TYPE_GIMBAL = 26,
#[doc = "ADSB system"]
MAV_TYPE_ADSB = 27,
#[doc = "Steerable, nonrigid airfoil"]
MAV_TYPE_PARAFOIL = 28,
#[doc = "Dodecarotor"]
MAV_TYPE_DODECAROTOR = 29,
#[doc = "Camera"]
MAV_TYPE_CAMERA = 30,
#[doc = "Charging station"]
MAV_TYPE_CHARGING_STATION = 31,
#[doc = "FLARM collision avoidance system"]
MAV_TYPE_FLARM = 32,
#[doc = "Servo"]
MAV_TYPE_SERVO = 33,
#[doc = "Open Drone ID. See https://mavlink.io/en/services/opendroneid.html."]
MAV_TYPE_ODID = 34,
#[doc = "Decarotor"]
MAV_TYPE_DECAROTOR = 35,
#[doc = "Battery"]
MAV_TYPE_BATTERY = 36,
#[doc = "Parachute"]
MAV_TYPE_PARACHUTE = 37,
#[doc = "Log"]
MAV_TYPE_LOG = 38,
#[doc = "OSD"]
MAV_TYPE_OSD = 39,
#[doc = "IMU"]
MAV_TYPE_IMU = 40,
#[doc = "GPS"]
MAV_TYPE_GPS = 41,
#[doc = "Winch"]
MAV_TYPE_WINCH = 42,
}
impl Default for MavType {
fn default() -> Self {
Self::MAV_TYPE_GENERIC
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Enumeration of the ADSB altimeter types"]
pub enum AdsbAltitudeType {
#[doc = "Altitude reported from a Baro source using QNH reference"]
ADSB_ALTITUDE_TYPE_PRESSURE_QNH = 0,
#[doc = "Altitude reported from a GNSS source"]
ADSB_ALTITUDE_TYPE_GEOMETRIC = 1,
}
impl Default for AdsbAltitudeType {
fn default() -> Self {
Self::ADSB_ALTITUDE_TYPE_PRESSURE_QNH
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum GimbalAxis {
#[doc = "Gimbal yaw axis."]
GIMBAL_AXIS_YAW = 0,
#[doc = "Gimbal pitch axis."]
GIMBAL_AXIS_PITCH = 1,
#[doc = "Gimbal roll axis."]
GIMBAL_AXIS_ROLL = 2,
}
impl Default for GimbalAxis {
fn default() -> Self {
Self::GIMBAL_AXIS_YAW
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Enumeration of landed detector states"]
pub enum MavLandedState {
#[doc = "MAV landed state is unknown"]
MAV_LANDED_STATE_UNDEFINED = 0,
#[doc = "MAV is landed (on ground)"]
MAV_LANDED_STATE_ON_GROUND = 1,
#[doc = "MAV is in air"]
MAV_LANDED_STATE_IN_AIR = 2,
#[doc = "MAV currently taking off"]
MAV_LANDED_STATE_TAKEOFF = 3,
#[doc = "MAV currently landing"]
MAV_LANDED_STATE_LANDING = 4,
}
impl Default for MavLandedState {
fn default() -> Self {
Self::MAV_LANDED_STATE_UNDEFINED
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Battery mode. Note, the normal operation mode (i.e. when flying) should be reported as MAV_BATTERY_MODE_UNKNOWN to allow message trimming in normal flight."]
pub enum MavBatteryMode {
#[doc = "Battery mode not supported/unknown battery mode/normal operation."]
MAV_BATTERY_MODE_UNKNOWN = 0,
#[doc = "Battery is auto discharging (towards storage level)."]
MAV_BATTERY_MODE_AUTO_DISCHARGING = 1,
#[doc = "Battery in hot-swap mode (current limited to prevent spikes that might damage sensitive electrical circuits)."]
MAV_BATTERY_MODE_HOT_SWAP = 2,
}
impl Default for MavBatteryMode {
fn default() -> Self {
Self::MAV_BATTERY_MODE_UNKNOWN
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum SpeedType {
SPEED_TYPE_AIRSPEED = 0,
SPEED_TYPE_GROUNDSPEED = 1,
}
impl Default for SpeedType {
fn default() -> Self {
Self::SPEED_TYPE_AIRSPEED
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "These flags are used to diagnose the failure state of CELLULAR_STATUS"]
pub enum CellularNetworkFailedReason {
#[doc = "No error"]
CELLULAR_NETWORK_FAILED_REASON_NONE = 0,
#[doc = "Error state is unknown"]
CELLULAR_NETWORK_FAILED_REASON_UNKNOWN = 1,
#[doc = "SIM is required for the modem but missing"]
CELLULAR_NETWORK_FAILED_REASON_SIM_MISSING = 2,
#[doc = "SIM is available, but not usable for connection"]
CELLULAR_NETWORK_FAILED_REASON_SIM_ERROR = 3,
}
impl Default for CellularNetworkFailedReason {
fn default() -> Self {
Self::CELLULAR_NETWORK_FAILED_REASON_NONE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Coordinate frames used by MAVLink. Not all frames are supported by all commands, messages, or vehicles. Global frames use the following naming conventions: - \"GLOBAL\": Global coordinate frame with WGS84 latitude/longitude and altitude positive over mean sea level (MSL) by default. The following modifiers may be used with \"GLOBAL\": - \"RELATIVE_ALT\": Altitude is relative to the vehicle home position rather than MSL. - \"TERRAIN_ALT\": Altitude is relative to ground level rather than MSL. - \"INT\": Latitude/longitude (in degrees) are scaled by multiplying by 1E7. Local frames use the following naming conventions: - \"LOCAL\": Origin of local frame is fixed relative to earth. Unless otherwise specified this origin is the origin of the vehicle position-estimator (\"EKF\"). - \"BODY\": Origin of local frame travels with the vehicle. NOTE, \"BODY\" does NOT indicate alignment of frame axis with vehicle attitude. - \"OFFSET\": Deprecated synonym for \"BODY\" (origin travels with the vehicle). Not to be used for new frames. Some deprecated frames do not follow these conventions (e.g. MAV_FRAME_BODY_NED and MAV_FRAME_BODY_OFFSET_NED)."]
pub enum MavFrame {
#[doc = "Global (WGS84) coordinate frame + MSL altitude. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL)."]
MAV_FRAME_GLOBAL = 0,
#[doc = "NED local tangent frame (x: North, y: East, z: Down) with origin fixed relative to earth."]
MAV_FRAME_LOCAL_NED = 1,
#[doc = "NOT a coordinate frame, indicates a mission command."]
MAV_FRAME_MISSION = 2,
#[doc = "Global (WGS84) coordinate frame + altitude relative to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home position."]
MAV_FRAME_GLOBAL_RELATIVE_ALT = 3,
#[doc = "ENU local tangent frame (x: East, y: North, z: Up) with origin fixed relative to earth."]
MAV_FRAME_LOCAL_ENU = 4,
#[doc = "Global (WGS84) coordinate frame (scaled) + MSL altitude. First value / x: latitude in degrees*1E7, second value / y: longitude in degrees*1E7, third value / z: positive altitude over mean sea level (MSL)."]
MAV_FRAME_GLOBAL_INT = 5,
#[doc = "Global (WGS84) coordinate frame (scaled) + altitude relative to the home position. First value / x: latitude in degrees*1E7, second value / y: longitude in degrees*1E7, third value / z: positive altitude with 0 being at the altitude of the home position."]
MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6,
#[doc = "NED local tangent frame (x: North, y: East, z: Down) with origin that travels with the vehicle."]
MAV_FRAME_LOCAL_OFFSET_NED = 7,
#[doc = "Same as MAV_FRAME_LOCAL_NED when used to represent position values. Same as MAV_FRAME_BODY_FRD when used with velocity/acceleration values."]
MAV_FRAME_BODY_NED = 8,
#[doc = "This is the same as MAV_FRAME_BODY_FRD."]
MAV_FRAME_BODY_OFFSET_NED = 9,
#[doc = "Global (WGS84) coordinate frame with AGL altitude (at the waypoint coordinate). First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model."]
MAV_FRAME_GLOBAL_TERRAIN_ALT = 10,
#[doc = "Global (WGS84) coordinate frame (scaled) with AGL altitude (at the waypoint coordinate). First value / x: latitude in degrees*1E7, second value / y: longitude in degrees*1E7, third value / z: positive altitude in meters with 0 being at ground level in terrain model."]
MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11,
#[doc = "FRD local frame aligned to the vehicle's attitude (x: Forward, y: Right, z: Down) with an origin that travels with vehicle."]
MAV_FRAME_BODY_FRD = 12,
#[doc = "MAV_FRAME_BODY_FLU - Body fixed frame of reference, Z-up (x: Forward, y: Left, z: Up)."]
MAV_FRAME_RESERVED_13 = 13,
#[doc = "MAV_FRAME_MOCAP_NED - Odometry local coordinate frame of data given by a motion capture system, Z-down (x: North, y: East, z: Down)."]
MAV_FRAME_RESERVED_14 = 14,
#[doc = "MAV_FRAME_MOCAP_ENU - Odometry local coordinate frame of data given by a motion capture system, Z-up (x: East, y: North, z: Up)."]
MAV_FRAME_RESERVED_15 = 15,
#[doc = "MAV_FRAME_VISION_NED - Odometry local coordinate frame of data given by a vision estimation system, Z-down (x: North, y: East, z: Down)."]
MAV_FRAME_RESERVED_16 = 16,
#[doc = "MAV_FRAME_VISION_ENU - Odometry local coordinate frame of data given by a vision estimation system, Z-up (x: East, y: North, z: Up)."]
MAV_FRAME_RESERVED_17 = 17,
#[doc = "MAV_FRAME_ESTIM_NED - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-down (x: North, y: East, z: Down)."]
MAV_FRAME_RESERVED_18 = 18,
#[doc = "MAV_FRAME_ESTIM_ENU - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-up (x: East, y: North, z: Up)."]
MAV_FRAME_RESERVED_19 = 19,
#[doc = "FRD local tangent frame (x: Forward, y: Right, z: Down) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane."]
MAV_FRAME_LOCAL_FRD = 20,
#[doc = "FLU local tangent frame (x: Forward, y: Left, z: Up) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane."]
MAV_FRAME_LOCAL_FLU = 21,
}
impl Default for MavFrame {
fn default() -> Self {
Self::MAV_FRAME_GLOBAL
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 9 is set the floats afx afy afz should be interpreted as force instead of acceleration."] pub struct PositionTargetTypemask : u16 { # [doc = "Ignore position x"] const POSITION_TARGET_TYPEMASK_X_IGNORE = 1 ; # [doc = "Ignore position y"] const POSITION_TARGET_TYPEMASK_Y_IGNORE = 2 ; # [doc = "Ignore position z"] const POSITION_TARGET_TYPEMASK_Z_IGNORE = 4 ; # [doc = "Ignore velocity x"] const POSITION_TARGET_TYPEMASK_VX_IGNORE = 8 ; # [doc = "Ignore velocity y"] const POSITION_TARGET_TYPEMASK_VY_IGNORE = 16 ; # [doc = "Ignore velocity z"] const POSITION_TARGET_TYPEMASK_VZ_IGNORE = 32 ; # [doc = "Ignore acceleration x"] const POSITION_TARGET_TYPEMASK_AX_IGNORE = 64 ; # [doc = "Ignore acceleration y"] const POSITION_TARGET_TYPEMASK_AY_IGNORE = 128 ; # [doc = "Ignore acceleration z"] const POSITION_TARGET_TYPEMASK_AZ_IGNORE = 256 ; # [doc = "Use force instead of acceleration"] const POSITION_TARGET_TYPEMASK_FORCE_SET = 512 ; # [doc = "Ignore yaw"] const POSITION_TARGET_TYPEMASK_YAW_IGNORE = 1024 ; # [doc = "Ignore yaw rate"] const POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE = 2048 ; } }
impl Default for PositionTargetTypemask {
fn default() -> Self {
Self::POSITION_TARGET_TYPEMASK_X_IGNORE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Type of AIS vessel, enum duplicated from AIS standard, https://gpsd.gitlab.io/gpsd/AIVDM.html"]
pub enum AisType {
#[doc = "Not available (default)."]
AIS_TYPE_UNKNOWN = 0,
AIS_TYPE_RESERVED_1 = 1,
AIS_TYPE_RESERVED_2 = 2,
AIS_TYPE_RESERVED_3 = 3,
AIS_TYPE_RESERVED_4 = 4,
AIS_TYPE_RESERVED_5 = 5,
AIS_TYPE_RESERVED_6 = 6,
AIS_TYPE_RESERVED_7 = 7,
AIS_TYPE_RESERVED_8 = 8,
AIS_TYPE_RESERVED_9 = 9,
AIS_TYPE_RESERVED_10 = 10,
AIS_TYPE_RESERVED_11 = 11,
AIS_TYPE_RESERVED_12 = 12,
AIS_TYPE_RESERVED_13 = 13,
AIS_TYPE_RESERVED_14 = 14,
AIS_TYPE_RESERVED_15 = 15,
AIS_TYPE_RESERVED_16 = 16,
AIS_TYPE_RESERVED_17 = 17,
AIS_TYPE_RESERVED_18 = 18,
AIS_TYPE_RESERVED_19 = 19,
#[doc = "Wing In Ground effect."]
AIS_TYPE_WIG = 20,
AIS_TYPE_WIG_HAZARDOUS_A = 21,
AIS_TYPE_WIG_HAZARDOUS_B = 22,
AIS_TYPE_WIG_HAZARDOUS_C = 23,
AIS_TYPE_WIG_HAZARDOUS_D = 24,
AIS_TYPE_WIG_RESERVED_1 = 25,
AIS_TYPE_WIG_RESERVED_2 = 26,
AIS_TYPE_WIG_RESERVED_3 = 27,
AIS_TYPE_WIG_RESERVED_4 = 28,
AIS_TYPE_WIG_RESERVED_5 = 29,
AIS_TYPE_FISHING = 30,
AIS_TYPE_TOWING = 31,
#[doc = "Towing: length exceeds 200m or breadth exceeds 25m."]
AIS_TYPE_TOWING_LARGE = 32,
#[doc = "Dredging or other underwater ops."]
AIS_TYPE_DREDGING = 33,
AIS_TYPE_DIVING = 34,
AIS_TYPE_MILITARY = 35,
AIS_TYPE_SAILING = 36,
AIS_TYPE_PLEASURE = 37,
AIS_TYPE_RESERVED_20 = 38,
AIS_TYPE_RESERVED_21 = 39,
#[doc = "High Speed Craft."]
AIS_TYPE_HSC = 40,
AIS_TYPE_HSC_HAZARDOUS_A = 41,
AIS_TYPE_HSC_HAZARDOUS_B = 42,
AIS_TYPE_HSC_HAZARDOUS_C = 43,
AIS_TYPE_HSC_HAZARDOUS_D = 44,
AIS_TYPE_HSC_RESERVED_1 = 45,
AIS_TYPE_HSC_RESERVED_2 = 46,
AIS_TYPE_HSC_RESERVED_3 = 47,
AIS_TYPE_HSC_RESERVED_4 = 48,
AIS_TYPE_HSC_UNKNOWN = 49,
AIS_TYPE_PILOT = 50,
#[doc = "Search And Rescue vessel."]
AIS_TYPE_SAR = 51,
AIS_TYPE_TUG = 52,
AIS_TYPE_PORT_TENDER = 53,
#[doc = "Anti-pollution equipment."]
AIS_TYPE_ANTI_POLLUTION = 54,
AIS_TYPE_LAW_ENFORCEMENT = 55,
AIS_TYPE_SPARE_LOCAL_1 = 56,
AIS_TYPE_SPARE_LOCAL_2 = 57,
AIS_TYPE_MEDICAL_TRANSPORT = 58,
#[doc = "Noncombatant ship according to RR Resolution No. 18."]
AIS_TYPE_NONECOMBATANT = 59,
AIS_TYPE_PASSENGER = 60,
AIS_TYPE_PASSENGER_HAZARDOUS_A = 61,
AIS_TYPE_PASSENGER_HAZARDOUS_B = 62,
AIS_TYPE_PASSENGER_HAZARDOUS_C = 63,
AIS_TYPE_PASSENGER_HAZARDOUS_D = 64,
AIS_TYPE_PASSENGER_RESERVED_1 = 65,
AIS_TYPE_PASSENGER_RESERVED_2 = 66,
AIS_TYPE_PASSENGER_RESERVED_3 = 67,
AIS_TYPE_PASSENGER_RESERVED_4 = 68,
AIS_TYPE_PASSENGER_UNKNOWN = 69,
AIS_TYPE_CARGO = 70,
AIS_TYPE_CARGO_HAZARDOUS_A = 71,
AIS_TYPE_CARGO_HAZARDOUS_B = 72,
AIS_TYPE_CARGO_HAZARDOUS_C = 73,
AIS_TYPE_CARGO_HAZARDOUS_D = 74,
AIS_TYPE_CARGO_RESERVED_1 = 75,
AIS_TYPE_CARGO_RESERVED_2 = 76,
AIS_TYPE_CARGO_RESERVED_3 = 77,
AIS_TYPE_CARGO_RESERVED_4 = 78,
AIS_TYPE_CARGO_UNKNOWN = 79,
AIS_TYPE_TANKER = 80,
AIS_TYPE_TANKER_HAZARDOUS_A = 81,
AIS_TYPE_TANKER_HAZARDOUS_B = 82,
AIS_TYPE_TANKER_HAZARDOUS_C = 83,
AIS_TYPE_TANKER_HAZARDOUS_D = 84,
AIS_TYPE_TANKER_RESERVED_1 = 85,
AIS_TYPE_TANKER_RESERVED_2 = 86,
AIS_TYPE_TANKER_RESERVED_3 = 87,
AIS_TYPE_TANKER_RESERVED_4 = 88,
AIS_TYPE_TANKER_UNKNOWN = 89,
AIS_TYPE_OTHER = 90,
AIS_TYPE_OTHER_HAZARDOUS_A = 91,
AIS_TYPE_OTHER_HAZARDOUS_B = 92,
AIS_TYPE_OTHER_HAZARDOUS_C = 93,
AIS_TYPE_OTHER_HAZARDOUS_D = 94,
AIS_TYPE_OTHER_RESERVED_1 = 95,
AIS_TYPE_OTHER_RESERVED_2 = 96,
AIS_TYPE_OTHER_RESERVED_3 = 97,
AIS_TYPE_OTHER_RESERVED_4 = 98,
AIS_TYPE_OTHER_UNKNOWN = 99,
}
impl Default for AisType {
fn default() -> Self {
Self::AIS_TYPE_UNKNOWN
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Actions that may be specified in MAV_CMD_OVERRIDE_GOTO to override mission execution."]
pub enum MavGoto {
#[doc = "Hold at the current position."]
MAV_GOTO_DO_HOLD = 0,
#[doc = "Continue with the next item in mission execution."]
MAV_GOTO_DO_CONTINUE = 1,
#[doc = "Hold at the current position of the system"]
MAV_GOTO_HOLD_AT_CURRENT_POSITION = 2,
#[doc = "Hold at the position specified in the parameters of the DO_HOLD action"]
MAV_GOTO_HOLD_AT_SPECIFIED_POSITION = 3,
}
impl Default for MavGoto {
fn default() -> Self {
Self::MAV_GOTO_DO_HOLD
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "MAV FTP error codes (https://mavlink.io/en/services/ftp.html)"]
pub enum MavFtpErr {
#[doc = "None: No error"]
MAV_FTP_ERR_NONE = 0,
#[doc = "Fail: Unknown failure"]
MAV_FTP_ERR_FAIL = 1,
#[doc = "FailErrno: Command failed, Err number sent back in PayloadHeader.data[1]. \t\tThis is a file-system error number understood by the server operating system."]
MAV_FTP_ERR_FAILERRNO = 2,
#[doc = "InvalidDataSize: Payload size is invalid"]
MAV_FTP_ERR_INVALIDDATASIZE = 3,
#[doc = "InvalidSession: Session is not currently open"]
MAV_FTP_ERR_INVALIDSESSION = 4,
#[doc = "NoSessionsAvailable: All available sessions are already in use"]
MAV_FTP_ERR_NOSESSIONSAVAILABLE = 5,
#[doc = "EOF: Offset past end of file for ListDirectory and ReadFile commands"]
MAV_FTP_ERR_EOF = 6,
#[doc = "UnknownCommand: Unknown command / opcode"]
MAV_FTP_ERR_UNKNOWNCOMMAND = 7,
#[doc = "FileExists: File/directory already exists"]
MAV_FTP_ERR_FILEEXISTS = 8,
#[doc = "FileProtected: File/directory is write protected"]
MAV_FTP_ERR_FILEPROTECTED = 9,
#[doc = "FileNotFound: File/directory not found"]
MAV_FTP_ERR_FILENOTFOUND = 10,
}
impl Default for MavFtpErr {
fn default() -> Self {
Self::MAV_FTP_ERR_NONE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Component ids (values) for the different types and instances of onboard hardware/software that might make up a MAVLink system (autopilot, cameras, servos, GPS systems, avoidance systems etc.). Components must use the appropriate ID in their source address when sending messages. Components can also use IDs to determine if they are the intended recipient of an incoming message. The MAV_COMP_ID_ALL value is used to indicate messages that must be processed by all components. When creating new entries, components that can have multiple instances (e.g. cameras, servos etc.) should be allocated sequential values. An appropriate number of values should be left free after these components to allow the number of instances to be expanded."]
pub enum MavComponent {
#[doc = "Target id (target_component) used to broadcast messages to all components of the receiving system. Components should attempt to process messages with this component ID and forward to components on any other interfaces. Note: This is not a valid *source* component id for a message."]
MAV_COMP_ID_ALL = 0,
#[doc = "System flight controller component (\"autopilot\"). Only one autopilot is expected in a particular system."]
MAV_COMP_ID_AUTOPILOT1 = 1,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER1 = 25,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER2 = 26,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER3 = 27,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER4 = 28,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER5 = 29,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER6 = 30,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER7 = 31,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER8 = 32,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER9 = 33,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER10 = 34,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER11 = 35,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER12 = 36,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER13 = 37,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER14 = 38,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER15 = 39,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER16 = 40,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER17 = 41,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER18 = 42,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER19 = 43,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER20 = 44,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER21 = 45,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER22 = 46,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER23 = 47,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER24 = 48,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER25 = 49,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER26 = 50,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER27 = 51,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER28 = 52,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER29 = 53,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER30 = 54,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER31 = 55,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER32 = 56,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER33 = 57,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER34 = 58,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER35 = 59,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER36 = 60,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER37 = 61,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER38 = 62,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER39 = 63,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER40 = 64,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER41 = 65,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER42 = 66,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER43 = 67,
#[doc = "Telemetry radio (e.g. SiK radio, or other component that emits RADIO_STATUS messages)."]
MAV_COMP_ID_TELEMETRY_RADIO = 68,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER45 = 69,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER46 = 70,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER47 = 71,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER48 = 72,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER49 = 73,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER50 = 74,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER51 = 75,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER52 = 76,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER53 = 77,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER54 = 78,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER55 = 79,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER56 = 80,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER57 = 81,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER58 = 82,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER59 = 83,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER60 = 84,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER61 = 85,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER62 = 86,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER63 = 87,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER64 = 88,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER65 = 89,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER66 = 90,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER67 = 91,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER68 = 92,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER69 = 93,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER70 = 94,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER71 = 95,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER72 = 96,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER73 = 97,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER74 = 98,
#[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
MAV_COMP_ID_USER75 = 99,
#[doc = "Camera #1."]
MAV_COMP_ID_CAMERA = 100,
#[doc = "Camera #2."]
MAV_COMP_ID_CAMERA2 = 101,
#[doc = "Camera #3."]
MAV_COMP_ID_CAMERA3 = 102,
#[doc = "Camera #4."]
MAV_COMP_ID_CAMERA4 = 103,
#[doc = "Camera #5."]
MAV_COMP_ID_CAMERA5 = 104,
#[doc = "Camera #6."]
MAV_COMP_ID_CAMERA6 = 105,
#[doc = "Servo #1."]
MAV_COMP_ID_SERVO1 = 140,
#[doc = "Servo #2."]
MAV_COMP_ID_SERVO2 = 141,
#[doc = "Servo #3."]
MAV_COMP_ID_SERVO3 = 142,
#[doc = "Servo #4."]
MAV_COMP_ID_SERVO4 = 143,
#[doc = "Servo #5."]
MAV_COMP_ID_SERVO5 = 144,
#[doc = "Servo #6."]
MAV_COMP_ID_SERVO6 = 145,
#[doc = "Servo #7."]
MAV_COMP_ID_SERVO7 = 146,
#[doc = "Servo #8."]
MAV_COMP_ID_SERVO8 = 147,
#[doc = "Servo #9."]
MAV_COMP_ID_SERVO9 = 148,
#[doc = "Servo #10."]
MAV_COMP_ID_SERVO10 = 149,
#[doc = "Servo #11."]
MAV_COMP_ID_SERVO11 = 150,
#[doc = "Servo #12."]
MAV_COMP_ID_SERVO12 = 151,
#[doc = "Servo #13."]
MAV_COMP_ID_SERVO13 = 152,
#[doc = "Servo #14."]
MAV_COMP_ID_SERVO14 = 153,
#[doc = "Gimbal #1."]
MAV_COMP_ID_GIMBAL = 154,
#[doc = "Logging component."]
MAV_COMP_ID_LOG = 155,
#[doc = "Automatic Dependent Surveillance-Broadcast (ADS-B) component."]
MAV_COMP_ID_ADSB = 156,
#[doc = "On Screen Display (OSD) devices for video links."]
MAV_COMP_ID_OSD = 157,
#[doc = "Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter microservice."]
MAV_COMP_ID_PERIPHERAL = 158,
#[doc = "Gimbal ID for QX1."]
MAV_COMP_ID_QX1_GIMBAL = 159,
#[doc = "FLARM collision alert component."]
MAV_COMP_ID_FLARM = 160,
#[doc = "Parachute component."]
MAV_COMP_ID_PARACHUTE = 161,
#[doc = "Winch component."]
MAV_COMP_ID_WINCH = 169,
#[doc = "Gimbal #2."]
MAV_COMP_ID_GIMBAL2 = 171,
#[doc = "Gimbal #3."]
MAV_COMP_ID_GIMBAL3 = 172,
#[doc = "Gimbal #4"]
MAV_COMP_ID_GIMBAL4 = 173,
#[doc = "Gimbal #5."]
MAV_COMP_ID_GIMBAL5 = 174,
#[doc = "Gimbal #6."]
MAV_COMP_ID_GIMBAL6 = 175,
#[doc = "Battery #1."]
MAV_COMP_ID_BATTERY = 180,
#[doc = "Battery #2."]
MAV_COMP_ID_BATTERY2 = 181,
#[doc = "CAN over MAVLink client."]
MAV_COMP_ID_MAVCAN = 189,
#[doc = "Component that can generate/supply a mission flight plan (e.g. GCS or developer API)."]
MAV_COMP_ID_MISSIONPLANNER = 190,
#[doc = "Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on."]
MAV_COMP_ID_ONBOARD_COMPUTER = 191,
#[doc = "Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on."]
MAV_COMP_ID_ONBOARD_COMPUTER2 = 192,
#[doc = "Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on."]
MAV_COMP_ID_ONBOARD_COMPUTER3 = 193,
#[doc = "Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on."]
MAV_COMP_ID_ONBOARD_COMPUTER4 = 194,
#[doc = "Component that finds an optimal path between points based on a certain constraint (e.g. minimum snap, shortest path, cost, etc.)."]
MAV_COMP_ID_PATHPLANNER = 195,
#[doc = "Component that plans a collision free path between two points."]
MAV_COMP_ID_OBSTACLE_AVOIDANCE = 196,
#[doc = "Component that provides position estimates using VIO techniques."]
MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY = 197,
#[doc = "Component that manages pairing of vehicle and GCS."]
MAV_COMP_ID_PAIRING_MANAGER = 198,
#[doc = "Inertial Measurement Unit (IMU) #1."]
MAV_COMP_ID_IMU = 200,
#[doc = "Inertial Measurement Unit (IMU) #2."]
MAV_COMP_ID_IMU_2 = 201,
#[doc = "Inertial Measurement Unit (IMU) #3."]
MAV_COMP_ID_IMU_3 = 202,
#[doc = "GPS #1."]
MAV_COMP_ID_GPS = 220,
#[doc = "GPS #2."]
MAV_COMP_ID_GPS2 = 221,
#[doc = "Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet)."]
MAV_COMP_ID_ODID_TXRX_1 = 236,
#[doc = "Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet)."]
MAV_COMP_ID_ODID_TXRX_2 = 237,
#[doc = "Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet)."]
MAV_COMP_ID_ODID_TXRX_3 = 238,
#[doc = "Component to bridge MAVLink to UDP (i.e. from a UART)."]
MAV_COMP_ID_UDP_BRIDGE = 240,
#[doc = "Component to bridge to UART (i.e. from UDP)."]
MAV_COMP_ID_UART_BRIDGE = 241,
#[doc = "Component handling TUNNEL messages (e.g. vendor specific GUI of a component)."]
MAV_COMP_ID_TUNNEL_NODE = 242,
#[doc = "Deprecated, don't use. Component for handling system messages (e.g. to ARM, takeoff, etc.)."]
MAV_COMP_ID_SYSTEM_CONTROL = 250,
}
impl Default for MavComponent {
fn default() -> Self {
Self::MAV_COMP_ID_ALL
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum GimbalAxisCalibrationRequired {
#[doc = "Whether or not this axis requires calibration is unknown at this time."]
GIMBAL_AXIS_CALIBRATION_REQUIRED_UNKNOWN = 0,
#[doc = "This axis requires calibration."]
GIMBAL_AXIS_CALIBRATION_REQUIRED_TRUE = 1,
#[doc = "This axis does not require calibration."]
GIMBAL_AXIS_CALIBRATION_REQUIRED_FALSE = 2,
}
impl Default for GimbalAxisCalibrationRequired {
fn default() -> Self {
Self::GIMBAL_AXIS_CALIBRATION_REQUIRED_UNKNOWN
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum GoproResolution {
#[doc = "848 x 480 (480p)."]
GOPRO_RESOLUTION_480p = 0,
#[doc = "1280 x 720 (720p)."]
GOPRO_RESOLUTION_720p = 1,
#[doc = "1280 x 960 (960p)."]
GOPRO_RESOLUTION_960p = 2,
#[doc = "1920 x 1080 (1080p)."]
GOPRO_RESOLUTION_1080p = 3,
#[doc = "1920 x 1440 (1440p)."]
GOPRO_RESOLUTION_1440p = 4,
#[doc = "2704 x 1440 (2.7k-17:9)."]
GOPRO_RESOLUTION_2_7k_17_9 = 5,
#[doc = "2704 x 1524 (2.7k-16:9)."]
GOPRO_RESOLUTION_2_7k_16_9 = 6,
#[doc = "2704 x 2028 (2.7k-4:3)."]
GOPRO_RESOLUTION_2_7k_4_3 = 7,
#[doc = "3840 x 2160 (4k-16:9)."]
GOPRO_RESOLUTION_4k_16_9 = 8,
#[doc = "4096 x 2160 (4k-17:9)."]
GOPRO_RESOLUTION_4k_17_9 = 9,
#[doc = "1280 x 720 (720p-SuperView)."]
GOPRO_RESOLUTION_720p_SUPERVIEW = 10,
#[doc = "1920 x 1080 (1080p-SuperView)."]
GOPRO_RESOLUTION_1080p_SUPERVIEW = 11,
#[doc = "2704 x 1520 (2.7k-SuperView)."]
GOPRO_RESOLUTION_2_7k_SUPERVIEW = 12,
#[doc = "3840 x 2160 (4k-SuperView)."]
GOPRO_RESOLUTION_4k_SUPERVIEW = 13,
}
impl Default for GoproResolution {
fn default() -> Self {
Self::GOPRO_RESOLUTION_480p
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Specifies the datatype of a MAVLink extended parameter."]
pub enum MavParamExtType {
#[doc = "8-bit unsigned integer"]
MAV_PARAM_EXT_TYPE_UINT8 = 1,
#[doc = "8-bit signed integer"]
MAV_PARAM_EXT_TYPE_INT8 = 2,
#[doc = "16-bit unsigned integer"]
MAV_PARAM_EXT_TYPE_UINT16 = 3,
#[doc = "16-bit signed integer"]
MAV_PARAM_EXT_TYPE_INT16 = 4,
#[doc = "32-bit unsigned integer"]
MAV_PARAM_EXT_TYPE_UINT32 = 5,
#[doc = "32-bit signed integer"]
MAV_PARAM_EXT_TYPE_INT32 = 6,
#[doc = "64-bit unsigned integer"]
MAV_PARAM_EXT_TYPE_UINT64 = 7,
#[doc = "64-bit signed integer"]
MAV_PARAM_EXT_TYPE_INT64 = 8,
#[doc = "32-bit floating-point"]
MAV_PARAM_EXT_TYPE_REAL32 = 9,
#[doc = "64-bit floating-point"]
MAV_PARAM_EXT_TYPE_REAL64 = 10,
#[doc = "Custom Type"]
MAV_PARAM_EXT_TYPE_CUSTOM = 11,
}
impl Default for MavParamExtType {
fn default() -> Self {
Self::MAV_PARAM_EXT_TYPE_UINT8
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum GoproFrameRate {
#[doc = "12 FPS."]
GOPRO_FRAME_RATE_12 = 0,
#[doc = "15 FPS."]
GOPRO_FRAME_RATE_15 = 1,
#[doc = "24 FPS."]
GOPRO_FRAME_RATE_24 = 2,
#[doc = "25 FPS."]
GOPRO_FRAME_RATE_25 = 3,
#[doc = "30 FPS."]
GOPRO_FRAME_RATE_30 = 4,
#[doc = "48 FPS."]
GOPRO_FRAME_RATE_48 = 5,
#[doc = "50 FPS."]
GOPRO_FRAME_RATE_50 = 6,
#[doc = "60 FPS."]
GOPRO_FRAME_RATE_60 = 7,
#[doc = "80 FPS."]
GOPRO_FRAME_RATE_80 = 8,
#[doc = "90 FPS."]
GOPRO_FRAME_RATE_90 = 9,
#[doc = "100 FPS."]
GOPRO_FRAME_RATE_100 = 10,
#[doc = "120 FPS."]
GOPRO_FRAME_RATE_120 = 11,
#[doc = "240 FPS."]
GOPRO_FRAME_RATE_240 = 12,
#[doc = "12.5 FPS."]
GOPRO_FRAME_RATE_12_5 = 13,
}
impl Default for GoproFrameRate {
fn default() -> Self {
Self::GOPRO_FRAME_RATE_12
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Deepstall flight stage."]
pub enum DeepstallStage {
#[doc = "Flying to the landing point."]
DEEPSTALL_STAGE_FLY_TO_LANDING = 0,
#[doc = "Building an estimate of the wind."]
DEEPSTALL_STAGE_ESTIMATE_WIND = 1,
#[doc = "Waiting to breakout of the loiter to fly the approach."]
DEEPSTALL_STAGE_WAIT_FOR_BREAKOUT = 2,
#[doc = "Flying to the first arc point to turn around to the landing point."]
DEEPSTALL_STAGE_FLY_TO_ARC = 3,
#[doc = "Turning around back to the deepstall landing point."]
DEEPSTALL_STAGE_ARC = 4,
#[doc = "Approaching the landing point."]
DEEPSTALL_STAGE_APPROACH = 5,
#[doc = "Stalling and steering towards the land point."]
DEEPSTALL_STAGE_LAND = 6,
}
impl Default for DeepstallStage {
fn default() -> Self {
Self::DEEPSTALL_STAGE_FLY_TO_LANDING
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Cellular network radio type"]
pub enum CellularNetworkRadioType {
CELLULAR_NETWORK_RADIO_TYPE_NONE = 0,
CELLULAR_NETWORK_RADIO_TYPE_GSM = 1,
CELLULAR_NETWORK_RADIO_TYPE_CDMA = 2,
CELLULAR_NETWORK_RADIO_TYPE_WCDMA = 3,
CELLULAR_NETWORK_RADIO_TYPE_LTE = 4,
}
impl Default for CellularNetworkRadioType {
fn default() -> Self {
Self::CELLULAR_NETWORK_RADIO_TYPE_NONE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Special ACK block numbers control activation of dataflash log streaming."]
pub enum MavRemoteLogDataBlockCommands {
#[doc = "UAV to stop sending DataFlash blocks."]
MAV_REMOTE_LOG_DATA_BLOCK_STOP = 2147483645,
#[doc = "UAV to start sending DataFlash blocks."]
MAV_REMOTE_LOG_DATA_BLOCK_START = 2147483646,
}
impl Default for MavRemoteLogDataBlockCommands {
fn default() -> Self {
Self::MAV_REMOTE_LOG_DATA_BLOCK_STOP
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "These values define the type of firmware release. These values indicate the first version or release of this type. For example the first alpha release would be 64, the second would be 65."]
pub enum FirmwareVersionType {
#[doc = "development release"]
FIRMWARE_VERSION_TYPE_DEV = 0,
#[doc = "alpha release"]
FIRMWARE_VERSION_TYPE_ALPHA = 64,
#[doc = "beta release"]
FIRMWARE_VERSION_TYPE_BETA = 128,
#[doc = "release candidate"]
FIRMWARE_VERSION_TYPE_RC = 192,
#[doc = "official stable release"]
FIRMWARE_VERSION_TYPE_OFFICIAL = 255,
}
impl Default for FirmwareVersionType {
fn default() -> Self {
Self::FIRMWARE_VERSION_TYPE_DEV
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "ADSB classification for the type of vehicle emitting the transponder signal"]
pub enum AdsbEmitterType {
ADSB_EMITTER_TYPE_NO_INFO = 0,
ADSB_EMITTER_TYPE_LIGHT = 1,
ADSB_EMITTER_TYPE_SMALL = 2,
ADSB_EMITTER_TYPE_LARGE = 3,
ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE = 4,
ADSB_EMITTER_TYPE_HEAVY = 5,
ADSB_EMITTER_TYPE_HIGHLY_MANUV = 6,
ADSB_EMITTER_TYPE_ROTOCRAFT = 7,
ADSB_EMITTER_TYPE_UNASSIGNED = 8,
ADSB_EMITTER_TYPE_GLIDER = 9,
ADSB_EMITTER_TYPE_LIGHTER_AIR = 10,
ADSB_EMITTER_TYPE_PARACHUTE = 11,
ADSB_EMITTER_TYPE_ULTRA_LIGHT = 12,
ADSB_EMITTER_TYPE_UNASSIGNED2 = 13,
ADSB_EMITTER_TYPE_UAV = 14,
ADSB_EMITTER_TYPE_SPACE = 15,
ADSB_EMITTER_TYPE_UNASSGINED3 = 16,
ADSB_EMITTER_TYPE_EMERGENCY_SURFACE = 17,
ADSB_EMITTER_TYPE_SERVICE_SURFACE = 18,
ADSB_EMITTER_TYPE_POINT_OBSTACLE = 19,
}
impl Default for AdsbEmitterType {
fn default() -> Self {
Self::ADSB_EMITTER_TYPE_NO_INFO
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Precision land modes (used in MAV_CMD_NAV_LAND)."]
pub enum PrecisionLandMode {
#[doc = "Normal (non-precision) landing."]
PRECISION_LAND_MODE_DISABLED = 0,
#[doc = "Use precision landing if beacon detected when land command accepted, otherwise land normally."]
PRECISION_LAND_MODE_OPPORTUNISTIC = 1,
#[doc = "Use precision landing, searching for beacon if not found when land command accepted (land normally if beacon cannot be found)."]
PRECISION_LAND_MODE_REQUIRED = 2,
}
impl Default for PrecisionLandMode {
fn default() -> Self {
Self::PRECISION_LAND_MODE_DISABLED
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "A data stream is not a fixed set of messages, but rather a recommendation to the autopilot software. Individual autopilots may or may not obey the recommended messages."]
pub enum MavDataStream {
#[doc = "Enable all data streams"]
MAV_DATA_STREAM_ALL = 0,
#[doc = "Enable IMU_RAW, GPS_RAW, GPS_STATUS packets."]
MAV_DATA_STREAM_RAW_SENSORS = 1,
#[doc = "Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS"]
MAV_DATA_STREAM_EXTENDED_STATUS = 2,
#[doc = "Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW"]
MAV_DATA_STREAM_RC_CHANNELS = 3,
#[doc = "Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT."]
MAV_DATA_STREAM_RAW_CONTROLLER = 4,
#[doc = "Enable LOCAL_POSITION, GLOBAL_POSITION_INT messages."]
MAV_DATA_STREAM_POSITION = 6,
#[doc = "Dependent on the autopilot"]
MAV_DATA_STREAM_EXTRA1 = 10,
#[doc = "Dependent on the autopilot"]
MAV_DATA_STREAM_EXTRA2 = 11,
#[doc = "Dependent on the autopilot"]
MAV_DATA_STREAM_EXTRA3 = 12,
}
impl Default for MavDataStream {
fn default() -> Self {
Self::MAV_DATA_STREAM_ALL
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] pub struct LimitModule : u8 { # [doc = "Pre-initialization."] const LIMIT_GPSLOCK = 1 ; # [doc = "Disabled."] const LIMIT_GEOFENCE = 2 ; # [doc = "Checking limits."] const LIMIT_ALTITUDE = 4 ; } }
impl Default for LimitModule {
fn default() -> Self {
Self::LIMIT_GPSLOCK
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Enable axes that will be tuned via autotuning. Used in MAV_CMD_DO_AUTOTUNE_ENABLE."]
pub enum AutotuneAxis {
#[doc = "Flight stack tunes axis according to its default settings."]
AUTOTUNE_AXIS_DEFAULT = 0,
#[doc = "Autotune roll axis."]
AUTOTUNE_AXIS_ROLL = 1,
#[doc = "Autotune pitch axis."]
AUTOTUNE_AXIS_PITCH = 2,
#[doc = "Autotune yaw axis."]
AUTOTUNE_AXIS_YAW = 4,
}
impl Default for AutotuneAxis {
fn default() -> Self {
Self::AUTOTUNE_AXIS_DEFAULT
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "These flags encode the cellular network status"]
pub enum CellularStatusFlag {
#[doc = "State unknown or not reportable."]
CELLULAR_STATUS_FLAG_UNKNOWN = 0,
#[doc = "Modem is unusable"]
CELLULAR_STATUS_FLAG_FAILED = 1,
#[doc = "Modem is being initialized"]
CELLULAR_STATUS_FLAG_INITIALIZING = 2,
#[doc = "Modem is locked"]
CELLULAR_STATUS_FLAG_LOCKED = 3,
#[doc = "Modem is not enabled and is powered down"]
CELLULAR_STATUS_FLAG_DISABLED = 4,
#[doc = "Modem is currently transitioning to the CELLULAR_STATUS_FLAG_DISABLED state"]
CELLULAR_STATUS_FLAG_DISABLING = 5,
#[doc = "Modem is currently transitioning to the CELLULAR_STATUS_FLAG_ENABLED state"]
CELLULAR_STATUS_FLAG_ENABLING = 6,
#[doc = "Modem is enabled and powered on but not registered with a network provider and not available for data connections"]
CELLULAR_STATUS_FLAG_ENABLED = 7,
#[doc = "Modem is searching for a network provider to register"]
CELLULAR_STATUS_FLAG_SEARCHING = 8,
#[doc = "Modem is registered with a network provider, and data connections and messaging may be available for use"]
CELLULAR_STATUS_FLAG_REGISTERED = 9,
#[doc = "Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated"]
CELLULAR_STATUS_FLAG_DISCONNECTING = 10,
#[doc = "Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered"]
CELLULAR_STATUS_FLAG_CONNECTING = 11,
#[doc = "One or more packet data bearers is active and connected"]
CELLULAR_STATUS_FLAG_CONNECTED = 12,
}
impl Default for CellularStatusFlag {
fn default() -> Self {
Self::CELLULAR_STATUS_FLAG_UNKNOWN
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum MavOdidOperatorIdType {
#[doc = "CAA (Civil Aviation Authority) registered operator ID."]
MAV_ODID_OPERATOR_ID_TYPE_CAA = 0,
}
impl Default for MavOdidOperatorIdType {
fn default() -> Self {
Self::MAV_ODID_OPERATOR_ID_TYPE_CAA
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. NaN and INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current yaw or latitude rather than a specific value). See https://mavlink.io/en/guide/xml_schema.html#MAV_CMD for information about the structure of the MAV_CMD entries"]
pub enum MavCmd {
#[doc = "Navigate to waypoint."]
MAV_CMD_NAV_WAYPOINT = 16,
#[doc = "Loiter around this waypoint an unlimited amount of time"]
MAV_CMD_NAV_LOITER_UNLIM = 17,
#[doc = "Loiter around this waypoint for X turns"]
MAV_CMD_NAV_LOITER_TURNS = 18,
#[doc = "Loiter at the specified latitude, longitude and altitude for a certain amount of time. Multicopter vehicles stop at the point (within a vehicle-specific acceptance radius). Forward-only moving vehicles (e.g. fixed-wing) circle the point with the specified radius/direction. If the Heading Required parameter (2) is non-zero forward moving aircraft will only leave the loiter circle once heading towards the next waypoint."]
MAV_CMD_NAV_LOITER_TIME = 19,
#[doc = "Return to launch location"]
MAV_CMD_NAV_RETURN_TO_LAUNCH = 20,
#[doc = "Land at location."]
MAV_CMD_NAV_LAND = 21,
#[doc = "Takeoff from ground / hand. Vehicles that support multiple takeoff modes (e.g. VTOL quadplane) should take off using the currently configured mode."]
MAV_CMD_NAV_TAKEOFF = 22,
#[doc = "Land at local position (local frame only)"]
MAV_CMD_NAV_LAND_LOCAL = 23,
#[doc = "Takeoff from local position (local frame only)"]
MAV_CMD_NAV_TAKEOFF_LOCAL = 24,
#[doc = "Vehicle following, i.e. this waypoint represents the position of a moving vehicle"]
MAV_CMD_NAV_FOLLOW = 25,
#[doc = "Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached."]
MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT = 30,
#[doc = "Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint."]
MAV_CMD_NAV_LOITER_TO_ALT = 31,
#[doc = "Begin following a target"]
MAV_CMD_DO_FOLLOW = 32,
#[doc = "Reposition the MAV after a follow target command has been sent"]
MAV_CMD_DO_FOLLOW_REPOSITION = 33,
#[doc = "Start orbiting on the circumference of a circle defined by the parameters. Setting values to NaN/INT32_MAX (as appropriate) results in using defaults."]
MAV_CMD_DO_ORBIT = 34,
#[doc = "Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras."]
MAV_CMD_NAV_ROI = 80,
#[doc = "Control autonomous path planning on the MAV."]
MAV_CMD_NAV_PATHPLANNING = 81,
#[doc = "Navigate to waypoint using a spline path."]
MAV_CMD_NAV_SPLINE_WAYPOINT = 82,
#[doc = "Takeoff from ground using VTOL mode, and transition to forward flight with specified heading. The command should be ignored by vehicles that dont support both VTOL and fixed-wing flight (multicopters, boats,etc.)."]
MAV_CMD_NAV_VTOL_TAKEOFF = 84,
#[doc = "Land using VTOL mode"]
MAV_CMD_NAV_VTOL_LAND = 85,
#[doc = "hand control over to an external controller"]
MAV_CMD_NAV_GUIDED_ENABLE = 92,
#[doc = "Delay the next navigation command a number of seconds or until a specified time"]
MAV_CMD_NAV_DELAY = 93,
#[doc = "Descend and place payload. Vehicle moves to specified location, descends until it detects a hanging payload has reached the ground, and then releases the payload. If ground is not detected before the reaching the maximum descent value (param1), the command will complete without releasing the payload."]
MAV_CMD_NAV_PAYLOAD_PLACE = 94,
#[doc = "NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration"]
MAV_CMD_NAV_LAST = 95,
#[doc = "Delay mission state machine."]
MAV_CMD_CONDITION_DELAY = 112,
#[doc = "Ascend/descend to target altitude at specified rate. Delay mission state machine until desired altitude reached."]
MAV_CMD_CONDITION_CHANGE_ALT = 113,
#[doc = "Delay mission state machine until within desired distance of next NAV point."]
MAV_CMD_CONDITION_DISTANCE = 114,
#[doc = "Reach a certain target angle."]
MAV_CMD_CONDITION_YAW = 115,
#[doc = "NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration"]
MAV_CMD_CONDITION_LAST = 159,
#[doc = "Set system mode."]
MAV_CMD_DO_SET_MODE = 176,
#[doc = "Jump to the desired command in the mission list. Repeat this action only the specified number of times"]
MAV_CMD_DO_JUMP = 177,
#[doc = "Change speed and/or throttle set points. The value persists until it is overridden or there is a mode change."]
MAV_CMD_DO_CHANGE_SPEED = 178,
#[doc = "Sets the home position to either to the current position or a specified position. The home position is the default position that the system will return to and land on. The position is set automatically by the system during the takeoff (and may also be set using this command). Note: the current home position may be emitted in a HOME_POSITION message on request (using MAV_CMD_REQUEST_MESSAGE with param1=242)."]
MAV_CMD_DO_SET_HOME = 179,
#[doc = "Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter."]
MAV_CMD_DO_SET_PARAMETER = 180,
#[doc = "Set a relay to a condition."]
MAV_CMD_DO_SET_RELAY = 181,
#[doc = "Cycle a relay on and off for a desired number of cycles with a desired period."]
MAV_CMD_DO_REPEAT_RELAY = 182,
#[doc = "Set a servo to a desired PWM value."]
MAV_CMD_DO_SET_SERVO = 183,
#[doc = "Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period."]
MAV_CMD_DO_REPEAT_SERVO = 184,
#[doc = "Terminate flight immediately. Flight termination immediately and irreversably terminates the current flight, returning the vehicle to ground. The vehicle will ignore RC or other input until it has been power-cycled. Termination may trigger safety measures, including: disabling motors and deployment of parachute on multicopters, and setting flight surfaces to initiate a landing pattern on fixed-wing). On multicopters without a parachute it may trigger a crash landing. Support for this command can be tested using the protocol bit: MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION. Support for this command can also be tested by sending the command with param1=0 (< 0.5); the ACK should be either MAV_RESULT_FAILED or MAV_RESULT_UNSUPPORTED."]
MAV_CMD_DO_FLIGHTTERMINATION = 185,
#[doc = "Change altitude set point."]
MAV_CMD_DO_CHANGE_ALTITUDE = 186,
#[doc = "Sets actuators (e.g. servos) to a desired value. The actuator numbers are mapped to specific outputs (e.g. on any MAIN or AUX PWM or UAVCAN) using a flight-stack specific mechanism (i.e. a parameter)."]
MAV_CMD_DO_SET_ACTUATOR = 187,
#[doc = "Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. \t It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. \t The Latitude/Longitude/Altitude is optional, and may be set to 0 if not needed. If specified then it will be used to help find the closest landing sequence."]
MAV_CMD_DO_LAND_START = 189,
#[doc = "Mission command to perform a landing from a rally point."]
MAV_CMD_DO_RALLY_LAND = 190,
#[doc = "Mission command to safely abort an autonomous landing."]
MAV_CMD_DO_GO_AROUND = 191,
#[doc = "Reposition the vehicle to a specific WGS84 global position."]
MAV_CMD_DO_REPOSITION = 192,
#[doc = "If in a GPS controlled position mode, hold the current position or continue."]
MAV_CMD_DO_PAUSE_CONTINUE = 193,
#[doc = "Set moving direction to forward or reverse."]
MAV_CMD_DO_SET_REVERSE = 194,
#[doc = "Sets the region of interest (ROI) to a location. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal is not to react to this message."]
MAV_CMD_DO_SET_ROI_LOCATION = 195,
#[doc = "Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message."]
MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET = 196,
#[doc = "Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message. After this command the gimbal manager should go back to manual input if available, and otherwise assume a neutral position."]
MAV_CMD_DO_SET_ROI_NONE = 197,
#[doc = "Mount tracks system with specified system ID. Determination of target vehicle position may be done with GLOBAL_POSITION_INT or any other means. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message."]
MAV_CMD_DO_SET_ROI_SYSID = 198,
#[doc = "Control onboard camera system."]
MAV_CMD_DO_CONTROL_VIDEO = 200,
#[doc = "Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras."]
MAV_CMD_DO_SET_ROI = 201,
#[doc = "Configure digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see https://mavlink.io/en/services/camera_def.html )."]
MAV_CMD_DO_DIGICAM_CONFIGURE = 202,
#[doc = "Control digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see https://mavlink.io/en/services/camera_def.html )."]
MAV_CMD_DO_DIGICAM_CONTROL = 203,
#[doc = "Mission command to configure a camera or antenna mount"]
MAV_CMD_DO_MOUNT_CONFIGURE = 204,
#[doc = "Mission command to control a camera or antenna mount"]
MAV_CMD_DO_MOUNT_CONTROL = 205,
#[doc = "Mission command to set camera trigger distance for this flight. The camera is triggered each time this distance is exceeded. This command can also be used to set the shutter integration time for the camera."]
MAV_CMD_DO_SET_CAM_TRIGG_DIST = 206,
#[doc = "Mission command to enable the geofence"]
MAV_CMD_DO_FENCE_ENABLE = 207,
#[doc = "Mission item/command to release a parachute or enable/disable auto release."]
MAV_CMD_DO_PARACHUTE = 208,
#[doc = "Command to perform motor test."]
MAV_CMD_DO_MOTOR_TEST = 209,
#[doc = "Change to/from inverted flight."]
MAV_CMD_DO_INVERTED_FLIGHT = 210,
#[doc = "Mission command to operate a gripper."]
MAV_CMD_DO_GRIPPER = 211,
#[doc = "Enable/disable autotune."]
MAV_CMD_DO_AUTOTUNE_ENABLE = 212,
#[doc = "Sets a desired vehicle turn angle and speed change."]
MAV_CMD_NAV_SET_YAW_SPEED = 213,
#[doc = "Mission command to set camera trigger interval for this flight. If triggering is enabled, the camera is triggered each time this interval expires. This command can also be used to set the shutter integration time for the camera."]
MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL = 214,
#[doc = "Mission command to control a camera or antenna mount, using a quaternion as reference."]
MAV_CMD_DO_MOUNT_CONTROL_QUAT = 220,
#[doc = "set id of master controller"]
MAV_CMD_DO_GUIDED_MASTER = 221,
#[doc = "Set limits for external control"]
MAV_CMD_DO_GUIDED_LIMITS = 222,
#[doc = "Control vehicle engine. This is interpreted by the vehicles engine controller to change the target engine state. It is intended for vehicles with internal combustion engines"]
MAV_CMD_DO_ENGINE_CONTROL = 223,
#[doc = "Set the mission item with sequence number seq as the current item and emit MISSION_CURRENT (whether or not the mission number changed). If a mission is currently being executed, the system will continue to this new mission item on the shortest path, skipping any intermediate mission items. \t Note that mission jump repeat counters are not reset unless param2 is set (see MAV_CMD_DO_JUMP param2). This command may trigger a mission state-machine change on some systems: for example from MISSION_STATE_NOT_STARTED or MISSION_STATE_PAUSED to MISSION_STATE_ACTIVE. If the system is in mission mode, on those systems this command might therefore start, restart or resume the mission. If the system is not in mission mode this command must not trigger a switch to mission mode. The mission may be \"reset\" using param2. Resetting sets jump counters to initial values (to reset counters without changing the current mission item set the param1 to `-1`). Resetting also explicitly changes a mission state of MISSION_STATE_COMPLETE to MISSION_STATE_PAUSED or MISSION_STATE_ACTIVE, potentially allowing it to resume when it is (next) in a mission mode. \t The command will ACK with MAV_RESULT_FAILED if the sequence number is out of range (including if there is no mission item)."]
MAV_CMD_DO_SET_MISSION_CURRENT = 224,
#[doc = "NOP - This command is only used to mark the upper limit of the DO commands in the enumeration"]
MAV_CMD_DO_LAST = 240,
#[doc = "Trigger calibration. This command will be only accepted if in pre-flight mode. Except for Temperature Calibration, only one sensor should be set in a single message and all others should be zero."]
MAV_CMD_PREFLIGHT_CALIBRATION = 241,
#[doc = "Set sensor offsets. This command will be only accepted if in pre-flight mode."]
MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242,
#[doc = "Trigger UAVCAN configuration (actuator ID assignment and direction mapping). Note that this maps to the legacy UAVCAN v0 function UAVCAN_ENUMERATE, which is intended to be executed just once during initial vehicle configuration (it is not a normal pre-flight command and has been poorly named)."]
MAV_CMD_PREFLIGHT_UAVCAN = 243,
#[doc = "Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode."]
MAV_CMD_PREFLIGHT_STORAGE = 245,
#[doc = "Request the reboot or shutdown of system components."]
MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246,
#[doc = "Override current mission with command to pause mission, pause mission and move to position, continue/resume mission. When param 1 indicates that the mission is paused (MAV_GOTO_DO_HOLD), param 2 defines whether it holds in place or moves to another position."]
MAV_CMD_OVERRIDE_GOTO = 252,
#[doc = "Mission command to set a Camera Auto Mount Pivoting Oblique Survey (Replaces CAM_TRIGG_DIST for this purpose). The camera is triggered each time this distance is exceeded, then the mount moves to the next position. Params 4~6 set-up the angle limits and number of positions for oblique survey, where mount-enabled vehicles automatically roll the camera between shots to emulate an oblique camera setup (providing an increased HFOV). This command can also be used to set the shutter integration time for the camera."]
MAV_CMD_OBLIQUE_SURVEY = 260,
#[doc = "start running a mission"]
MAV_CMD_MISSION_START = 300,
#[doc = "Actuator testing command. This is similar to MAV_CMD_DO_MOTOR_TEST but operates on the level of output functions, i.e. it is possible to test Motor1 independent from which output it is configured on. Autopilots typically refuse this command while armed."]
MAV_CMD_ACTUATOR_TEST = 310,
#[doc = "Actuator configuration command."]
MAV_CMD_CONFIGURE_ACTUATOR = 311,
#[doc = "Arms / Disarms a component"]
MAV_CMD_COMPONENT_ARM_DISARM = 400,
#[doc = "Instructs a target system to run pre-arm checks. This allows preflight checks to be run on demand, which may be useful on systems that normally run them at low rate, or which do not trigger checks when the armable state might have changed. This command should return MAV_RESULT_ACCEPTED if it will run the checks. The results of the checks are usually then reported in SYS_STATUS messages (this is system-specific). The command should return MAV_RESULT_TEMPORARILY_REJECTED if the system is already armed."]
MAV_CMD_RUN_PREARM_CHECKS = 401,
#[doc = "Turns illuminators ON/OFF. An illuminator is a light source that is used for lighting up dark areas external to the sytstem: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light)."]
MAV_CMD_ILLUMINATOR_ON_OFF = 405,
#[doc = "Request the home position from the vehicle. \t The vehicle will ACK the command and then emit the HOME_POSITION message."]
MAV_CMD_GET_HOME_POSITION = 410,
#[doc = "Inject artificial failure for testing purposes. Note that autopilots should implement an additional protection before accepting this command such as a specific param setting."]
MAV_CMD_INJECT_FAILURE = 420,
#[doc = "Starts receiver pairing."]
MAV_CMD_START_RX_PAIR = 500,
#[doc = "Request the interval between messages for a particular MAVLink message ID. The receiver should ACK the command and then emit its response in a MESSAGE_INTERVAL message."]
MAV_CMD_GET_MESSAGE_INTERVAL = 510,
#[doc = "Set the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM."]
MAV_CMD_SET_MESSAGE_INTERVAL = 511,
#[doc = "Request the target system(s) emit a single instance of a specified message (i.e. a \"one-shot\" version of MAV_CMD_SET_MESSAGE_INTERVAL)."]
MAV_CMD_REQUEST_MESSAGE = 512,
#[doc = "Request MAVLink protocol version compatibility. All receivers should ACK the command and then emit their capabilities in an PROTOCOL_VERSION message"]
MAV_CMD_REQUEST_PROTOCOL_VERSION = 519,
#[doc = "Request autopilot capabilities. The receiver should ACK the command and then emit its capabilities in an AUTOPILOT_VERSION message"]
MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES = 520,
#[doc = "Request camera information (CAMERA_INFORMATION)."]
MAV_CMD_REQUEST_CAMERA_INFORMATION = 521,
#[doc = "Request camera settings (CAMERA_SETTINGS)."]
MAV_CMD_REQUEST_CAMERA_SETTINGS = 522,
#[doc = "Request storage information (STORAGE_INFORMATION). Use the command's target_component to target a specific component's storage."]
MAV_CMD_REQUEST_STORAGE_INFORMATION = 525,
#[doc = "Format a storage medium. Once format is complete, a STORAGE_INFORMATION message is sent. Use the command's target_component to target a specific component's storage."]
MAV_CMD_STORAGE_FORMAT = 526,
#[doc = "Request camera capture status (CAMERA_CAPTURE_STATUS)"]
MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS = 527,
#[doc = "Request flight information (FLIGHT_INFORMATION)"]
MAV_CMD_REQUEST_FLIGHT_INFORMATION = 528,
#[doc = "Reset all camera settings to Factory Default"]
MAV_CMD_RESET_CAMERA_SETTINGS = 529,
#[doc = "Set camera running mode. Use NaN for reserved values. GCS will send a MAV_CMD_REQUEST_VIDEO_STREAM_STATUS command after a mode change if the camera supports video streaming."]
MAV_CMD_SET_CAMERA_MODE = 530,
#[doc = "Set camera zoom. Camera must respond with a CAMERA_SETTINGS message (on success)."]
MAV_CMD_SET_CAMERA_ZOOM = 531,
#[doc = "Set camera focus. Camera must respond with a CAMERA_SETTINGS message (on success)."]
MAV_CMD_SET_CAMERA_FOCUS = 532,
#[doc = "Set that a particular storage is the preferred location for saving photos, videos, and/or other media (e.g. to set that an SD card is used for storing videos). There can only be one preferred save location for each particular media type: setting a media usage flag will clear/reset that same flag if set on any other storage. If no flag is set the system should use its default storage. A target system can choose to always use default storage, in which case it should ACK the command with MAV_RESULT_UNSUPPORTED. A target system can choose to not allow a particular storage to be set as preferred storage, in which case it should ACK the command with MAV_RESULT_DENIED."]
MAV_CMD_SET_STORAGE_USAGE = 533,
#[doc = "Tagged jump target. Can be jumped to with MAV_CMD_DO_JUMP_TAG."]
MAV_CMD_JUMP_TAG = 600,
#[doc = "Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number."]
MAV_CMD_DO_JUMP_TAG = 601,
#[doc = "High level setpoint to be sent to a gimbal manager to set a gimbal attitude. It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: a gimbal is never to react to this command but only the gimbal manager."]
MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW = 1000,
#[doc = "Gimbal configuration to set which sysid/compid is in primary and secondary control."]
MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE = 1001,
#[doc = "Start image capture sequence. Sends CAMERA_IMAGE_CAPTURED after each capture. Use NaN for reserved values."]
MAV_CMD_IMAGE_START_CAPTURE = 2000,
#[doc = "Stop image capture sequence Use NaN for reserved values."]
MAV_CMD_IMAGE_STOP_CAPTURE = 2001,
#[doc = "Re-request a CAMERA_IMAGE_CAPTURED message."]
MAV_CMD_REQUEST_CAMERA_IMAGE_CAPTURE = 2002,
#[doc = "Enable or disable on-board camera triggering system."]
MAV_CMD_DO_TRIGGER_CONTROL = 2003,
#[doc = "If the camera supports point visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_POINT is set), this command allows to initiate the tracking."]
MAV_CMD_CAMERA_TRACK_POINT = 2004,
#[doc = "If the camera supports rectangle visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE is set), this command allows to initiate the tracking."]
MAV_CMD_CAMERA_TRACK_RECTANGLE = 2005,
#[doc = "Stops ongoing tracking."]
MAV_CMD_CAMERA_STOP_TRACKING = 2010,
#[doc = "Starts video capture (recording)."]
MAV_CMD_VIDEO_START_CAPTURE = 2500,
#[doc = "Stop the current video capture (recording)."]
MAV_CMD_VIDEO_STOP_CAPTURE = 2501,
#[doc = "Start video streaming"]
MAV_CMD_VIDEO_START_STREAMING = 2502,
#[doc = "Stop the given video stream"]
MAV_CMD_VIDEO_STOP_STREAMING = 2503,
#[doc = "Request video stream information (VIDEO_STREAM_INFORMATION)"]
MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION = 2504,
#[doc = "Request video stream status (VIDEO_STREAM_STATUS)"]
MAV_CMD_REQUEST_VIDEO_STREAM_STATUS = 2505,
#[doc = "Request to start streaming logging data over MAVLink (see also LOGGING_DATA message)"]
MAV_CMD_LOGGING_START = 2510,
#[doc = "Request to stop streaming log data over MAVLink"]
MAV_CMD_LOGGING_STOP = 2511,
MAV_CMD_AIRFRAME_CONFIGURATION = 2520,
#[doc = "Request to start/stop transmitting over the high latency telemetry"]
MAV_CMD_CONTROL_HIGH_LATENCY = 2600,
#[doc = "Create a panorama at the current position"]
MAV_CMD_PANORAMA_CREATE = 2800,
#[doc = "Request VTOL transition"]
MAV_CMD_DO_VTOL_TRANSITION = 3000,
#[doc = "Request authorization to arm the vehicle to a external entity, the arm authorizer is responsible to request all data that is needs from the vehicle before authorize or deny the request. \t\tIf approved the COMMAND_ACK message progress field should be set with period of time that this authorization is valid in seconds. \t\tIf the authorization is denied COMMAND_ACK.result_param2 should be set with one of the reasons in ARM_AUTH_DENIED_REASON."]
MAV_CMD_ARM_AUTHORIZATION_REQUEST = 3001,
#[doc = "This command sets the submode to standard guided when vehicle is in guided mode. The vehicle holds position and altitude and the user can input the desired velocities along all three axes."]
MAV_CMD_SET_GUIDED_SUBMODE_STANDARD = 4000,
#[doc = "This command sets submode circle when vehicle is in guided mode. Vehicle flies along a circle facing the center of the circle. The user can input the velocity along the circle and change the radius. If no input is given the vehicle will hold position."]
MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE = 4001,
#[doc = "Delay mission state machine until gate has been reached."]
MAV_CMD_CONDITION_GATE = 4501,
#[doc = "Fence return point (there can only be one such point in a geofence definition). If rally points are supported they should be used instead."]
MAV_CMD_NAV_FENCE_RETURN_POINT = 5000,
#[doc = "Fence vertex for an inclusion polygon (the polygon must not be self-intersecting). The vehicle must stay within this area. Minimum of 3 vertices required."]
MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION = 5001,
#[doc = "Fence vertex for an exclusion polygon (the polygon must not be self-intersecting). The vehicle must stay outside this area. Minimum of 3 vertices required."]
MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION = 5002,
#[doc = "Circular fence area. The vehicle must stay inside this area."]
MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION = 5003,
#[doc = "Circular fence area. The vehicle must stay outside this area."]
MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION = 5004,
#[doc = "Rally point. You can have multiple rally points defined."]
MAV_CMD_NAV_RALLY_POINT = 5100,
#[doc = "Commands the vehicle to respond with a sequence of messages UAVCAN_NODE_INFO, one message per every UAVCAN node that is online. Note that some of the response messages can be lost, which the receiver can detect easily by checking whether every received UAVCAN_NODE_STATUS has a matching message UAVCAN_NODE_INFO received earlier; if not, this command should be sent again in order to request re-transmission of the node information messages."]
MAV_CMD_UAVCAN_GET_NODE_INFO = 5200,
#[doc = "Trigger the start of an ADSB-out IDENT. This should only be used when requested to do so by an Air Traffic Controller in controlled airspace. This starts the IDENT which is then typically held for 18 seconds by the hardware per the Mode A, C, and S transponder spec."]
MAV_CMD_DO_ADSB_OUT_IDENT = 10001,
#[doc = "Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity."]
MAV_CMD_PAYLOAD_PREPARE_DEPLOY = 30001,
#[doc = "Control the payload deployment."]
MAV_CMD_PAYLOAD_CONTROL_DEPLOY = 30002,
#[doc = "Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location."]
MAV_CMD_FIXED_MAG_CAL_YAW = 42006,
#[doc = "Command to operate winch."]
MAV_CMD_DO_WINCH = 42600,
#[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
MAV_CMD_WAYPOINT_USER_1 = 31000,
#[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
MAV_CMD_WAYPOINT_USER_2 = 31001,
#[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
MAV_CMD_WAYPOINT_USER_3 = 31002,
#[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
MAV_CMD_WAYPOINT_USER_4 = 31003,
#[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
MAV_CMD_WAYPOINT_USER_5 = 31004,
#[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
MAV_CMD_SPATIAL_USER_1 = 31005,
#[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
MAV_CMD_SPATIAL_USER_2 = 31006,
#[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
MAV_CMD_SPATIAL_USER_3 = 31007,
#[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
MAV_CMD_SPATIAL_USER_4 = 31008,
#[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
MAV_CMD_SPATIAL_USER_5 = 31009,
#[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
MAV_CMD_USER_1 = 31010,
#[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
MAV_CMD_USER_2 = 31011,
#[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
MAV_CMD_USER_3 = 31012,
#[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
MAV_CMD_USER_4 = 31013,
#[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
MAV_CMD_USER_5 = 31014,
#[doc = "Request forwarding of CAN packets from the given CAN bus to this component. CAN Frames are sent using CAN_FRAME and CANFD_FRAME messages"]
MAV_CMD_CAN_FORWARD = 32000,
#[doc = "Set the distance to be repeated on mission resume"]
MAV_CMD_DO_SET_RESUME_REPEAT_DIST = 215,
#[doc = "Control attached liquid sprayer"]
MAV_CMD_DO_SPRAYER = 216,
#[doc = "Pass instructions onto scripting, a script should be checking for a new command"]
MAV_CMD_DO_SEND_SCRIPT_MESSAGE = 217,
#[doc = "Execute auxiliary function"]
MAV_CMD_DO_AUX_FUNCTION = 218,
#[doc = "Mission command to wait for an altitude or downwards vertical speed. This is meant for high altitude balloon launches, allowing the aircraft to be idle until either an altitude is reached or a negative vertical speed is reached (indicating early balloon burst). The wiggle time is how often to wiggle the control surfaces to prevent them seizing up."]
MAV_CMD_NAV_ALTITUDE_WAIT = 83,
#[doc = "A system wide power-off event has been initiated."]
MAV_CMD_POWER_OFF_INITIATED = 42000,
#[doc = "FLY button has been clicked."]
MAV_CMD_SOLO_BTN_FLY_CLICK = 42001,
#[doc = "FLY button has been held for 1.5 seconds."]
MAV_CMD_SOLO_BTN_FLY_HOLD = 42002,
#[doc = "PAUSE button has been clicked."]
MAV_CMD_SOLO_BTN_PAUSE_CLICK = 42003,
#[doc = "Magnetometer calibration based on fixed position in earth field given by inclination, declination and intensity."]
MAV_CMD_FIXED_MAG_CAL = 42004,
#[doc = "Magnetometer calibration based on fixed expected field values."]
MAV_CMD_FIXED_MAG_CAL_FIELD = 42005,
#[doc = "Set EKF sensor source set."]
MAV_CMD_SET_EKF_SOURCE_SET = 42007,
#[doc = "Initiate a magnetometer calibration."]
MAV_CMD_DO_START_MAG_CAL = 42424,
#[doc = "Accept a magnetometer calibration."]
MAV_CMD_DO_ACCEPT_MAG_CAL = 42425,
#[doc = "Cancel a running magnetometer calibration."]
MAV_CMD_DO_CANCEL_MAG_CAL = 42426,
#[doc = "Used when doing accelerometer calibration. When sent to the GCS tells it what position to put the vehicle in. When sent to the vehicle says what position the vehicle is in."]
MAV_CMD_ACCELCAL_VEHICLE_POS = 42429,
#[doc = "Reply with the version banner."]
MAV_CMD_DO_SEND_BANNER = 42428,
#[doc = "Command autopilot to get into factory test/diagnostic mode."]
MAV_CMD_SET_FACTORY_TEST_MODE = 42427,
#[doc = "Causes the gimbal to reset and boot as if it was just powered on."]
MAV_CMD_GIMBAL_RESET = 42501,
#[doc = "Reports progress and success or failure of gimbal axis calibration procedure."]
MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS = 42502,
#[doc = "Starts commutation calibration on the gimbal."]
MAV_CMD_GIMBAL_REQUEST_AXIS_CALIBRATION = 42503,
#[doc = "Erases gimbal application and parameters."]
MAV_CMD_GIMBAL_FULL_RESET = 42505,
#[doc = "Update the bootloader"]
MAV_CMD_FLASH_BOOTLOADER = 42650,
#[doc = "Reset battery capacity for batteries that accumulate consumed battery via integration."]
MAV_CMD_BATTERY_RESET = 42651,
#[doc = "Issue a trap signal to the autopilot process, presumably to enter the debugger."]
MAV_CMD_DEBUG_TRAP = 42700,
#[doc = "Control onboard scripting."]
MAV_CMD_SCRIPTING = 42701,
#[doc = "Scripting command as NAV command with wait for completion."]
MAV_CMD_NAV_SCRIPT_TIME = 42702,
#[doc = "Maintain an attitude for a specified time."]
MAV_CMD_NAV_ATTITUDE_TIME = 42703,
#[doc = "Change flight speed at a given rate. This slews the vehicle at a controllable rate between it's previous speed and the new one. (affects GUIDED only. Outside GUIDED, aircraft ignores these commands. Designed for onboard companion-computer command-and-control, not normally operator/GCS control.)"]
MAV_CMD_GUIDED_CHANGE_SPEED = 43000,
#[doc = "Change target altitude at a given rate. This slews the vehicle at a controllable rate between it's previous altitude and the new one. (affects GUIDED only. Outside GUIDED, aircraft ignores these commands. Designed for onboard companion-computer command-and-control, not normally operator/GCS control.)"]
MAV_CMD_GUIDED_CHANGE_ALTITUDE = 43001,
#[doc = "Change to target heading at a given rate, overriding previous heading/s. This slews the vehicle at a controllable rate between it's previous heading and the new one. (affects GUIDED only. Exiting GUIDED returns aircraft to normal behaviour defined elsewhere. Designed for onboard companion-computer command-and-control, not normally operator/GCS control.)"]
MAV_CMD_GUIDED_CHANGE_HEADING = 43002,
}
impl Default for MavCmd {
fn default() -> Self {
Self::MAV_CMD_NAV_WAYPOINT
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Result from a MAVLink command (MAV_CMD)"]
pub enum MavResult {
#[doc = "Command is valid (is supported and has valid parameters), and was executed."]
MAV_RESULT_ACCEPTED = 0,
#[doc = "Command is valid, but cannot be executed at this time. This is used to indicate a problem that should be fixed just by waiting (e.g. a state machine is busy, can't arm because have not got GPS lock, etc.). Retrying later should work."]
MAV_RESULT_TEMPORARILY_REJECTED = 1,
#[doc = "Command is invalid (is supported but has invalid parameters). Retrying same command and parameters will not work."]
MAV_RESULT_DENIED = 2,
#[doc = "Command is not supported (unknown)."]
MAV_RESULT_UNSUPPORTED = 3,
#[doc = "Command is valid, but execution has failed. This is used to indicate any non-temporary or unexpected problem, i.e. any problem that must be fixed before the command can succeed/be retried. For example, attempting to write a file when out of memory, attempting to arm when sensors are not calibrated, etc."]
MAV_RESULT_FAILED = 4,
#[doc = "Command is valid and is being executed. This will be followed by further progress updates, i.e. the component may send further COMMAND_ACK messages with result MAV_RESULT_IN_PROGRESS (at a rate decided by the implementation), and must terminate by sending a COMMAND_ACK message with final result of the operation. The COMMAND_ACK.progress field can be used to indicate the progress of the operation."]
MAV_RESULT_IN_PROGRESS = 5,
#[doc = "Command has been cancelled (as a result of receiving a COMMAND_CANCEL message)."]
MAV_RESULT_CANCELLED = 6,
}
impl Default for MavResult {
fn default() -> Self {
Self::MAV_RESULT_ACCEPTED
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum MavOdidDescType {
#[doc = "Optional free-form text description of the purpose of the flight."]
MAV_ODID_DESC_TYPE_TEXT = 0,
#[doc = "Optional additional clarification when status == MAV_ODID_STATUS_EMERGENCY."]
MAV_ODID_DESC_TYPE_EMERGENCY = 1,
#[doc = "Optional additional clarification when status != MAV_ODID_STATUS_EMERGENCY."]
MAV_ODID_DESC_TYPE_EXTENDED_STATUS = 2,
}
impl Default for MavOdidDescType {
fn default() -> Self {
Self::MAV_ODID_DESC_TYPE_TEXT
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "Flags in EKF_STATUS message."] pub struct EkfStatusFlags : u16 { # [doc = "Set if EKF's attitude estimate is good."] const EKF_ATTITUDE = 1 ; # [doc = "Set if EKF's horizontal velocity estimate is good."] const EKF_VELOCITY_HORIZ = 2 ; # [doc = "Set if EKF's vertical velocity estimate is good."] const EKF_VELOCITY_VERT = 4 ; # [doc = "Set if EKF's horizontal position (relative) estimate is good."] const EKF_POS_HORIZ_REL = 8 ; # [doc = "Set if EKF's horizontal position (absolute) estimate is good."] const EKF_POS_HORIZ_ABS = 16 ; # [doc = "Set if EKF's vertical position (absolute) estimate is good."] const EKF_POS_VERT_ABS = 32 ; # [doc = "Set if EKF's vertical position (above ground) estimate is good."] const EKF_POS_VERT_AGL = 64 ; # [doc = "EKF is in constant position mode and does not know it's absolute or relative position."] const EKF_CONST_POS_MODE = 128 ; # [doc = "Set if EKF's predicted horizontal position (relative) estimate is good."] const EKF_PRED_POS_HORIZ_REL = 256 ; # [doc = "Set if EKF's predicted horizontal position (absolute) estimate is good."] const EKF_PRED_POS_HORIZ_ABS = 512 ; # [doc = "Set if EKF has never been healthy."] const EKF_UNINITIALIZED = 1024 ; } }
impl Default for EkfStatusFlags {
fn default() -> Self {
Self::EKF_ATTITUDE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "States of the mission state machine. Note that these states are independent of whether the mission is in a mode that can execute mission items or not (is suspended). They may not all be relevant on all vehicles."]
pub enum MissionState {
#[doc = "The mission status reporting is not supported."]
MISSION_STATE_UNKNOWN = 0,
#[doc = "No mission on the vehicle."]
MISSION_STATE_NO_MISSION = 1,
#[doc = "Mission has not started. This is the case after a mission has uploaded but not yet started executing."]
MISSION_STATE_NOT_STARTED = 2,
#[doc = "Mission is active, and will execute mission items when in auto mode."]
MISSION_STATE_ACTIVE = 3,
#[doc = "Mission is paused when in auto mode."]
MISSION_STATE_PAUSED = 4,
#[doc = "Mission has executed all mission items."]
MISSION_STATE_COMPLETE = 5,
}
impl Default for MissionState {
fn default() -> Self {
Self::MISSION_STATE_UNKNOWN
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum MavOdidSpeedAcc {
#[doc = "The speed accuracy is unknown."]
MAV_ODID_SPEED_ACC_UNKNOWN = 0,
#[doc = "The speed accuracy is smaller than 10 meters per second."]
MAV_ODID_SPEED_ACC_10_METERS_PER_SECOND = 1,
#[doc = "The speed accuracy is smaller than 3 meters per second."]
MAV_ODID_SPEED_ACC_3_METERS_PER_SECOND = 2,
#[doc = "The speed accuracy is smaller than 1 meters per second."]
MAV_ODID_SPEED_ACC_1_METERS_PER_SECOND = 3,
#[doc = "The speed accuracy is smaller than 0.3 meters per second."]
MAV_ODID_SPEED_ACC_0_3_METERS_PER_SECOND = 4,
}
impl Default for MavOdidSpeedAcc {
fn default() -> Self {
Self::MAV_ODID_SPEED_ACC_UNKNOWN
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Possible responses from a WIFI_CONFIG_AP message."]
pub enum WifiConfigApResponse {
#[doc = "Undefined response. Likely an indicative of a system that doesn't support this request."]
WIFI_CONFIG_AP_RESPONSE_UNDEFINED = 0,
#[doc = "Changes accepted."]
WIFI_CONFIG_AP_RESPONSE_ACCEPTED = 1,
#[doc = "Changes rejected."]
WIFI_CONFIG_AP_RESPONSE_REJECTED = 2,
#[doc = "Invalid Mode."]
WIFI_CONFIG_AP_RESPONSE_MODE_ERROR = 3,
#[doc = "Invalid SSID."]
WIFI_CONFIG_AP_RESPONSE_SSID_ERROR = 4,
#[doc = "Invalid Password."]
WIFI_CONFIG_AP_RESPONSE_PASSWORD_ERROR = 5,
}
impl Default for WifiConfigApResponse {
fn default() -> Self {
Self::WIFI_CONFIG_AP_RESPONSE_UNDEFINED
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "Flags to report status/failure cases for a power generator (used in GENERATOR_STATUS). Note that FAULTS are conditions that cause the generator to fail. Warnings are conditions that require attention before the next use (they indicate the system is not operating properly)."] pub struct MavGeneratorStatusFlag : u64 { # [doc = "Generator is off."] const MAV_GENERATOR_STATUS_FLAG_OFF = 1 ; # [doc = "Generator is ready to start generating power."] const MAV_GENERATOR_STATUS_FLAG_READY = 2 ; # [doc = "Generator is generating power."] const MAV_GENERATOR_STATUS_FLAG_GENERATING = 4 ; # [doc = "Generator is charging the batteries (generating enough power to charge and provide the load)."] const MAV_GENERATOR_STATUS_FLAG_CHARGING = 8 ; # [doc = "Generator is operating at a reduced maximum power."] const MAV_GENERATOR_STATUS_FLAG_REDUCED_POWER = 16 ; # [doc = "Generator is providing the maximum output."] const MAV_GENERATOR_STATUS_FLAG_MAXPOWER = 32 ; # [doc = "Generator is near the maximum operating temperature, cooling is insufficient."] const MAV_GENERATOR_STATUS_FLAG_OVERTEMP_WARNING = 64 ; # [doc = "Generator hit the maximum operating temperature and shutdown."] const MAV_GENERATOR_STATUS_FLAG_OVERTEMP_FAULT = 128 ; # [doc = "Power electronics are near the maximum operating temperature, cooling is insufficient."] const MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_WARNING = 256 ; # [doc = "Power electronics hit the maximum operating temperature and shutdown."] const MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_FAULT = 512 ; # [doc = "Power electronics experienced a fault and shutdown."] const MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_FAULT = 1024 ; # [doc = "The power source supplying the generator failed e.g. mechanical generator stopped, tether is no longer providing power, solar cell is in shade, hydrogen reaction no longer happening."] const MAV_GENERATOR_STATUS_FLAG_POWERSOURCE_FAULT = 2048 ; # [doc = "Generator controller having communication problems."] const MAV_GENERATOR_STATUS_FLAG_COMMUNICATION_WARNING = 4096 ; # [doc = "Power electronic or generator cooling system error."] const MAV_GENERATOR_STATUS_FLAG_COOLING_WARNING = 8192 ; # [doc = "Generator controller power rail experienced a fault."] const MAV_GENERATOR_STATUS_FLAG_POWER_RAIL_FAULT = 16384 ; # [doc = "Generator controller exceeded the overcurrent threshold and shutdown to prevent damage."] const MAV_GENERATOR_STATUS_FLAG_OVERCURRENT_FAULT = 32768 ; # [doc = "Generator controller detected a high current going into the batteries and shutdown to prevent battery damage."] const MAV_GENERATOR_STATUS_FLAG_BATTERY_OVERCHARGE_CURRENT_FAULT = 65536 ; # [doc = "Generator controller exceeded it's overvoltage threshold and shutdown to prevent it exceeding the voltage rating."] const MAV_GENERATOR_STATUS_FLAG_OVERVOLTAGE_FAULT = 131072 ; # [doc = "Batteries are under voltage (generator will not start)."] const MAV_GENERATOR_STATUS_FLAG_BATTERY_UNDERVOLT_FAULT = 262144 ; # [doc = "Generator start is inhibited by e.g. a safety switch."] const MAV_GENERATOR_STATUS_FLAG_START_INHIBITED = 524288 ; # [doc = "Generator requires maintenance."] const MAV_GENERATOR_STATUS_FLAG_MAINTENANCE_REQUIRED = 1048576 ; # [doc = "Generator is not ready to generate yet."] const MAV_GENERATOR_STATUS_FLAG_WARMING_UP = 2097152 ; # [doc = "Generator is idle."] const MAV_GENERATOR_STATUS_FLAG_IDLE = 4194304 ; } }
impl Default for MavGeneratorStatusFlag {
fn default() -> Self {
Self::MAV_GENERATOR_STATUS_FLAG_OFF
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum MavModeGimbal {
#[doc = "Gimbal is powered on but has not started initializing yet."]
MAV_MODE_GIMBAL_UNINITIALIZED = 0,
#[doc = "Gimbal is currently running calibration on the pitch axis."]
MAV_MODE_GIMBAL_CALIBRATING_PITCH = 1,
#[doc = "Gimbal is currently running calibration on the roll axis."]
MAV_MODE_GIMBAL_CALIBRATING_ROLL = 2,
#[doc = "Gimbal is currently running calibration on the yaw axis."]
MAV_MODE_GIMBAL_CALIBRATING_YAW = 3,
#[doc = "Gimbal has finished calibrating and initializing, but is relaxed pending reception of first rate command from copter."]
MAV_MODE_GIMBAL_INITIALIZED = 4,
#[doc = "Gimbal is actively stabilizing."]
MAV_MODE_GIMBAL_ACTIVE = 5,
#[doc = "Gimbal is relaxed because it missed more than 10 expected rate command messages in a row. Gimbal will move back to active mode when it receives a new rate command."]
MAV_MODE_GIMBAL_RATE_CMD_TIMEOUT = 6,
}
impl Default for MavModeGimbal {
fn default() -> Self {
Self::MAV_MODE_GIMBAL_UNINITIALIZED
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Flags for high level gimbal manager operation The first 16 bits are identical to the GIMBAL_DEVICE_FLAGS."]
pub enum GimbalManagerFlags {
#[doc = "Based on GIMBAL_DEVICE_FLAGS_RETRACT."]
GIMBAL_MANAGER_FLAGS_RETRACT = 1,
#[doc = "Based on GIMBAL_DEVICE_FLAGS_NEUTRAL."]
GIMBAL_MANAGER_FLAGS_NEUTRAL = 2,
#[doc = "Based on GIMBAL_DEVICE_FLAGS_ROLL_LOCK."]
GIMBAL_MANAGER_FLAGS_ROLL_LOCK = 4,
#[doc = "Based on GIMBAL_DEVICE_FLAGS_PITCH_LOCK."]
GIMBAL_MANAGER_FLAGS_PITCH_LOCK = 8,
#[doc = "Based on GIMBAL_DEVICE_FLAGS_YAW_LOCK."]
GIMBAL_MANAGER_FLAGS_YAW_LOCK = 16,
#[doc = "Based on GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME."]
GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME = 32,
#[doc = "Based on GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME."]
GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME = 64,
#[doc = "Based on GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME."]
GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME = 128,
#[doc = "Based on GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE."]
GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE = 256,
#[doc = "Based on GIMBAL_DEVICE_FLAGS_RC_MIXED."]
GIMBAL_MANAGER_FLAGS_RC_MIXED = 512,
}
impl Default for GimbalManagerFlags {
fn default() -> Self {
Self::GIMBAL_MANAGER_FLAGS_RETRACT
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum MagCalStatus {
MAG_CAL_NOT_STARTED = 0,
MAG_CAL_WAITING_TO_START = 1,
MAG_CAL_RUNNING_STEP_ONE = 2,
MAG_CAL_RUNNING_STEP_TWO = 3,
MAG_CAL_SUCCESS = 4,
MAG_CAL_FAILED = 5,
MAG_CAL_BAD_ORIENTATION = 6,
MAG_CAL_BAD_RADIUS = 7,
}
impl Default for MagCalStatus {
fn default() -> Self {
Self::MAG_CAL_NOT_STARTED
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "A mapping of copter flight modes for custom_mode field of heartbeat."]
pub enum CopterMode {
COPTER_MODE_STABILIZE = 0,
COPTER_MODE_ACRO = 1,
COPTER_MODE_ALT_HOLD = 2,
COPTER_MODE_AUTO = 3,
COPTER_MODE_GUIDED = 4,
COPTER_MODE_LOITER = 5,
COPTER_MODE_RTL = 6,
COPTER_MODE_CIRCLE = 7,
COPTER_MODE_LAND = 9,
COPTER_MODE_DRIFT = 11,
COPTER_MODE_SPORT = 13,
COPTER_MODE_FLIP = 14,
COPTER_MODE_AUTOTUNE = 15,
COPTER_MODE_POSHOLD = 16,
COPTER_MODE_BRAKE = 17,
COPTER_MODE_THROW = 18,
COPTER_MODE_AVOID_ADSB = 19,
COPTER_MODE_GUIDED_NOGPS = 20,
COPTER_MODE_SMART_RTL = 21,
COPTER_MODE_FLOWHOLD = 22,
COPTER_MODE_FOLLOW = 23,
COPTER_MODE_ZIGZAG = 24,
COPTER_MODE_SYSTEMID = 25,
COPTER_MODE_AUTOROTATE = 26,
COPTER_MODE_AUTO_RTL = 27,
}
impl Default for CopterMode {
fn default() -> Self {
Self::COPTER_MODE_STABILIZE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Definitions for aircraft size"]
pub enum UavionixAdsbOutCfgAircraftSize {
UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_NO_DATA = 0,
UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L15M_W23M = 1,
UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L25M_W28P5M = 2,
UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L25_34M = 3,
UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L35_33M = 4,
UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L35_38M = 5,
UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L45_39P5M = 6,
UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L45_45M = 7,
UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L55_45M = 8,
UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L55_52M = 9,
UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L65_59P5M = 10,
UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L65_67M = 11,
UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L75_W72P5M = 12,
UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L75_W80M = 13,
UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L85_W80M = 14,
UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L85_W90M = 15,
}
impl Default for UavionixAdsbOutCfgAircraftSize {
fn default() -> Self {
Self::UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_NO_DATA
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "Flags for gimbal device (lower level) operation."] pub struct GimbalDeviceFlags : u16 { # [doc = "Set to retracted safe position (no stabilization), takes presedence over all other flags."] const GIMBAL_DEVICE_FLAGS_RETRACT = 1 ; # [doc = "Set to neutral/default position, taking precedence over all other flags except RETRACT. Neutral is commonly forward-facing and horizontal (roll=pitch=yaw=0) but may be any orientation."] const GIMBAL_DEVICE_FLAGS_NEUTRAL = 2 ; # [doc = "Lock roll angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal."] const GIMBAL_DEVICE_FLAGS_ROLL_LOCK = 4 ; # [doc = "Lock pitch angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal."] const GIMBAL_DEVICE_FLAGS_PITCH_LOCK = 8 ; # [doc = "Lock yaw angle to absolute angle relative to North (not relative to vehicle). If this flag is set, the yaw angle and z component of angular velocity are relative to North (earth frame, x-axis pointing North), else they are relative to the vehicle heading (vehicle frame, earth frame rotated so that the x-axis is pointing forward)."] const GIMBAL_DEVICE_FLAGS_YAW_LOCK = 16 ; # [doc = "Yaw angle and z component of angular velocity are relative to the vehicle heading (vehicle frame, earth frame rotated such that the x-axis is pointing forward)."] const GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME = 32 ; # [doc = "Yaw angle and z component of angular velocity are relative to North (earth frame, x-axis is pointing North)."] const GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME = 64 ; # [doc = "Gimbal device can accept yaw angle inputs relative to North (earth frame). This flag is only for reporting (attempts to set this flag are ignored)."] const GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME = 128 ; # [doc = "The gimbal orientation is set exclusively by the RC signals feed to the gimbal's radio control inputs. MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE) are ignored."] const GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE = 256 ; # [doc = "The gimbal orientation is determined by combining/mixing the RC signals feed to the gimbal's radio control inputs and the MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE). How these two controls are combined or mixed is not defined by the protocol but is up to the implementation."] const GIMBAL_DEVICE_FLAGS_RC_MIXED = 512 ; } }
impl Default for GimbalDeviceFlags {
fn default() -> Self {
Self::GIMBAL_DEVICE_FLAGS_RETRACT
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "A mapping of plane flight modes for custom_mode field of heartbeat."]
pub enum PlaneMode {
PLANE_MODE_MANUAL = 0,
PLANE_MODE_CIRCLE = 1,
PLANE_MODE_STABILIZE = 2,
PLANE_MODE_TRAINING = 3,
PLANE_MODE_ACRO = 4,
PLANE_MODE_FLY_BY_WIRE_A = 5,
PLANE_MODE_FLY_BY_WIRE_B = 6,
PLANE_MODE_CRUISE = 7,
PLANE_MODE_AUTOTUNE = 8,
PLANE_MODE_AUTO = 10,
PLANE_MODE_RTL = 11,
PLANE_MODE_LOITER = 12,
PLANE_MODE_TAKEOFF = 13,
PLANE_MODE_AVOID_ADSB = 14,
PLANE_MODE_GUIDED = 15,
PLANE_MODE_INITIALIZING = 16,
PLANE_MODE_QSTABILIZE = 17,
PLANE_MODE_QHOVER = 18,
PLANE_MODE_QLOITER = 19,
PLANE_MODE_QLAND = 20,
PLANE_MODE_QRTL = 21,
PLANE_MODE_QAUTOTUNE = 22,
PLANE_MODE_QACRO = 23,
PLANE_MODE_THERMAL = 24,
}
impl Default for PlaneMode {
fn default() -> Self {
Self::PLANE_MODE_MANUAL
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/."]
pub enum MavSeverity {
#[doc = "System is unusable. This is a \"panic\" condition."]
MAV_SEVERITY_EMERGENCY = 0,
#[doc = "Action should be taken immediately. Indicates error in non-critical systems."]
MAV_SEVERITY_ALERT = 1,
#[doc = "Action must be taken immediately. Indicates failure in a primary system."]
MAV_SEVERITY_CRITICAL = 2,
#[doc = "Indicates an error in secondary/redundant systems."]
MAV_SEVERITY_ERROR = 3,
#[doc = "Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning."]
MAV_SEVERITY_WARNING = 4,
#[doc = "An unusual event has occurred, though not an error condition. This should be investigated for the root cause."]
MAV_SEVERITY_NOTICE = 5,
#[doc = "Normal operational messages. Useful for logging. No action is required for these messages."]
MAV_SEVERITY_INFO = 6,
#[doc = "Useful non-operational messages that can assist in debugging. These should not occur during normal operation."]
MAV_SEVERITY_DEBUG = 7,
}
impl Default for MavSeverity {
fn default() -> Self {
Self::MAV_SEVERITY_EMERGENCY
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum MavOdidIdType {
#[doc = "No type defined."]
MAV_ODID_ID_TYPE_NONE = 0,
#[doc = "Manufacturer Serial Number (ANSI/CTA-2063 format)."]
MAV_ODID_ID_TYPE_SERIAL_NUMBER = 1,
#[doc = "CAA (Civil Aviation Authority) registered ID. Format: [ICAO Country Code].[CAA Assigned ID]."]
MAV_ODID_ID_TYPE_CAA_REGISTRATION_ID = 2,
#[doc = "UTM (Unmanned Traffic Management) assigned UUID (RFC4122)."]
MAV_ODID_ID_TYPE_UTM_ASSIGNED_UUID = 3,
#[doc = "A 20 byte ID for a specific flight/session. The exact ID type is indicated by the first byte of uas_id and these type values are managed by ICAO."]
MAV_ODID_ID_TYPE_SPECIFIC_SESSION_ID = 4,
}
impl Default for MavOdidIdType {
fn default() -> Self {
Self::MAV_ODID_ID_TYPE_NONE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Camera tracking target data (shows where tracked target is within image)"]
pub enum CameraTrackingTargetData {
#[doc = "No target data"]
CAMERA_TRACKING_TARGET_DATA_NONE = 0,
#[doc = "Target data embedded in image data (proprietary)"]
CAMERA_TRACKING_TARGET_DATA_EMBEDDED = 1,
#[doc = "Target data rendered in image"]
CAMERA_TRACKING_TARGET_DATA_RENDERED = 2,
#[doc = "Target data within status message (Point or Rectangle)"]
CAMERA_TRACKING_TARGET_DATA_IN_STATUS = 4,
}
impl Default for CameraTrackingTargetData {
fn default() -> Self {
Self::CAMERA_TRACKING_TARGET_DATA_NONE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum MavOdidUaType {
#[doc = "No UA (Unmanned Aircraft) type defined."]
MAV_ODID_UA_TYPE_NONE = 0,
#[doc = "Aeroplane/Airplane. Fixed wing."]
MAV_ODID_UA_TYPE_AEROPLANE = 1,
#[doc = "Helicopter or multirotor."]
MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR = 2,
#[doc = "Gyroplane."]
MAV_ODID_UA_TYPE_GYROPLANE = 3,
#[doc = "VTOL (Vertical Take-Off and Landing). Fixed wing aircraft that can take off vertically."]
MAV_ODID_UA_TYPE_HYBRID_LIFT = 4,
#[doc = "Ornithopter."]
MAV_ODID_UA_TYPE_ORNITHOPTER = 5,
#[doc = "Glider."]
MAV_ODID_UA_TYPE_GLIDER = 6,
#[doc = "Kite."]
MAV_ODID_UA_TYPE_KITE = 7,
#[doc = "Free Balloon."]
MAV_ODID_UA_TYPE_FREE_BALLOON = 8,
#[doc = "Captive Balloon."]
MAV_ODID_UA_TYPE_CAPTIVE_BALLOON = 9,
#[doc = "Airship. E.g. a blimp."]
MAV_ODID_UA_TYPE_AIRSHIP = 10,
#[doc = "Free Fall/Parachute (unpowered)."]
MAV_ODID_UA_TYPE_FREE_FALL_PARACHUTE = 11,
#[doc = "Rocket."]
MAV_ODID_UA_TYPE_ROCKET = 12,
#[doc = "Tethered powered aircraft."]
MAV_ODID_UA_TYPE_TETHERED_POWERED_AIRCRAFT = 13,
#[doc = "Ground Obstacle."]
MAV_ODID_UA_TYPE_GROUND_OBSTACLE = 14,
#[doc = "Other type of aircraft not listed earlier."]
MAV_ODID_UA_TYPE_OTHER = 15,
}
impl Default for MavOdidUaType {
fn default() -> Self {
Self::MAV_ODID_UA_TYPE_NONE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Zoom types for MAV_CMD_SET_CAMERA_ZOOM"]
pub enum CameraZoomType {
#[doc = "Zoom one step increment (-1 for wide, 1 for tele)"]
ZOOM_TYPE_STEP = 0,
#[doc = "Continuous zoom up/down until stopped (-1 for wide, 1 for tele, 0 to stop zooming)"]
ZOOM_TYPE_CONTINUOUS = 1,
#[doc = "Zoom value as proportion of full camera range (a percentage value between 0.0 and 100.0)"]
ZOOM_TYPE_RANGE = 2,
#[doc = "Zoom value/variable focal length in millimetres. Note that there is no message to get the valid zoom range of the camera, so this can type can only be used for cameras where the zoom range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera)"]
ZOOM_TYPE_FOCAL_LENGTH = 3,
}
impl Default for CameraZoomType {
fn default() -> Self {
Self::ZOOM_TYPE_STEP
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates that none of the setpoint dimensions should be ignored."] pub struct AttitudeTargetTypemask : u8 { # [doc = "Ignore body roll rate"] const ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE = 1 ; # [doc = "Ignore body pitch rate"] const ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE = 2 ; # [doc = "Ignore body yaw rate"] const ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE = 4 ; # [doc = "Use 3D body thrust setpoint instead of throttle"] const ATTITUDE_TARGET_TYPEMASK_THRUST_BODY_SET = 32 ; # [doc = "Ignore throttle"] const ATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE = 64 ; # [doc = "Ignore attitude"] const ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE = 128 ; } }
impl Default for AttitudeTargetTypemask {
fn default() -> Self {
Self::ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Enumeration of battery types"]
pub enum MavBatteryType {
#[doc = "Not specified."]
MAV_BATTERY_TYPE_UNKNOWN = 0,
#[doc = "Lithium polymer battery"]
MAV_BATTERY_TYPE_LIPO = 1,
#[doc = "Lithium-iron-phosphate battery"]
MAV_BATTERY_TYPE_LIFE = 2,
#[doc = "Lithium-ION battery"]
MAV_BATTERY_TYPE_LION = 3,
#[doc = "Nickel metal hydride battery"]
MAV_BATTERY_TYPE_NIMH = 4,
}
impl Default for MavBatteryType {
fn default() -> Self {
Self::MAV_BATTERY_TYPE_UNKNOWN
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "Camera capability flags (Bitmap)"] pub struct CameraCapFlags : u32 { # [doc = "Camera is able to record video"] const CAMERA_CAP_FLAGS_CAPTURE_VIDEO = 1 ; # [doc = "Camera is able to capture images"] const CAMERA_CAP_FLAGS_CAPTURE_IMAGE = 2 ; # [doc = "Camera has separate Video and Image/Photo modes (MAV_CMD_SET_CAMERA_MODE)"] const CAMERA_CAP_FLAGS_HAS_MODES = 4 ; # [doc = "Camera can capture images while in video mode"] const CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE = 8 ; # [doc = "Camera can capture videos while in Photo/Image mode"] const CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE = 16 ; # [doc = "Camera has image survey mode (MAV_CMD_SET_CAMERA_MODE)"] const CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE = 32 ; # [doc = "Camera has basic zoom control (MAV_CMD_SET_CAMERA_ZOOM)"] const CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM = 64 ; # [doc = "Camera has basic focus control (MAV_CMD_SET_CAMERA_FOCUS)"] const CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS = 128 ; # [doc = "Camera has video streaming capabilities (request VIDEO_STREAM_INFORMATION with MAV_CMD_REQUEST_MESSAGE for video streaming info)"] const CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM = 256 ; # [doc = "Camera supports tracking of a point on the camera view."] const CAMERA_CAP_FLAGS_HAS_TRACKING_POINT = 512 ; # [doc = "Camera supports tracking of a selection rectangle on the camera view."] const CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE = 1024 ; # [doc = "Camera supports tracking geo status (CAMERA_TRACKING_GEO_STATUS)."] const CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS = 2048 ; } }
impl Default for CameraCapFlags {
fn default() -> Self {
Self::CAMERA_CAP_FLAGS_CAPTURE_VIDEO
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Possible actions an aircraft can take to avoid a collision."]
pub enum MavCollisionAction {
#[doc = "Ignore any potential collisions"]
MAV_COLLISION_ACTION_NONE = 0,
#[doc = "Report potential collision"]
MAV_COLLISION_ACTION_REPORT = 1,
#[doc = "Ascend or Descend to avoid threat"]
MAV_COLLISION_ACTION_ASCEND_OR_DESCEND = 2,
#[doc = "Move horizontally to avoid threat"]
MAV_COLLISION_ACTION_MOVE_HORIZONTALLY = 3,
#[doc = "Aircraft to move perpendicular to the collision's velocity vector"]
MAV_COLLISION_ACTION_MOVE_PERPENDICULAR = 4,
#[doc = "Aircraft to fly directly back to its launch point"]
MAV_COLLISION_ACTION_RTL = 5,
#[doc = "Aircraft to stop in place"]
MAV_COLLISION_ACTION_HOVER = 6,
}
impl Default for MavCollisionAction {
fn default() -> Self {
Self::MAV_COLLISION_ACTION_NONE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Actions following geofence breach."]
pub enum FenceAction {
#[doc = "Disable fenced mode. If used in a plan this would mean the next fence is disabled."]
FENCE_ACTION_NONE = 0,
#[doc = "Fly to geofence MAV_CMD_NAV_FENCE_RETURN_POINT in GUIDED mode. Note: This action is only supported by ArduPlane, and may not be supported in all versions."]
FENCE_ACTION_GUIDED = 1,
#[doc = "Report fence breach, but don't take action"]
FENCE_ACTION_REPORT = 2,
#[doc = "Fly to geofence MAV_CMD_NAV_FENCE_RETURN_POINT with manual throttle control in GUIDED mode. Note: This action is only supported by ArduPlane, and may not be supported in all versions."]
FENCE_ACTION_GUIDED_THR_PASS = 3,
#[doc = "Return/RTL mode."]
FENCE_ACTION_RTL = 4,
#[doc = "Hold at current location."]
FENCE_ACTION_HOLD = 5,
#[doc = "Termination failsafe. Motors are shut down (some flight stacks may trigger other failsafe actions)."]
FENCE_ACTION_TERMINATE = 6,
#[doc = "Land at current location."]
FENCE_ACTION_LAND = 7,
}
impl Default for FenceAction {
fn default() -> Self {
Self::FENCE_ACTION_NONE
}
}
bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [doc = "Tune formats (used for vehicle buzzer/tone generation)."] pub struct TuneFormat : u32 { # [doc = "Format is QBasic 1.1 Play: https://www.qbasic.net/en/reference/qb11/Statement/PLAY-006.htm."] const TUNE_FORMAT_QBASIC1_1 = 1 ; # [doc = "Format is Modern Music Markup Language (MML): https://en.wikipedia.org/wiki/Music_Macro_Language#Modern_MML."] const TUNE_FORMAT_MML_MODERN = 2 ; } }
impl Default for TuneFormat {
fn default() -> Self {
Self::TUNE_FORMAT_QBASIC1_1
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override."]
pub enum MavMode {
#[doc = "System is not ready to fly, booting, calibrating, etc. No flag is set."]
MAV_MODE_PREFLIGHT = 0,
#[doc = "System is allowed to be active, under assisted RC control."]
MAV_MODE_STABILIZE_DISARMED = 80,
#[doc = "System is allowed to be active, under assisted RC control."]
MAV_MODE_STABILIZE_ARMED = 208,
#[doc = "System is allowed to be active, under manual (RC) control, no stabilization"]
MAV_MODE_MANUAL_DISARMED = 64,
#[doc = "System is allowed to be active, under manual (RC) control, no stabilization"]
MAV_MODE_MANUAL_ARMED = 192,
#[doc = "System is allowed to be active, under autonomous control, manual setpoint"]
MAV_MODE_GUIDED_DISARMED = 88,
#[doc = "System is allowed to be active, under autonomous control, manual setpoint"]
MAV_MODE_GUIDED_ARMED = 216,
#[doc = "System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints)"]
MAV_MODE_AUTO_DISARMED = 92,
#[doc = "System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints)"]
MAV_MODE_AUTO_ARMED = 220,
#[doc = "UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only."]
MAV_MODE_TEST_DISARMED = 66,
#[doc = "UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only."]
MAV_MODE_TEST_ARMED = 194,
}
impl Default for MavMode {
fn default() -> Self {
Self::MAV_MODE_PREFLIGHT
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum MavArmAuthDeniedReason {
#[doc = "Not a specific reason"]
MAV_ARM_AUTH_DENIED_REASON_GENERIC = 0,
#[doc = "Authorizer will send the error as string to GCS"]
MAV_ARM_AUTH_DENIED_REASON_NONE = 1,
#[doc = "At least one waypoint have a invalid value"]
MAV_ARM_AUTH_DENIED_REASON_INVALID_WAYPOINT = 2,
#[doc = "Timeout in the authorizer process(in case it depends on network)"]
MAV_ARM_AUTH_DENIED_REASON_TIMEOUT = 3,
#[doc = "Airspace of the mission in use by another vehicle, second result parameter can have the waypoint id that caused it to be denied."]
MAV_ARM_AUTH_DENIED_REASON_AIRSPACE_IN_USE = 4,
#[doc = "Weather is not good to fly"]
MAV_ARM_AUTH_DENIED_REASON_BAD_WEATHER = 5,
}
impl Default for MavArmAuthDeniedReason {
fn default() -> Self {
Self::MAV_ARM_AUTH_DENIED_REASON_GENERIC
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "SERIAL_CONTROL device types"]
pub enum SerialControlDev {
#[doc = "First telemetry port"]
SERIAL_CONTROL_DEV_TELEM1 = 0,
#[doc = "Second telemetry port"]
SERIAL_CONTROL_DEV_TELEM2 = 1,
#[doc = "First GPS port"]
SERIAL_CONTROL_DEV_GPS1 = 2,
#[doc = "Second GPS port"]
SERIAL_CONTROL_DEV_GPS2 = 3,
#[doc = "system shell"]
SERIAL_CONTROL_DEV_SHELL = 10,
#[doc = "SERIAL0"]
SERIAL_CONTROL_SERIAL0 = 100,
#[doc = "SERIAL1"]
SERIAL_CONTROL_SERIAL1 = 101,
#[doc = "SERIAL2"]
SERIAL_CONTROL_SERIAL2 = 102,
#[doc = "SERIAL3"]
SERIAL_CONTROL_SERIAL3 = 103,
#[doc = "SERIAL4"]
SERIAL_CONTROL_SERIAL4 = 104,
#[doc = "SERIAL5"]
SERIAL_CONTROL_SERIAL5 = 105,
#[doc = "SERIAL6"]
SERIAL_CONTROL_SERIAL6 = 106,
#[doc = "SERIAL7"]
SERIAL_CONTROL_SERIAL7 = 107,
#[doc = "SERIAL8"]
SERIAL_CONTROL_SERIAL8 = 108,
#[doc = "SERIAL9"]
SERIAL_CONTROL_SERIAL9 = 109,
}
impl Default for SerialControlDev {
fn default() -> Self {
Self::SERIAL_CONTROL_DEV_TELEM1
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "WiFi Mode."]
pub enum WifiConfigApMode {
#[doc = "WiFi mode is undefined."]
WIFI_CONFIG_AP_MODE_UNDEFINED = 0,
#[doc = "WiFi configured as an access point."]
WIFI_CONFIG_AP_MODE_AP = 1,
#[doc = "WiFi configured as a station connected to an existing local WiFi network."]
WIFI_CONFIG_AP_MODE_STATION = 2,
#[doc = "WiFi disabled."]
WIFI_CONFIG_AP_MODE_DISABLED = 3,
}
impl Default for WifiConfigApMode {
fn default() -> Self {
Self::WIFI_CONFIG_AP_MODE_UNDEFINED
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Gripper actions."]
pub enum GripperActions {
#[doc = "Gripper release cargo."]
GRIPPER_ACTION_RELEASE = 0,
#[doc = "Gripper grab onto cargo."]
GRIPPER_ACTION_GRAB = 1,
}
impl Default for GripperActions {
fn default() -> Self {
Self::GRIPPER_ACTION_RELEASE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Reason for an event error response."]
pub enum MavEventErrorReason {
#[doc = "The requested event is not available (anymore)."]
MAV_EVENT_ERROR_REASON_UNAVAILABLE = 0,
}
impl Default for MavEventErrorReason {
fn default() -> Self {
Self::MAV_EVENT_ERROR_REASON_UNAVAILABLE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum GoproModel {
#[doc = "Unknown gopro model."]
GOPRO_MODEL_UNKNOWN = 0,
#[doc = "Hero 3+ Silver (HeroBus not supported by GoPro)."]
GOPRO_MODEL_HERO_3_PLUS_SILVER = 1,
#[doc = "Hero 3+ Black."]
GOPRO_MODEL_HERO_3_PLUS_BLACK = 2,
#[doc = "Hero 4 Silver."]
GOPRO_MODEL_HERO_4_SILVER = 3,
#[doc = "Hero 4 Black."]
GOPRO_MODEL_HERO_4_BLACK = 4,
}
impl Default for GoproModel {
fn default() -> Self {
Self::GOPRO_MODEL_UNKNOWN
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Result of mission operation (in a MISSION_ACK message)."]
pub enum MavMissionResult {
#[doc = "mission accepted OK"]
MAV_MISSION_ACCEPTED = 0,
#[doc = "Generic error / not accepting mission commands at all right now."]
MAV_MISSION_ERROR = 1,
#[doc = "Coordinate frame is not supported."]
MAV_MISSION_UNSUPPORTED_FRAME = 2,
#[doc = "Command is not supported."]
MAV_MISSION_UNSUPPORTED = 3,
#[doc = "Mission items exceed storage space."]
MAV_MISSION_NO_SPACE = 4,
#[doc = "One of the parameters has an invalid value."]
MAV_MISSION_INVALID = 5,
#[doc = "param1 has an invalid value."]
MAV_MISSION_INVALID_PARAM1 = 6,
#[doc = "param2 has an invalid value."]
MAV_MISSION_INVALID_PARAM2 = 7,
#[doc = "param3 has an invalid value."]
MAV_MISSION_INVALID_PARAM3 = 8,
#[doc = "param4 has an invalid value."]
MAV_MISSION_INVALID_PARAM4 = 9,
#[doc = "x / param5 has an invalid value."]
MAV_MISSION_INVALID_PARAM5_X = 10,
#[doc = "y / param6 has an invalid value."]
MAV_MISSION_INVALID_PARAM6_Y = 11,
#[doc = "z / param7 has an invalid value."]
MAV_MISSION_INVALID_PARAM7 = 12,
#[doc = "Mission item received out of sequence"]
MAV_MISSION_INVALID_SEQUENCE = 13,
#[doc = "Not accepting any mission commands from this communication partner."]
MAV_MISSION_DENIED = 14,
#[doc = "Current mission operation cancelled (e.g. mission upload, mission download)."]
MAV_MISSION_OPERATION_CANCELLED = 15,
}
impl Default for MavMissionResult {
fn default() -> Self {
Self::MAV_MISSION_ACCEPTED
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Indicates the ESC connection type."]
pub enum EscConnectionType {
#[doc = "Traditional PPM ESC."]
ESC_CONNECTION_TYPE_PPM = 0,
#[doc = "Serial Bus connected ESC."]
ESC_CONNECTION_TYPE_SERIAL = 1,
#[doc = "One Shot PPM ESC."]
ESC_CONNECTION_TYPE_ONESHOT = 2,
#[doc = "I2C ESC."]
ESC_CONNECTION_TYPE_I2C = 3,
#[doc = "CAN-Bus ESC."]
ESC_CONNECTION_TYPE_CAN = 4,
#[doc = "DShot ESC."]
ESC_CONNECTION_TYPE_DSHOT = 5,
}
impl Default for EscConnectionType {
fn default() -> Self {
Self::ESC_CONNECTION_TYPE_PPM
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Enumeration of VTOL states"]
pub enum MavVtolState {
#[doc = "MAV is not configured as VTOL"]
MAV_VTOL_STATE_UNDEFINED = 0,
#[doc = "VTOL is in transition from multicopter to fixed-wing"]
MAV_VTOL_STATE_TRANSITION_TO_FW = 1,
#[doc = "VTOL is in transition from fixed-wing to multicopter"]
MAV_VTOL_STATE_TRANSITION_TO_MC = 2,
#[doc = "VTOL is in multicopter state"]
MAV_VTOL_STATE_MC = 3,
#[doc = "VTOL is in fixed-wing state"]
MAV_VTOL_STATE_FW = 4,
}
impl Default for MavVtolState {
fn default() -> Self {
Self::MAV_VTOL_STATE_UNDEFINED
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum MavOdidArmStatus {
#[doc = "Passing arming checks."]
MAV_ODID_ARM_STATUS_GOOD_TO_ARM = 0,
#[doc = "Generic arming failure, see error string for details."]
MAV_ODID_ARM_STATUS_PRE_ARM_FAIL_GENERIC = 1,
}
impl Default for MavOdidArmStatus {
fn default() -> Self {
Self::MAV_ODID_ARM_STATUS_GOOD_TO_ARM
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Status for ADS-B transponder dynamic input"]
pub enum UavionixAdsbOutDynamicGpsFix {
UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_NONE_0 = 0,
UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_NONE_1 = 1,
UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_2D = 2,
UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_3D = 3,
UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_DGPS = 4,
UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_RTK = 5,
}
impl Default for UavionixAdsbOutDynamicGpsFix {
fn default() -> Self {
Self::UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_NONE_0
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Type of mission items being requested/sent in mission protocol."]
pub enum MavMissionType {
#[doc = "Items are mission commands for main mission."]
MAV_MISSION_TYPE_MISSION = 0,
#[doc = "Specifies GeoFence area(s). Items are MAV_CMD_NAV_FENCE_ GeoFence items."]
MAV_MISSION_TYPE_FENCE = 1,
#[doc = "Specifies the rally points for the vehicle. Rally points are alternative RTL points. Items are MAV_CMD_NAV_RALLY_POINT rally point items."]
MAV_MISSION_TYPE_RALLY = 2,
#[doc = "Only used in MISSION_CLEAR_ALL to clear all mission types."]
MAV_MISSION_TYPE_ALL = 255,
}
impl Default for MavMissionType {
fn default() -> Self {
Self::MAV_MISSION_TYPE_MISSION
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum CameraFeedbackFlags {
#[doc = "Shooting photos, not video."]
CAMERA_FEEDBACK_PHOTO = 0,
#[doc = "Shooting video, not stills."]
CAMERA_FEEDBACK_VIDEO = 1,
#[doc = "Unable to achieve requested exposure (e.g. shutter speed too low)."]
CAMERA_FEEDBACK_BADEXPOSURE = 2,
#[doc = "Closed loop feedback from camera, we know for sure it has successfully taken a picture."]
CAMERA_FEEDBACK_CLOSEDLOOP = 3,
#[doc = "Open loop camera, an image trigger has been requested but we can't know for sure it has successfully taken a picture."]
CAMERA_FEEDBACK_OPENLOOP = 4,
}
impl Default for CameraFeedbackFlags {
fn default() -> Self {
Self::CAMERA_FEEDBACK_PHOTO
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Enumeration of possible mount operation modes. This message is used by obsolete/deprecated gimbal messages."]
pub enum MavMountMode {
#[doc = "Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization"]
MAV_MOUNT_MODE_RETRACT = 0,
#[doc = "Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory."]
MAV_MOUNT_MODE_NEUTRAL = 1,
#[doc = "Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization"]
MAV_MOUNT_MODE_MAVLINK_TARGETING = 2,
#[doc = "Load neutral position and start RC Roll,Pitch,Yaw control with stabilization"]
MAV_MOUNT_MODE_RC_TARGETING = 3,
#[doc = "Load neutral position and start to point to Lat,Lon,Alt"]
MAV_MOUNT_MODE_GPS_POINT = 4,
#[doc = "Gimbal tracks system with specified system ID"]
MAV_MOUNT_MODE_SYSID_TARGET = 5,
#[doc = "Gimbal tracks home position"]
MAV_MOUNT_MODE_HOME_LOCATION = 6,
}
impl Default for MavMountMode {
fn default() -> Self {
Self::MAV_MOUNT_MODE_RETRACT
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Actions being taken to mitigate/prevent fence breach"]
pub enum FenceMitigate {
#[doc = "Unknown"]
FENCE_MITIGATE_UNKNOWN = 0,
#[doc = "No actions being taken"]
FENCE_MITIGATE_NONE = 1,
#[doc = "Velocity limiting active to prevent breach"]
FENCE_MITIGATE_VEL_LIMIT = 2,
}
impl Default for FenceMitigate {
fn default() -> Self {
Self::FENCE_MITIGATE_UNKNOWN
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum AccelcalVehiclePos {
ACCELCAL_VEHICLE_POS_LEVEL = 1,
ACCELCAL_VEHICLE_POS_LEFT = 2,
ACCELCAL_VEHICLE_POS_RIGHT = 3,
ACCELCAL_VEHICLE_POS_NOSEDOWN = 4,
ACCELCAL_VEHICLE_POS_NOSEUP = 5,
ACCELCAL_VEHICLE_POS_BACK = 6,
ACCELCAL_VEHICLE_POS_SUCCESS = 16777215,
ACCELCAL_VEHICLE_POS_FAILED = 16777216,
}
impl Default for AccelcalVehiclePos {
fn default() -> Self {
Self::ACCELCAL_VEHICLE_POS_LEVEL
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum GimbalAxisCalibrationStatus {
#[doc = "Axis calibration is in progress."]
GIMBAL_AXIS_CALIBRATION_STATUS_IN_PROGRESS = 0,
#[doc = "Axis calibration succeeded."]
GIMBAL_AXIS_CALIBRATION_STATUS_SUCCEEDED = 1,
#[doc = "Axis calibration failed."]
GIMBAL_AXIS_CALIBRATION_STATUS_FAILED = 2,
}
impl Default for GimbalAxisCalibrationStatus {
fn default() -> Self {
Self::GIMBAL_AXIS_CALIBRATION_STATUS_IN_PROGRESS
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum GoproVideoSettingsFlags {
#[doc = "0=NTSC, 1=PAL."]
GOPRO_VIDEO_SETTINGS_TV_MODE = 1,
}
impl Default for GoproVideoSettingsFlags {
fn default() -> Self {
Self::GOPRO_VIDEO_SETTINGS_TV_MODE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum GoproProtuneColour {
#[doc = "Auto."]
GOPRO_PROTUNE_COLOUR_STANDARD = 0,
#[doc = "Neutral."]
GOPRO_PROTUNE_COLOUR_NEUTRAL = 1,
}
impl Default for GoproProtuneColour {
fn default() -> Self {
Self::GOPRO_PROTUNE_COLOUR_STANDARD
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Enumeration of sensor orientation, according to its rotations"]
pub enum MavSensorOrientation {
#[doc = "Roll: 0, Pitch: 0, Yaw: 0"]
MAV_SENSOR_ROTATION_NONE = 0,
#[doc = "Roll: 0, Pitch: 0, Yaw: 45"]
MAV_SENSOR_ROTATION_YAW_45 = 1,
#[doc = "Roll: 0, Pitch: 0, Yaw: 90"]
MAV_SENSOR_ROTATION_YAW_90 = 2,
#[doc = "Roll: 0, Pitch: 0, Yaw: 135"]
MAV_SENSOR_ROTATION_YAW_135 = 3,
#[doc = "Roll: 0, Pitch: 0, Yaw: 180"]
MAV_SENSOR_ROTATION_YAW_180 = 4,
#[doc = "Roll: 0, Pitch: 0, Yaw: 225"]
MAV_SENSOR_ROTATION_YAW_225 = 5,
#[doc = "Roll: 0, Pitch: 0, Yaw: 270"]
MAV_SENSOR_ROTATION_YAW_270 = 6,
#[doc = "Roll: 0, Pitch: 0, Yaw: 315"]
MAV_SENSOR_ROTATION_YAW_315 = 7,
#[doc = "Roll: 180, Pitch: 0, Yaw: 0"]
MAV_SENSOR_ROTATION_ROLL_180 = 8,
#[doc = "Roll: 180, Pitch: 0, Yaw: 45"]
MAV_SENSOR_ROTATION_ROLL_180_YAW_45 = 9,
#[doc = "Roll: 180, Pitch: 0, Yaw: 90"]
MAV_SENSOR_ROTATION_ROLL_180_YAW_90 = 10,
#[doc = "Roll: 180, Pitch: 0, Yaw: 135"]
MAV_SENSOR_ROTATION_ROLL_180_YAW_135 = 11,
#[doc = "Roll: 0, Pitch: 180, Yaw: 0"]
MAV_SENSOR_ROTATION_PITCH_180 = 12,
#[doc = "Roll: 180, Pitch: 0, Yaw: 225"]
MAV_SENSOR_ROTATION_ROLL_180_YAW_225 = 13,
#[doc = "Roll: 180, Pitch: 0, Yaw: 270"]
MAV_SENSOR_ROTATION_ROLL_180_YAW_270 = 14,
#[doc = "Roll: 180, Pitch: 0, Yaw: 315"]
MAV_SENSOR_ROTATION_ROLL_180_YAW_315 = 15,
#[doc = "Roll: 90, Pitch: 0, Yaw: 0"]
MAV_SENSOR_ROTATION_ROLL_90 = 16,
#[doc = "Roll: 90, Pitch: 0, Yaw: 45"]
MAV_SENSOR_ROTATION_ROLL_90_YAW_45 = 17,
#[doc = "Roll: 90, Pitch: 0, Yaw: 90"]
MAV_SENSOR_ROTATION_ROLL_90_YAW_90 = 18,
#[doc = "Roll: 90, Pitch: 0, Yaw: 135"]
MAV_SENSOR_ROTATION_ROLL_90_YAW_135 = 19,
#[doc = "Roll: 270, Pitch: 0, Yaw: 0"]
MAV_SENSOR_ROTATION_ROLL_270 = 20,
#[doc = "Roll: 270, Pitch: 0, Yaw: 45"]
MAV_SENSOR_ROTATION_ROLL_270_YAW_45 = 21,
#[doc = "Roll: 270, Pitch: 0, Yaw: 90"]
MAV_SENSOR_ROTATION_ROLL_270_YAW_90 = 22,
#[doc = "Roll: 270, Pitch: 0, Yaw: 135"]
MAV_SENSOR_ROTATION_ROLL_270_YAW_135 = 23,
#[doc = "Roll: 0, Pitch: 90, Yaw: 0"]
MAV_SENSOR_ROTATION_PITCH_90 = 24,
#[doc = "Roll: 0, Pitch: 270, Yaw: 0"]
MAV_SENSOR_ROTATION_PITCH_270 = 25,
#[doc = "Roll: 0, Pitch: 180, Yaw: 90"]
MAV_SENSOR_ROTATION_PITCH_180_YAW_90 = 26,
#[doc = "Roll: 0, Pitch: 180, Yaw: 270"]
MAV_SENSOR_ROTATION_PITCH_180_YAW_270 = 27,
#[doc = "Roll: 90, Pitch: 90, Yaw: 0"]
MAV_SENSOR_ROTATION_ROLL_90_PITCH_90 = 28,
#[doc = "Roll: 180, Pitch: 90, Yaw: 0"]
MAV_SENSOR_ROTATION_ROLL_180_PITCH_90 = 29,
#[doc = "Roll: 270, Pitch: 90, Yaw: 0"]
MAV_SENSOR_ROTATION_ROLL_270_PITCH_90 = 30,
#[doc = "Roll: 90, Pitch: 180, Yaw: 0"]
MAV_SENSOR_ROTATION_ROLL_90_PITCH_180 = 31,
#[doc = "Roll: 270, Pitch: 180, Yaw: 0"]
MAV_SENSOR_ROTATION_ROLL_270_PITCH_180 = 32,
#[doc = "Roll: 90, Pitch: 270, Yaw: 0"]
MAV_SENSOR_ROTATION_ROLL_90_PITCH_270 = 33,
#[doc = "Roll: 180, Pitch: 270, Yaw: 0"]
MAV_SENSOR_ROTATION_ROLL_180_PITCH_270 = 34,
#[doc = "Roll: 270, Pitch: 270, Yaw: 0"]
MAV_SENSOR_ROTATION_ROLL_270_PITCH_270 = 35,
#[doc = "Roll: 90, Pitch: 180, Yaw: 90"]
MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90 = 36,
#[doc = "Roll: 90, Pitch: 0, Yaw: 270"]
MAV_SENSOR_ROTATION_ROLL_90_YAW_270 = 37,
#[doc = "Roll: 90, Pitch: 68, Yaw: 293"]
MAV_SENSOR_ROTATION_ROLL_90_PITCH_68_YAW_293 = 38,
#[doc = "Pitch: 315"]
MAV_SENSOR_ROTATION_PITCH_315 = 39,
#[doc = "Roll: 90, Pitch: 315"]
MAV_SENSOR_ROTATION_ROLL_90_PITCH_315 = 40,
#[doc = "Custom orientation"]
MAV_SENSOR_ROTATION_CUSTOM = 100,
}
impl Default for MavSensorOrientation {
fn default() -> Self {
Self::MAV_SENSOR_ROTATION_NONE
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum LimitsState {
#[doc = "Pre-initialization."]
LIMITS_INIT = 0,
#[doc = "Disabled."]
LIMITS_DISABLED = 1,
#[doc = "Checking limits."]
LIMITS_ENABLED = 2,
#[doc = "A limit has been breached."]
LIMITS_TRIGGERED = 3,
#[doc = "Taking action e.g. Return/RTL."]
LIMITS_RECOVERING = 4,
#[doc = "We're no longer in breach of a limit."]
LIMITS_RECOVERED = 5,
}
impl Default for LimitsState {
fn default() -> Self {
Self::LIMITS_INIT
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Airborne status of UAS."]
pub enum UtmFlightState {
#[doc = "The flight state can't be determined."]
UTM_FLIGHT_STATE_UNKNOWN = 1,
#[doc = "UAS on ground."]
UTM_FLIGHT_STATE_GROUND = 2,
#[doc = "UAS airborne."]
UTM_FLIGHT_STATE_AIRBORNE = 3,
#[doc = "UAS is in an emergency flight state."]
UTM_FLIGHT_STATE_EMERGENCY = 16,
#[doc = "UAS has no active controls."]
UTM_FLIGHT_STATE_NOCTRL = 32,
}
impl Default for UtmFlightState {
fn default() -> Self {
Self::UTM_FLIGHT_STATE_UNKNOWN
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
#[doc = "Actions for reading and writing plan information (mission, rally points, geofence) between persistent and volatile storage when using MAV_CMD_PREFLIGHT_STORAGE. (Commonly missions are loaded from persistent storage (flash/EEPROM) into volatile storage (RAM) on startup and written back when they are changed.)"]
pub enum PreflightStorageMissionAction {
#[doc = "Read current mission data from persistent storage"]
MISSION_READ_PERSISTENT = 0,
#[doc = "Write current mission data to persistent storage"]
MISSION_WRITE_PERSISTENT = 1,
#[doc = "Erase all mission data stored on the vehicle (both persistent and volatile storage)"]
MISSION_RESET_DEFAULT = 2,
}
impl Default for PreflightStorageMissionAction {
fn default() -> Self {
Self::MISSION_READ_PERSISTENT
}
}
#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum CanFilterOp {
CAN_FILTER_REPLACE = 0,
CAN_FILTER_ADD = 1,
CAN_FILTER_REMOVE = 2,
}
impl Default for CanFilterOp {
fn default() -> Self {
Self::CAN_FILTER_REPLACE
}
}
#[doc = "id: 38"]
#[doc = "This message is sent to the MAV to write a partial list. If start index == end index, only one item will be transmitted / updated. If the start index is NOT 0 and above the current list size, this request should be REJECTED!."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct MISSION_WRITE_PARTIAL_LIST_DATA {
#[doc = "Start index. Must be smaller / equal to the largest index of the current onboard list.."]
pub start_index: i16,
#[doc = "End index, equal or greater than start index.."]
pub end_index: i16,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "Mission type.."]
#[cfg_attr(feature = "serde", serde(default))]
pub mission_type: MavMissionType,
}
impl MISSION_WRITE_PARTIAL_LIST_DATA {
pub const ENCODED_LEN: usize = 7usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.start_index = buf.get_i16_le();
_struct.end_index = buf.get_i16_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
let tmp = buf.get_u8();
_struct.mission_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavMissionType",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_i16_le(self.start_index);
_tmp.put_i16_le(self.end_index);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.mission_type as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 50004"]
#[doc = "Start firmware update with encapsulated data.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct CUBEPILOT_FIRMWARE_UPDATE_START_DATA {
#[doc = "FW Size.."]
pub size: u32,
#[doc = "FW CRC.."]
pub crc: u32,
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Component ID.."]
pub target_component: u8,
}
impl CUBEPILOT_FIRMWARE_UPDATE_START_DATA {
pub const ENCODED_LEN: usize = 10usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.size = buf.get_u32_le();
_struct.crc = buf.get_u32_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.size);
_tmp.put_u32_le(self.crc);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 250"]
#[doc = "To debug something using a named 3D vector.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct DEBUG_VECT_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "x."]
pub x: f32,
#[doc = "y."]
pub y: f32,
#[doc = "z."]
pub z: f32,
#[doc = "Name."]
pub name: [u8; 10],
}
impl DEBUG_VECT_DATA {
pub const ENCODED_LEN: usize = 30usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.x = buf.get_f32_le();
_struct.y = buf.get_f32_le();
_struct.z = buf.get_f32_le();
for idx in 0..10usize {
let val = buf.get_u8();
_struct.name[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_f32_le(self.x);
_tmp.put_f32_le(self.y);
_tmp.put_f32_le(self.z);
for val in &self.name {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 201"]
#[doc = "Control message for rate gimbal.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct GIMBAL_CONTROL_DATA {
#[doc = "Demanded angular rate X.."]
pub demanded_rate_x: f32,
#[doc = "Demanded angular rate Y.."]
pub demanded_rate_y: f32,
#[doc = "Demanded angular rate Z.."]
pub demanded_rate_z: f32,
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Component ID.."]
pub target_component: u8,
}
impl GIMBAL_CONTROL_DATA {
pub const ENCODED_LEN: usize = 14usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.demanded_rate_x = buf.get_f32_le();
_struct.demanded_rate_y = buf.get_f32_le();
_struct.demanded_rate_z = buf.get_f32_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.demanded_rate_x);
_tmp.put_f32_le(self.demanded_rate_y);
_tmp.put_f32_le(self.demanded_rate_z);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 177"]
#[doc = "Status of compassmot calibration.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct COMPASSMOT_STATUS_DATA {
#[doc = "Current.."]
pub current: f32,
#[doc = "Motor Compensation X.."]
pub CompensationX: f32,
#[doc = "Motor Compensation Y.."]
pub CompensationY: f32,
#[doc = "Motor Compensation Z.."]
pub CompensationZ: f32,
#[doc = "Throttle.."]
pub throttle: u16,
#[doc = "Interference.."]
pub interference: u16,
}
impl COMPASSMOT_STATUS_DATA {
pub const ENCODED_LEN: usize = 20usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.current = buf.get_f32_le();
_struct.CompensationX = buf.get_f32_le();
_struct.CompensationY = buf.get_f32_le();
_struct.CompensationZ = buf.get_f32_le();
_struct.throttle = buf.get_u16_le();
_struct.interference = buf.get_u16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.current);
_tmp.put_f32_le(self.CompensationX);
_tmp.put_f32_le(self.CompensationY);
_tmp.put_f32_le(self.CompensationZ);
_tmp.put_u16_le(self.throttle);
_tmp.put_u16_le(self.interference);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 257"]
#[doc = "Report button state change.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct BUTTON_CHANGE_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "Time of last change of button state.."]
pub last_change_ms: u32,
#[doc = "Bitmap for state of buttons.."]
pub state: u8,
}
impl BUTTON_CHANGE_DATA {
pub const ENCODED_LEN: usize = 9usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.last_change_ms = buf.get_u32_le();
_struct.state = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_u32_le(self.last_change_ms);
_tmp.put_u8(self.state);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 123"]
#[doc = "Data for injecting into the onboard GPS (used for DGPS)."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct GPS_INJECT_DATA_DATA {
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "Data length."]
pub len: u8,
#[doc = "Raw data (110 is enough for 12 satellites of RTCMv2)."]
pub data: Vec<u8, 110>,
}
impl GPS_INJECT_DATA_DATA {
pub const ENCODED_LEN: usize = 113usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
_struct.len = buf.get_u8();
for _ in 0..110usize {
let val = buf.get_u8();
_struct.data.push(val).unwrap();
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.len);
for val in &self.data {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 179"]
#[doc = "Camera Event.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct CAMERA_STATUS_DATA {
#[doc = "Image timestamp (since UNIX epoch, according to camera clock).."]
pub time_usec: u64,
#[doc = "Parameter 1 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).."]
pub p1: f32,
#[doc = "Parameter 2 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).."]
pub p2: f32,
#[doc = "Parameter 3 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).."]
pub p3: f32,
#[doc = "Parameter 4 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).."]
pub p4: f32,
#[doc = "Image index.."]
pub img_idx: u16,
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Camera ID.."]
pub cam_idx: u8,
#[doc = "Event type.."]
pub event_id: CameraStatusTypes,
}
impl CAMERA_STATUS_DATA {
pub const ENCODED_LEN: usize = 29usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.p1 = buf.get_f32_le();
_struct.p2 = buf.get_f32_le();
_struct.p3 = buf.get_f32_le();
_struct.p4 = buf.get_f32_le();
_struct.img_idx = buf.get_u16_le();
_struct.target_system = buf.get_u8();
_struct.cam_idx = buf.get_u8();
let tmp = buf.get_u8();
_struct.event_id = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "CameraStatusTypes",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_f32_le(self.p1);
_tmp.put_f32_le(self.p2);
_tmp.put_f32_le(self.p3);
_tmp.put_f32_le(self.p4);
_tmp.put_u16_le(self.img_idx);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.cam_idx);
_tmp.put_u8(self.event_id as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 217"]
#[doc = "Response from a GOPRO_COMMAND get request.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct GOPRO_GET_RESPONSE_DATA {
#[doc = "Command ID.."]
pub cmd_id: GoproCommand,
#[doc = "Status.."]
pub status: GoproRequestStatus,
#[doc = "Value.."]
pub value: [u8; 4],
}
impl GOPRO_GET_RESPONSE_DATA {
pub const ENCODED_LEN: usize = 6usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
let tmp = buf.get_u8();
_struct.cmd_id = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "GoproCommand",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.status = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "GoproRequestStatus",
value: tmp as u32,
})?;
for idx in 0..4usize {
let val = buf.get_u8();
_struct.value[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.cmd_id as u8);
_tmp.put_u8(self.status as u8);
for val in &self.value {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 50001"]
#[doc = "Raw RC Data."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct CUBEPILOT_RAW_RC_DATA {}
impl CUBEPILOT_RAW_RC_DATA {
pub const ENCODED_LEN: usize = 0usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
Ok(Self::default())
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 336"]
#[doc = "Configure cellular modems. This message is re-emitted as an acknowledgement by the modem. The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct CELLULAR_CONFIG_DATA {
#[doc = "Enable/disable LTE. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response.."]
pub enable_lte: u8,
#[doc = "Enable/disable PIN on the SIM card. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response.."]
pub enable_pin: u8,
#[doc = "PIN sent to the SIM card. Blank when PIN is disabled. Empty when message is sent back as a response.."]
pub pin: [u8; 16],
#[doc = "New PIN when changing the PIN. Blank to leave it unchanged. Empty when message is sent back as a response.."]
pub new_pin: [u8; 16],
#[doc = "Name of the cellular APN. Blank to leave it unchanged. Current APN when sent back as a response.."]
pub apn: [u8; 32],
#[doc = "Required PUK code in case the user failed to authenticate 3 times with the PIN. Empty when message is sent back as a response.."]
pub puk: [u8; 16],
#[doc = "Enable/disable roaming. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response.."]
pub roaming: u8,
#[doc = "Message acceptance response (sent back to GS).."]
pub response: CellularConfigResponse,
}
impl CELLULAR_CONFIG_DATA {
pub const ENCODED_LEN: usize = 84usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.enable_lte = buf.get_u8();
_struct.enable_pin = buf.get_u8();
for idx in 0..16usize {
let val = buf.get_u8();
_struct.pin[idx] = val;
}
for idx in 0..16usize {
let val = buf.get_u8();
_struct.new_pin[idx] = val;
}
for idx in 0..32usize {
let val = buf.get_u8();
_struct.apn[idx] = val;
}
for idx in 0..16usize {
let val = buf.get_u8();
_struct.puk[idx] = val;
}
_struct.roaming = buf.get_u8();
let tmp = buf.get_u8();
_struct.response = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "CellularConfigResponse",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.enable_lte);
_tmp.put_u8(self.enable_pin);
for val in &self.pin {
_tmp.put_u8(*val);
}
for val in &self.new_pin {
_tmp.put_u8(*val);
}
for val in &self.apn {
_tmp.put_u8(*val);
}
for val in &self.puk {
_tmp.put_u8(*val);
}
_tmp.put_u8(self.roaming);
_tmp.put_u8(self.response as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 124"]
#[doc = "Second GPS data.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct GPS2_RAW_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "Latitude (WGS84)."]
pub lat: i32,
#[doc = "Longitude (WGS84)."]
pub lon: i32,
#[doc = "Altitude (MSL). Positive for up.."]
pub alt: i32,
#[doc = "Age of DGPS info."]
pub dgps_age: u32,
#[doc = "GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX."]
pub eph: u16,
#[doc = "GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX."]
pub epv: u16,
#[doc = "GPS ground speed. If unknown, set to: UINT16_MAX."]
pub vel: u16,
#[doc = "Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX."]
pub cog: u16,
#[doc = "GPS fix type.."]
pub fix_type: GpsFixType,
#[doc = "Number of satellites visible. If unknown, set to UINT8_MAX."]
pub satellites_visible: u8,
#[doc = "Number of DGPS satellites."]
pub dgps_numch: u8,
#[doc = "Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.."]
#[cfg_attr(feature = "serde", serde(default))]
pub yaw: u16,
#[doc = "Altitude (above WGS84, EGM96 ellipsoid). Positive for up.."]
#[cfg_attr(feature = "serde", serde(default))]
pub alt_ellipsoid: i32,
#[doc = "Position uncertainty.."]
#[cfg_attr(feature = "serde", serde(default))]
pub h_acc: u32,
#[doc = "Altitude uncertainty.."]
#[cfg_attr(feature = "serde", serde(default))]
pub v_acc: u32,
#[doc = "Speed uncertainty.."]
#[cfg_attr(feature = "serde", serde(default))]
pub vel_acc: u32,
#[doc = "Heading / track uncertainty."]
#[cfg_attr(feature = "serde", serde(default))]
pub hdg_acc: u32,
}
impl GPS2_RAW_DATA {
pub const ENCODED_LEN: usize = 57usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.lat = buf.get_i32_le();
_struct.lon = buf.get_i32_le();
_struct.alt = buf.get_i32_le();
_struct.dgps_age = buf.get_u32_le();
_struct.eph = buf.get_u16_le();
_struct.epv = buf.get_u16_le();
_struct.vel = buf.get_u16_le();
_struct.cog = buf.get_u16_le();
let tmp = buf.get_u8();
_struct.fix_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "GpsFixType",
value: tmp as u32,
})?;
_struct.satellites_visible = buf.get_u8();
_struct.dgps_numch = buf.get_u8();
_struct.yaw = buf.get_u16_le();
_struct.alt_ellipsoid = buf.get_i32_le();
_struct.h_acc = buf.get_u32_le();
_struct.v_acc = buf.get_u32_le();
_struct.vel_acc = buf.get_u32_le();
_struct.hdg_acc = buf.get_u32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_i32_le(self.lat);
_tmp.put_i32_le(self.lon);
_tmp.put_i32_le(self.alt);
_tmp.put_u32_le(self.dgps_age);
_tmp.put_u16_le(self.eph);
_tmp.put_u16_le(self.epv);
_tmp.put_u16_le(self.vel);
_tmp.put_u16_le(self.cog);
_tmp.put_u8(self.fix_type as u8);
_tmp.put_u8(self.satellites_visible);
_tmp.put_u8(self.dgps_numch);
_tmp.put_u16_le(self.yaw);
_tmp.put_i32_le(self.alt_ellipsoid);
_tmp.put_u32_le(self.h_acc);
_tmp.put_u32_le(self.v_acc);
_tmp.put_u32_le(self.vel_acc);
_tmp.put_u32_le(self.hdg_acc);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 230"]
#[doc = "Estimator status message including flags, innovation test ratios and estimated accuracies. The flags message is an integer bitmask containing information on which EKF outputs are valid. See the ESTIMATOR_STATUS_FLAGS enum definition for further information. The innovation test ratios show the magnitude of the sensor innovation divided by the innovation check threshold. Under normal operation the innovation test ratios should be below 0.5 with occasional values up to 1.0. Values greater than 1.0 should be rare under normal operation and indicate that a measurement has been rejected by the filter. The user should be notified if an innovation test ratio greater than 1.0 is recorded. Notifications for values in the range between 0.5 and 1.0 should be optional and controllable by the user.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct ESTIMATOR_STATUS_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "Velocity innovation test ratio."]
pub vel_ratio: f32,
#[doc = "Horizontal position innovation test ratio."]
pub pos_horiz_ratio: f32,
#[doc = "Vertical position innovation test ratio."]
pub pos_vert_ratio: f32,
#[doc = "Magnetometer innovation test ratio."]
pub mag_ratio: f32,
#[doc = "Height above terrain innovation test ratio."]
pub hagl_ratio: f32,
#[doc = "True airspeed innovation test ratio."]
pub tas_ratio: f32,
#[doc = "Horizontal position 1-STD accuracy relative to the EKF local origin."]
pub pos_horiz_accuracy: f32,
#[doc = "Vertical position 1-STD accuracy relative to the EKF local origin."]
pub pos_vert_accuracy: f32,
#[doc = "Bitmap indicating which EKF outputs are valid.."]
pub flags: EstimatorStatusFlags,
}
impl ESTIMATOR_STATUS_DATA {
pub const ENCODED_LEN: usize = 42usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.vel_ratio = buf.get_f32_le();
_struct.pos_horiz_ratio = buf.get_f32_le();
_struct.pos_vert_ratio = buf.get_f32_le();
_struct.mag_ratio = buf.get_f32_le();
_struct.hagl_ratio = buf.get_f32_le();
_struct.tas_ratio = buf.get_f32_le();
_struct.pos_horiz_accuracy = buf.get_f32_le();
_struct.pos_vert_accuracy = buf.get_f32_le();
let tmp = buf.get_u16_le();
_struct.flags = EstimatorStatusFlags::from_bits(tmp & EstimatorStatusFlags::all().bits())
.ok_or(ParserError::InvalidFlag {
flag_type: "EstimatorStatusFlags",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_f32_le(self.vel_ratio);
_tmp.put_f32_le(self.pos_horiz_ratio);
_tmp.put_f32_le(self.pos_vert_ratio);
_tmp.put_f32_le(self.mag_ratio);
_tmp.put_f32_le(self.hagl_ratio);
_tmp.put_f32_le(self.tas_ratio);
_tmp.put_f32_le(self.pos_horiz_accuracy);
_tmp.put_f32_le(self.pos_vert_accuracy);
_tmp.put_u16_le(self.flags.bits());
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 311"]
#[doc = "General information describing a particular UAVCAN node. Please refer to the definition of the UAVCAN service \"uavcan.protocol.GetNodeInfo\" for the background information. This message should be emitted by the system whenever a new node appears online, or an existing node reboots. Additionally, it can be emitted upon request from the other end of the MAVLink channel (see MAV_CMD_UAVCAN_GET_NODE_INFO). It is also not prohibited to emit this message unconditionally at a low frequency. The UAVCAN specification is available at http://uavcan.org.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct UAVCAN_NODE_INFO_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "Time since the start-up of the node.."]
pub uptime_sec: u32,
#[doc = "Version control system (VCS) revision identifier (e.g. git short commit hash). 0 if unknown.."]
pub sw_vcs_commit: u32,
#[doc = "Node name string. For example, \"sapog.px4.io\".."]
pub name: Vec<u8, 80>,
#[doc = "Hardware major version number.."]
pub hw_version_major: u8,
#[doc = "Hardware minor version number.."]
pub hw_version_minor: u8,
#[doc = "Hardware unique 128-bit ID.."]
pub hw_unique_id: [u8; 16],
#[doc = "Software major version number.."]
pub sw_version_major: u8,
#[doc = "Software minor version number.."]
pub sw_version_minor: u8,
}
impl UAVCAN_NODE_INFO_DATA {
pub const ENCODED_LEN: usize = 116usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.uptime_sec = buf.get_u32_le();
_struct.sw_vcs_commit = buf.get_u32_le();
for _ in 0..80usize {
let val = buf.get_u8();
_struct.name.push(val).unwrap();
}
_struct.hw_version_major = buf.get_u8();
_struct.hw_version_minor = buf.get_u8();
for idx in 0..16usize {
let val = buf.get_u8();
_struct.hw_unique_id[idx] = val;
}
_struct.sw_version_major = buf.get_u8();
_struct.sw_version_minor = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_u32_le(self.uptime_sec);
_tmp.put_u32_le(self.sw_vcs_commit);
for val in &self.name {
_tmp.put_u8(*val);
}
_tmp.put_u8(self.hw_version_major);
_tmp.put_u8(self.hw_version_minor);
for val in &self.hw_unique_id {
_tmp.put_u8(*val);
}
_tmp.put_u8(self.sw_version_major);
_tmp.put_u8(self.sw_version_minor);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 301"]
#[doc = "The location and information of an AIS vessel."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct AIS_VESSEL_DATA {
#[doc = "Mobile Marine Service Identifier, 9 decimal digits."]
pub MMSI: u32,
#[doc = "Latitude."]
pub lat: i32,
#[doc = "Longitude."]
pub lon: i32,
#[doc = "Course over ground."]
pub COG: u16,
#[doc = "True heading."]
pub heading: u16,
#[doc = "Speed over ground."]
pub velocity: u16,
#[doc = "Distance from lat/lon location to bow."]
pub dimension_bow: u16,
#[doc = "Distance from lat/lon location to stern."]
pub dimension_stern: u16,
#[doc = "Time since last communication in seconds."]
pub tslc: u16,
#[doc = "Bitmask to indicate various statuses including valid data fields."]
pub flags: AisFlags,
#[doc = "Turn rate."]
pub turn_rate: i8,
#[doc = "Navigational status."]
pub navigational_status: AisNavStatus,
#[doc = "Type of vessels."]
pub mavtype: AisType,
#[doc = "Distance from lat/lon location to port side."]
pub dimension_port: u8,
#[doc = "Distance from lat/lon location to starboard side."]
pub dimension_starboard: u8,
#[doc = "The vessel callsign."]
pub callsign: [u8; 7],
#[doc = "The vessel name."]
pub name: [u8; 20],
}
impl AIS_VESSEL_DATA {
pub const ENCODED_LEN: usize = 58usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.MMSI = buf.get_u32_le();
_struct.lat = buf.get_i32_le();
_struct.lon = buf.get_i32_le();
_struct.COG = buf.get_u16_le();
_struct.heading = buf.get_u16_le();
_struct.velocity = buf.get_u16_le();
_struct.dimension_bow = buf.get_u16_le();
_struct.dimension_stern = buf.get_u16_le();
_struct.tslc = buf.get_u16_le();
let tmp = buf.get_u16_le();
_struct.flags =
AisFlags::from_bits(tmp & AisFlags::all().bits()).ok_or(ParserError::InvalidFlag {
flag_type: "AisFlags",
value: tmp as u32,
})?;
_struct.turn_rate = buf.get_i8();
let tmp = buf.get_u8();
_struct.navigational_status =
FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "AisNavStatus",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.mavtype = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "AisType",
value: tmp as u32,
})?;
_struct.dimension_port = buf.get_u8();
_struct.dimension_starboard = buf.get_u8();
for idx in 0..7usize {
let val = buf.get_u8();
_struct.callsign[idx] = val;
}
for idx in 0..20usize {
let val = buf.get_u8();
_struct.name[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.MMSI);
_tmp.put_i32_le(self.lat);
_tmp.put_i32_le(self.lon);
_tmp.put_u16_le(self.COG);
_tmp.put_u16_le(self.heading);
_tmp.put_u16_le(self.velocity);
_tmp.put_u16_le(self.dimension_bow);
_tmp.put_u16_le(self.dimension_stern);
_tmp.put_u16_le(self.tslc);
_tmp.put_u16_le(self.flags.bits());
_tmp.put_i8(self.turn_rate);
_tmp.put_u8(self.navigational_status as u8);
_tmp.put_u8(self.mavtype as u8);
_tmp.put_u8(self.dimension_port);
_tmp.put_u8(self.dimension_starboard);
for val in &self.callsign {
_tmp.put_u8(*val);
}
for val in &self.name {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 42001"]
#[doc = "Kinematic multi bands (track) output from Daidalus."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct ICAROUS_KINEMATIC_BANDS_DATA {
#[doc = "min angle (degrees)."]
pub min1: f32,
#[doc = "max angle (degrees)."]
pub max1: f32,
#[doc = "min angle (degrees)."]
pub min2: f32,
#[doc = "max angle (degrees)."]
pub max2: f32,
#[doc = "min angle (degrees)."]
pub min3: f32,
#[doc = "max angle (degrees)."]
pub max3: f32,
#[doc = "min angle (degrees)."]
pub min4: f32,
#[doc = "max angle (degrees)."]
pub max4: f32,
#[doc = "min angle (degrees)."]
pub min5: f32,
#[doc = "max angle (degrees)."]
pub max5: f32,
#[doc = "Number of track bands."]
pub numBands: i8,
#[doc = "See the TRACK_BAND_TYPES enum.."]
pub type1: IcarousTrackBandTypes,
#[doc = "See the TRACK_BAND_TYPES enum.."]
pub type2: IcarousTrackBandTypes,
#[doc = "See the TRACK_BAND_TYPES enum.."]
pub type3: IcarousTrackBandTypes,
#[doc = "See the TRACK_BAND_TYPES enum.."]
pub type4: IcarousTrackBandTypes,
#[doc = "See the TRACK_BAND_TYPES enum.."]
pub type5: IcarousTrackBandTypes,
}
impl ICAROUS_KINEMATIC_BANDS_DATA {
pub const ENCODED_LEN: usize = 46usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.min1 = buf.get_f32_le();
_struct.max1 = buf.get_f32_le();
_struct.min2 = buf.get_f32_le();
_struct.max2 = buf.get_f32_le();
_struct.min3 = buf.get_f32_le();
_struct.max3 = buf.get_f32_le();
_struct.min4 = buf.get_f32_le();
_struct.max4 = buf.get_f32_le();
_struct.min5 = buf.get_f32_le();
_struct.max5 = buf.get_f32_le();
_struct.numBands = buf.get_i8();
let tmp = buf.get_u8();
_struct.type1 = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "IcarousTrackBandTypes",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.type2 = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "IcarousTrackBandTypes",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.type3 = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "IcarousTrackBandTypes",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.type4 = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "IcarousTrackBandTypes",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.type5 = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "IcarousTrackBandTypes",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.min1);
_tmp.put_f32_le(self.max1);
_tmp.put_f32_le(self.min2);
_tmp.put_f32_le(self.max2);
_tmp.put_f32_le(self.min3);
_tmp.put_f32_le(self.max3);
_tmp.put_f32_le(self.min4);
_tmp.put_f32_le(self.max4);
_tmp.put_f32_le(self.min5);
_tmp.put_f32_le(self.max5);
_tmp.put_i8(self.numBands);
_tmp.put_u8(self.type1 as u8);
_tmp.put_u8(self.type2 as u8);
_tmp.put_u8(self.type3 as u8);
_tmp.put_u8(self.type4 as u8);
_tmp.put_u8(self.type5 as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 225"]
#[doc = "EFI status output."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct EFI_STATUS_DATA {
#[doc = "ECU index."]
pub ecu_index: f32,
#[doc = "RPM."]
pub rpm: f32,
#[doc = "Fuel consumed."]
pub fuel_consumed: f32,
#[doc = "Fuel flow rate."]
pub fuel_flow: f32,
#[doc = "Engine load."]
pub engine_load: f32,
#[doc = "Throttle position."]
pub throttle_position: f32,
#[doc = "Spark dwell time."]
pub spark_dwell_time: f32,
#[doc = "Barometric pressure."]
pub barometric_pressure: f32,
#[doc = "Intake manifold pressure(."]
pub intake_manifold_pressure: f32,
#[doc = "Intake manifold temperature."]
pub intake_manifold_temperature: f32,
#[doc = "Cylinder head temperature."]
pub cylinder_head_temperature: f32,
#[doc = "Ignition timing (Crank angle degrees)."]
pub ignition_timing: f32,
#[doc = "Injection time."]
pub injection_time: f32,
#[doc = "Exhaust gas temperature."]
pub exhaust_gas_temperature: f32,
#[doc = "Output throttle."]
pub throttle_out: f32,
#[doc = "Pressure/temperature compensation."]
pub pt_compensation: f32,
#[doc = "EFI health status."]
pub health: u8,
#[doc = "Supply voltage to EFI sparking system. Zero in this value means \"unknown\", so if the supply voltage really is zero volts use 0.0001 instead.."]
#[cfg_attr(feature = "serde", serde(default))]
pub ignition_voltage: f32,
#[doc = "Fuel pressure. Zero in this value means \"unknown\", so if the fuel pressure really is zero kPa use 0.0001 instead.."]
#[cfg_attr(feature = "serde", serde(default))]
pub fuel_pressure: f32,
}
impl EFI_STATUS_DATA {
pub const ENCODED_LEN: usize = 73usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.ecu_index = buf.get_f32_le();
_struct.rpm = buf.get_f32_le();
_struct.fuel_consumed = buf.get_f32_le();
_struct.fuel_flow = buf.get_f32_le();
_struct.engine_load = buf.get_f32_le();
_struct.throttle_position = buf.get_f32_le();
_struct.spark_dwell_time = buf.get_f32_le();
_struct.barometric_pressure = buf.get_f32_le();
_struct.intake_manifold_pressure = buf.get_f32_le();
_struct.intake_manifold_temperature = buf.get_f32_le();
_struct.cylinder_head_temperature = buf.get_f32_le();
_struct.ignition_timing = buf.get_f32_le();
_struct.injection_time = buf.get_f32_le();
_struct.exhaust_gas_temperature = buf.get_f32_le();
_struct.throttle_out = buf.get_f32_le();
_struct.pt_compensation = buf.get_f32_le();
_struct.health = buf.get_u8();
_struct.ignition_voltage = buf.get_f32_le();
_struct.fuel_pressure = buf.get_f32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.ecu_index);
_tmp.put_f32_le(self.rpm);
_tmp.put_f32_le(self.fuel_consumed);
_tmp.put_f32_le(self.fuel_flow);
_tmp.put_f32_le(self.engine_load);
_tmp.put_f32_le(self.throttle_position);
_tmp.put_f32_le(self.spark_dwell_time);
_tmp.put_f32_le(self.barometric_pressure);
_tmp.put_f32_le(self.intake_manifold_pressure);
_tmp.put_f32_le(self.intake_manifold_temperature);
_tmp.put_f32_le(self.cylinder_head_temperature);
_tmp.put_f32_le(self.ignition_timing);
_tmp.put_f32_le(self.injection_time);
_tmp.put_f32_le(self.exhaust_gas_temperature);
_tmp.put_f32_le(self.throttle_out);
_tmp.put_f32_le(self.pt_compensation);
_tmp.put_u8(self.health);
_tmp.put_f32_le(self.ignition_voltage);
_tmp.put_f32_le(self.fuel_pressure);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 388"]
#[doc = "Modify the filter of what CAN messages to forward over the mavlink. This can be used to make CAN forwarding work well on low bandwidth links. The filtering is applied on bits 8 to 24 of the CAN id (2nd and 3rd bytes) which corresponds to the DroneCAN message ID for DroneCAN. Filters with more than 16 IDs can be constructed by sending multiple CAN_FILTER_MODIFY messages.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct CAN_FILTER_MODIFY_DATA {
#[doc = "filter IDs, length num_ids."]
pub ids: [u16; 16],
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Component ID.."]
pub target_component: u8,
#[doc = "bus number."]
pub bus: u8,
#[doc = "what operation to perform on the filter list. See CAN_FILTER_OP enum.."]
pub operation: CanFilterOp,
#[doc = "number of IDs in filter list."]
pub num_ids: u8,
}
impl CAN_FILTER_MODIFY_DATA {
pub const ENCODED_LEN: usize = 37usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
for idx in 0..16usize {
let val = buf.get_u16_le();
_struct.ids[idx] = val;
}
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
_struct.bus = buf.get_u8();
let tmp = buf.get_u8();
_struct.operation = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "CanFilterOp",
value: tmp as u32,
})?;
_struct.num_ids = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
for val in &self.ids {
_tmp.put_u16_le(*val);
}
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.bus);
_tmp.put_u8(self.operation as u8);
_tmp.put_u8(self.num_ids);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 50005"]
#[doc = "offset response to encapsulated data.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct CUBEPILOT_FIRMWARE_UPDATE_RESP_DATA {
#[doc = "FW Offset.."]
pub offset: u32,
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Component ID.."]
pub target_component: u8,
}
impl CUBEPILOT_FIRMWARE_UPDATE_RESP_DATA {
pub const ENCODED_LEN: usize = 6usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.offset = buf.get_u32_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.offset);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 350"]
#[doc = "Large debug/prototyping array. The message uses the maximum available payload for data. The array_id and name fields are used to discriminate between messages in code and in user interfaces (respectively). Do not use in production code.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct DEBUG_FLOAT_ARRAY_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "Unique ID used to discriminate between arrays."]
pub array_id: u16,
#[doc = "Name, for human-friendly display in a Ground Control Station."]
pub name: [u8; 10],
#[doc = "data."]
#[cfg_attr(feature = "serde", serde(default))]
pub data: Vec<f32, 58>,
}
impl DEBUG_FLOAT_ARRAY_DATA {
pub const ENCODED_LEN: usize = 252usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.array_id = buf.get_u16_le();
for idx in 0..10usize {
let val = buf.get_u8();
_struct.name[idx] = val;
}
for _ in 0..58usize {
let val = buf.get_f32_le();
_struct.data.push(val).unwrap();
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_u16_le(self.array_id);
for val in &self.name {
_tmp.put_u8(*val);
}
for val in &self.data {
_tmp.put_f32_le(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 299"]
#[doc = "Configure WiFi AP SSID, password, and mode. This message is re-emitted as an acknowledgement by the AP. The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct WIFI_CONFIG_AP_DATA {
#[doc = "Name of Wi-Fi network (SSID). Blank to leave it unchanged when setting. Current SSID when sent back as a response.."]
pub ssid: [u8; 32],
#[doc = "Password. Blank for an open AP. MD5 hash when message is sent back as a response.."]
pub password: Vec<u8, 64>,
#[doc = "WiFi Mode.."]
#[cfg_attr(feature = "serde", serde(default))]
pub mode: WifiConfigApMode,
#[doc = "Message acceptance response (sent back to GS).."]
#[cfg_attr(feature = "serde", serde(default))]
pub response: WifiConfigApResponse,
}
impl WIFI_CONFIG_AP_DATA {
pub const ENCODED_LEN: usize = 98usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
for idx in 0..32usize {
let val = buf.get_u8();
_struct.ssid[idx] = val;
}
for _ in 0..64usize {
let val = buf.get_u8();
_struct.password.push(val).unwrap();
}
let tmp = buf.get_i8();
_struct.mode = FromPrimitive::from_i8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "WifiConfigApMode",
value: tmp as u32,
})?;
let tmp = buf.get_i8();
_struct.response = FromPrimitive::from_i8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "WifiConfigApResponse",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
for val in &self.ssid {
_tmp.put_u8(*val);
}
for val in &self.password {
_tmp.put_u8(*val);
}
_tmp.put_i8(self.mode as i8);
_tmp.put_i8(self.response as i8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 153"]
#[doc = "Raw ADC output.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct AP_ADC_DATA {
#[doc = "ADC output 1.."]
pub adc1: u16,
#[doc = "ADC output 2.."]
pub adc2: u16,
#[doc = "ADC output 3.."]
pub adc3: u16,
#[doc = "ADC output 4.."]
pub adc4: u16,
#[doc = "ADC output 5.."]
pub adc5: u16,
#[doc = "ADC output 6.."]
pub adc6: u16,
}
impl AP_ADC_DATA {
pub const ENCODED_LEN: usize = 12usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.adc1 = buf.get_u16_le();
_struct.adc2 = buf.get_u16_le();
_struct.adc3 = buf.get_u16_le();
_struct.adc4 = buf.get_u16_le();
_struct.adc5 = buf.get_u16_le();
_struct.adc6 = buf.get_u16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.adc1);
_tmp.put_u16_le(self.adc2);
_tmp.put_u16_le(self.adc3);
_tmp.put_u16_le(self.adc4);
_tmp.put_u16_le(self.adc5);
_tmp.put_u16_le(self.adc6);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 168"]
#[doc = "Wind estimation.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct WIND_DATA {
#[doc = "Wind direction (that wind is coming from).."]
pub direction: f32,
#[doc = "Wind speed in ground plane.."]
pub speed: f32,
#[doc = "Vertical wind speed.."]
pub speed_z: f32,
}
impl WIND_DATA {
pub const ENCODED_LEN: usize = 12usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.direction = buf.get_f32_le();
_struct.speed = buf.get_f32_le();
_struct.speed_z = buf.get_f32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.direction);
_tmp.put_f32_le(self.speed);
_tmp.put_f32_le(self.speed_z);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 286"]
#[doc = "Low level message containing autopilot state relevant for a gimbal device. This message is to be sent from the autopilot to the gimbal device component. The data of this message are for the gimbal device's estimator corrections, in particular horizon compensation, as well as indicates autopilot control intentions, e.g. feed forward angular control in the z-axis.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_us: u64,
#[doc = "Quaternion components of autopilot attitude: w, x, y, z (1 0 0 0 is the null-rotation, Hamilton convention).."]
pub q: [f32; 4],
#[doc = "Estimated delay of the attitude data. 0 if unknown.."]
pub q_estimated_delay_us: u32,
#[doc = "X Speed in NED (North, East, Down). NAN if unknown.."]
pub vx: f32,
#[doc = "Y Speed in NED (North, East, Down). NAN if unknown.."]
pub vy: f32,
#[doc = "Z Speed in NED (North, East, Down). NAN if unknown.."]
pub vz: f32,
#[doc = "Estimated delay of the speed data. 0 if unknown.."]
pub v_estimated_delay_us: u32,
#[doc = "Feed forward Z component of angular velocity (positive: yawing to the right). NaN to be ignored. This is to indicate if the autopilot is actively yawing.."]
pub feed_forward_angular_velocity_z: f32,
#[doc = "Bitmap indicating which estimator outputs are valid.."]
pub estimator_status: EstimatorStatusFlags,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.."]
pub landed_state: MavLandedState,
#[doc = "Z component of angular velocity in NED (North, East, Down). NaN if unknown.."]
#[cfg_attr(feature = "serde", serde(default))]
pub angular_velocity_z: f32,
}
impl AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA {
pub const ENCODED_LEN: usize = 57usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_us = buf.get_u64_le();
for idx in 0..4usize {
let val = buf.get_f32_le();
_struct.q[idx] = val;
}
_struct.q_estimated_delay_us = buf.get_u32_le();
_struct.vx = buf.get_f32_le();
_struct.vy = buf.get_f32_le();
_struct.vz = buf.get_f32_le();
_struct.v_estimated_delay_us = buf.get_u32_le();
_struct.feed_forward_angular_velocity_z = buf.get_f32_le();
let tmp = buf.get_u16_le();
_struct.estimator_status = EstimatorStatusFlags::from_bits(
tmp & EstimatorStatusFlags::all().bits(),
)
.ok_or(ParserError::InvalidFlag {
flag_type: "EstimatorStatusFlags",
value: tmp as u32,
})?;
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
let tmp = buf.get_u8();
_struct.landed_state = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavLandedState",
value: tmp as u32,
})?;
_struct.angular_velocity_z = buf.get_f32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_boot_us);
for val in &self.q {
_tmp.put_f32_le(*val);
}
_tmp.put_u32_le(self.q_estimated_delay_us);
_tmp.put_f32_le(self.vx);
_tmp.put_f32_le(self.vy);
_tmp.put_f32_le(self.vz);
_tmp.put_u32_le(self.v_estimated_delay_us);
_tmp.put_f32_le(self.feed_forward_angular_velocity_z);
_tmp.put_u16_le(self.estimator_status.bits());
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.landed_state as u8);
_tmp.put_f32_le(self.angular_velocity_z);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 26"]
#[doc = "The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct SCALED_IMU_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "X acceleration."]
pub xacc: i16,
#[doc = "Y acceleration."]
pub yacc: i16,
#[doc = "Z acceleration."]
pub zacc: i16,
#[doc = "Angular speed around X axis."]
pub xgyro: i16,
#[doc = "Angular speed around Y axis."]
pub ygyro: i16,
#[doc = "Angular speed around Z axis."]
pub zgyro: i16,
#[doc = "X Magnetic field."]
pub xmag: i16,
#[doc = "Y Magnetic field."]
pub ymag: i16,
#[doc = "Z Magnetic field."]
pub zmag: i16,
#[doc = "Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C).."]
#[cfg_attr(feature = "serde", serde(default))]
pub temperature: i16,
}
impl SCALED_IMU_DATA {
pub const ENCODED_LEN: usize = 24usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.xacc = buf.get_i16_le();
_struct.yacc = buf.get_i16_le();
_struct.zacc = buf.get_i16_le();
_struct.xgyro = buf.get_i16_le();
_struct.ygyro = buf.get_i16_le();
_struct.zgyro = buf.get_i16_le();
_struct.xmag = buf.get_i16_le();
_struct.ymag = buf.get_i16_le();
_struct.zmag = buf.get_i16_le();
_struct.temperature = buf.get_i16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_i16_le(self.xacc);
_tmp.put_i16_le(self.yacc);
_tmp.put_i16_le(self.zacc);
_tmp.put_i16_le(self.xgyro);
_tmp.put_i16_le(self.ygyro);
_tmp.put_i16_le(self.zgyro);
_tmp.put_i16_le(self.xmag);
_tmp.put_i16_le(self.ymag);
_tmp.put_i16_le(self.zmag);
_tmp.put_i16_le(self.temperature);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 32"]
#[doc = "The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct LOCAL_POSITION_NED_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "X Position."]
pub x: f32,
#[doc = "Y Position."]
pub y: f32,
#[doc = "Z Position."]
pub z: f32,
#[doc = "X Speed."]
pub vx: f32,
#[doc = "Y Speed."]
pub vy: f32,
#[doc = "Z Speed."]
pub vz: f32,
}
impl LOCAL_POSITION_NED_DATA {
pub const ENCODED_LEN: usize = 28usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.x = buf.get_f32_le();
_struct.y = buf.get_f32_le();
_struct.z = buf.get_f32_le();
_struct.vx = buf.get_f32_le();
_struct.vy = buf.get_f32_le();
_struct.vz = buf.get_f32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_f32_le(self.x);
_tmp.put_f32_le(self.y);
_tmp.put_f32_le(self.z);
_tmp.put_f32_le(self.vx);
_tmp.put_f32_le(self.vy);
_tmp.put_f32_le(self.vz);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 219"]
#[doc = "Response from a GOPRO_COMMAND set request.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct GOPRO_SET_RESPONSE_DATA {
#[doc = "Command ID.."]
pub cmd_id: GoproCommand,
#[doc = "Status.."]
pub status: GoproRequestStatus,
}
impl GOPRO_SET_RESPONSE_DATA {
pub const ENCODED_LEN: usize = 2usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
let tmp = buf.get_u8();
_struct.cmd_id = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "GoproCommand",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.status = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "GoproRequestStatus",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.cmd_id as u8);
_tmp.put_u8(self.status as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 200"]
#[doc = "3 axis gimbal measurements.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct GIMBAL_REPORT_DATA {
#[doc = "Time since last update.."]
pub delta_time: f32,
#[doc = "Delta angle X.."]
pub delta_angle_x: f32,
#[doc = "Delta angle Y.."]
pub delta_angle_y: f32,
#[doc = "Delta angle X.."]
pub delta_angle_z: f32,
#[doc = "Delta velocity X.."]
pub delta_velocity_x: f32,
#[doc = "Delta velocity Y.."]
pub delta_velocity_y: f32,
#[doc = "Delta velocity Z.."]
pub delta_velocity_z: f32,
#[doc = "Joint ROLL.."]
pub joint_roll: f32,
#[doc = "Joint EL.."]
pub joint_el: f32,
#[doc = "Joint AZ.."]
pub joint_az: f32,
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Component ID.."]
pub target_component: u8,
}
impl GIMBAL_REPORT_DATA {
pub const ENCODED_LEN: usize = 42usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.delta_time = buf.get_f32_le();
_struct.delta_angle_x = buf.get_f32_le();
_struct.delta_angle_y = buf.get_f32_le();
_struct.delta_angle_z = buf.get_f32_le();
_struct.delta_velocity_x = buf.get_f32_le();
_struct.delta_velocity_y = buf.get_f32_le();
_struct.delta_velocity_z = buf.get_f32_le();
_struct.joint_roll = buf.get_f32_le();
_struct.joint_el = buf.get_f32_le();
_struct.joint_az = buf.get_f32_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.delta_time);
_tmp.put_f32_le(self.delta_angle_x);
_tmp.put_f32_le(self.delta_angle_y);
_tmp.put_f32_le(self.delta_angle_z);
_tmp.put_f32_le(self.delta_velocity_x);
_tmp.put_f32_le(self.delta_velocity_y);
_tmp.put_f32_le(self.delta_velocity_z);
_tmp.put_f32_le(self.joint_roll);
_tmp.put_f32_le(self.joint_el);
_tmp.put_f32_le(self.joint_az);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 11"]
#[doc = "Set the system mode, as defined by enum MAV_MODE. There is no target component id as the mode is by definition for the overall aircraft, not only for one component.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct SET_MODE_DATA {
#[doc = "The new autopilot-specific mode. This field can be ignored by an autopilot.."]
pub custom_mode: u32,
#[doc = "The system setting the mode."]
pub target_system: u8,
#[doc = "The new base mode.."]
pub base_mode: MavMode,
}
impl SET_MODE_DATA {
pub const ENCODED_LEN: usize = 6usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.custom_mode = buf.get_u32_le();
_struct.target_system = buf.get_u8();
let tmp = buf.get_u8();
_struct.base_mode = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavMode",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.custom_mode);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.base_mode as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 276"]
#[doc = "Camera tracking status, sent while in active tracking. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct CAMERA_TRACKING_GEO_STATUS_DATA {
#[doc = "Latitude of tracked object."]
pub lat: i32,
#[doc = "Longitude of tracked object."]
pub lon: i32,
#[doc = "Altitude of tracked object(AMSL, WGS84)."]
pub alt: f32,
#[doc = "Horizontal accuracy. NAN if unknown."]
pub h_acc: f32,
#[doc = "Vertical accuracy. NAN if unknown."]
pub v_acc: f32,
#[doc = "North velocity of tracked object. NAN if unknown."]
pub vel_n: f32,
#[doc = "East velocity of tracked object. NAN if unknown."]
pub vel_e: f32,
#[doc = "Down velocity of tracked object. NAN if unknown."]
pub vel_d: f32,
#[doc = "Velocity accuracy. NAN if unknown."]
pub vel_acc: f32,
#[doc = "Distance between camera and tracked object. NAN if unknown."]
pub dist: f32,
#[doc = "Heading in radians, in NED. NAN if unknown."]
pub hdg: f32,
#[doc = "Accuracy of heading, in NED. NAN if unknown."]
pub hdg_acc: f32,
#[doc = "Current tracking status."]
pub tracking_status: CameraTrackingStatusFlags,
}
impl CAMERA_TRACKING_GEO_STATUS_DATA {
pub const ENCODED_LEN: usize = 49usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.lat = buf.get_i32_le();
_struct.lon = buf.get_i32_le();
_struct.alt = buf.get_f32_le();
_struct.h_acc = buf.get_f32_le();
_struct.v_acc = buf.get_f32_le();
_struct.vel_n = buf.get_f32_le();
_struct.vel_e = buf.get_f32_le();
_struct.vel_d = buf.get_f32_le();
_struct.vel_acc = buf.get_f32_le();
_struct.dist = buf.get_f32_le();
_struct.hdg = buf.get_f32_le();
_struct.hdg_acc = buf.get_f32_le();
let tmp = buf.get_u8();
_struct.tracking_status = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "CameraTrackingStatusFlags",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_i32_le(self.lat);
_tmp.put_i32_le(self.lon);
_tmp.put_f32_le(self.alt);
_tmp.put_f32_le(self.h_acc);
_tmp.put_f32_le(self.v_acc);
_tmp.put_f32_le(self.vel_n);
_tmp.put_f32_le(self.vel_e);
_tmp.put_f32_le(self.vel_d);
_tmp.put_f32_le(self.vel_acc);
_tmp.put_f32_le(self.dist);
_tmp.put_f32_le(self.hdg);
_tmp.put_f32_le(self.hdg_acc);
_tmp.put_u8(self.tracking_status as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 324"]
#[doc = "Response from a PARAM_EXT_SET message.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PARAM_EXT_ACK_DATA {
#[doc = "Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string."]
pub param_id: [u8; 16],
#[doc = "Parameter value (new value if PARAM_ACK_ACCEPTED, current value otherwise)."]
pub param_value: Vec<u8, 128>,
#[doc = "Parameter type.."]
pub param_type: MavParamExtType,
#[doc = "Result code.."]
pub param_result: ParamAck,
}
impl PARAM_EXT_ACK_DATA {
pub const ENCODED_LEN: usize = 146usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
for idx in 0..16usize {
let val = buf.get_u8();
_struct.param_id[idx] = val;
}
for _ in 0..128usize {
let val = buf.get_u8();
_struct.param_value.push(val).unwrap();
}
let tmp = buf.get_u8();
_struct.param_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavParamExtType",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.param_result = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "ParamAck",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
for val in &self.param_id {
_tmp.put_u8(*val);
}
for val in &self.param_value {
_tmp.put_u8(*val);
}
_tmp.put_u8(self.param_type as u8);
_tmp.put_u8(self.param_result as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 11003"]
#[doc = "Write registers reply.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct DEVICE_OP_WRITE_REPLY_DATA {
#[doc = "Request ID - copied from request.."]
pub request_id: u32,
#[doc = "0 for success, anything else is failure code.."]
pub result: u8,
}
impl DEVICE_OP_WRITE_REPLY_DATA {
pub const ENCODED_LEN: usize = 5usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.request_id = buf.get_u32_le();
_struct.result = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.request_id);
_tmp.put_u8(self.result);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 174"]
#[doc = "Airspeed auto-calibration.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct AIRSPEED_AUTOCAL_DATA {
#[doc = "GPS velocity north.."]
pub vx: f32,
#[doc = "GPS velocity east.."]
pub vy: f32,
#[doc = "GPS velocity down.."]
pub vz: f32,
#[doc = "Differential pressure.."]
pub diff_pressure: f32,
#[doc = "Estimated to true airspeed ratio.."]
pub EAS2TAS: f32,
#[doc = "Airspeed ratio.."]
pub ratio: f32,
#[doc = "EKF state x.."]
pub state_x: f32,
#[doc = "EKF state y.."]
pub state_y: f32,
#[doc = "EKF state z.."]
pub state_z: f32,
#[doc = "EKF Pax.."]
pub Pax: f32,
#[doc = "EKF Pby.."]
pub Pby: f32,
#[doc = "EKF Pcz.."]
pub Pcz: f32,
}
impl AIRSPEED_AUTOCAL_DATA {
pub const ENCODED_LEN: usize = 48usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.vx = buf.get_f32_le();
_struct.vy = buf.get_f32_le();
_struct.vz = buf.get_f32_le();
_struct.diff_pressure = buf.get_f32_le();
_struct.EAS2TAS = buf.get_f32_le();
_struct.ratio = buf.get_f32_le();
_struct.state_x = buf.get_f32_le();
_struct.state_y = buf.get_f32_le();
_struct.state_z = buf.get_f32_le();
_struct.Pax = buf.get_f32_le();
_struct.Pby = buf.get_f32_le();
_struct.Pcz = buf.get_f32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.vx);
_tmp.put_f32_le(self.vy);
_tmp.put_f32_le(self.vz);
_tmp.put_f32_le(self.diff_pressure);
_tmp.put_f32_le(self.EAS2TAS);
_tmp.put_f32_le(self.ratio);
_tmp.put_f32_le(self.state_x);
_tmp.put_f32_le(self.state_y);
_tmp.put_f32_le(self.state_z);
_tmp.put_f32_le(self.Pax);
_tmp.put_f32_le(self.Pby);
_tmp.put_f32_le(self.Pcz);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 375"]
#[doc = "The raw values of the actuator outputs (e.g. on Pixhawk, from MAIN, AUX ports). This message supersedes SERVO_OUTPUT_RAW.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct ACTUATOR_OUTPUT_STATUS_DATA {
#[doc = "Timestamp (since system boot).."]
pub time_usec: u64,
#[doc = "Active outputs."]
pub active: u32,
#[doc = "Servo / motor output array values. Zero values indicate unused channels.."]
pub actuator: [f32; 32],
}
impl ACTUATOR_OUTPUT_STATUS_DATA {
pub const ENCODED_LEN: usize = 140usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.active = buf.get_u32_le();
for idx in 0..32usize {
let val = buf.get_f32_le();
_struct.actuator[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_u32_le(self.active);
for val in &self.actuator {
_tmp.put_f32_le(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 120"]
#[doc = "Reply to LOG_REQUEST_DATA."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct LOG_DATA_DATA {
#[doc = "Offset into the log."]
pub ofs: u32,
#[doc = "Log id (from LOG_ENTRY reply)."]
pub id: u16,
#[doc = "Number of bytes (zero for end of log)."]
pub count: u8,
#[doc = "log data."]
pub data: Vec<u8, 90>,
}
impl LOG_DATA_DATA {
pub const ENCODED_LEN: usize = 97usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.ofs = buf.get_u32_le();
_struct.id = buf.get_u16_le();
_struct.count = buf.get_u8();
for _ in 0..90usize {
let val = buf.get_u8();
_struct.data.push(val).unwrap();
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.ofs);
_tmp.put_u16_le(self.id);
_tmp.put_u8(self.count);
for val in &self.data {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 89"]
#[doc = "The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages of MAV X and the global coordinate frame in NED coordinates. Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "X Position."]
pub x: f32,
#[doc = "Y Position."]
pub y: f32,
#[doc = "Z Position."]
pub z: f32,
#[doc = "Roll."]
pub roll: f32,
#[doc = "Pitch."]
pub pitch: f32,
#[doc = "Yaw."]
pub yaw: f32,
}
impl LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA {
pub const ENCODED_LEN: usize = 28usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.x = buf.get_f32_le();
_struct.y = buf.get_f32_le();
_struct.z = buf.get_f32_le();
_struct.roll = buf.get_f32_le();
_struct.pitch = buf.get_f32_le();
_struct.yaw = buf.get_f32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_f32_le(self.x);
_tmp.put_f32_le(self.y);
_tmp.put_f32_le(self.z);
_tmp.put_f32_le(self.roll);
_tmp.put_f32_le(self.pitch);
_tmp.put_f32_le(self.yaw);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 215"]
#[doc = "Heartbeat from a HeroBus attached GoPro.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct GOPRO_HEARTBEAT_DATA {
#[doc = "Status.."]
pub status: GoproHeartbeatStatus,
#[doc = "Current capture mode.."]
pub capture_mode: GoproCaptureMode,
#[doc = "Additional status bits.."]
pub flags: GoproHeartbeatFlags,
}
impl GOPRO_HEARTBEAT_DATA {
pub const ENCODED_LEN: usize = 3usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
let tmp = buf.get_u8();
_struct.status = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "GoproHeartbeatStatus",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.capture_mode = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "GoproCaptureMode",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.flags = GoproHeartbeatFlags::from_bits(tmp & GoproHeartbeatFlags::all().bits())
.ok_or(ParserError::InvalidFlag {
flag_type: "GoproHeartbeatFlags",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.status as u8);
_tmp.put_u8(self.capture_mode as u8);
_tmp.put_u8(self.flags.bits());
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 259"]
#[doc = "Information about a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct CAMERA_INFORMATION_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff)."]
pub firmware_version: u32,
#[doc = "Focal length."]
pub focal_length: f32,
#[doc = "Image sensor size horizontal."]
pub sensor_size_h: f32,
#[doc = "Image sensor size vertical."]
pub sensor_size_v: f32,
#[doc = "Bitmap of camera capability flags.."]
pub flags: CameraCapFlags,
#[doc = "Horizontal image resolution."]
pub resolution_h: u16,
#[doc = "Vertical image resolution."]
pub resolution_v: u16,
#[doc = "Camera definition version (iteration)."]
pub cam_definition_version: u16,
#[doc = "Name of the camera vendor."]
pub vendor_name: [u8; 32],
#[doc = "Name of the camera model."]
pub model_name: [u8; 32],
#[doc = "Reserved for a lens ID."]
pub lens_id: u8,
#[doc = "Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). The definition file may be xz compressed, which will be indicated by the file extension .xml.xz (a GCS that implements the protocol must support decompressing the file). The string needs to be zero terminated.."]
pub cam_definition_uri: Vec<u8, 140>,
}
impl CAMERA_INFORMATION_DATA {
pub const ENCODED_LEN: usize = 235usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.firmware_version = buf.get_u32_le();
_struct.focal_length = buf.get_f32_le();
_struct.sensor_size_h = buf.get_f32_le();
_struct.sensor_size_v = buf.get_f32_le();
let tmp = buf.get_u32_le();
_struct.flags = CameraCapFlags::from_bits(tmp & CameraCapFlags::all().bits()).ok_or(
ParserError::InvalidFlag {
flag_type: "CameraCapFlags",
value: tmp as u32,
},
)?;
_struct.resolution_h = buf.get_u16_le();
_struct.resolution_v = buf.get_u16_le();
_struct.cam_definition_version = buf.get_u16_le();
for idx in 0..32usize {
let val = buf.get_u8();
_struct.vendor_name[idx] = val;
}
for idx in 0..32usize {
let val = buf.get_u8();
_struct.model_name[idx] = val;
}
_struct.lens_id = buf.get_u8();
for _ in 0..140usize {
let val = buf.get_u8();
_struct.cam_definition_uri.push(val).unwrap();
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_u32_le(self.firmware_version);
_tmp.put_f32_le(self.focal_length);
_tmp.put_f32_le(self.sensor_size_h);
_tmp.put_f32_le(self.sensor_size_v);
_tmp.put_u32_le(self.flags.bits());
_tmp.put_u16_le(self.resolution_h);
_tmp.put_u16_le(self.resolution_v);
_tmp.put_u16_le(self.cam_definition_version);
for val in &self.vendor_name {
_tmp.put_u8(*val);
}
for val in &self.model_name {
_tmp.put_u8(*val);
}
_tmp.put_u8(self.lens_id);
for val in &self.cam_definition_uri {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 11034"]
#[doc = "Configure OSD parameter reply.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct OSD_PARAM_CONFIG_REPLY_DATA {
#[doc = "Request ID - copied from request.."]
pub request_id: u32,
#[doc = "Config error type.."]
pub result: OsdParamConfigError,
}
impl OSD_PARAM_CONFIG_REPLY_DATA {
pub const ENCODED_LEN: usize = 5usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.request_id = buf.get_u32_le();
let tmp = buf.get_u8();
_struct.result = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "OsdParamConfigError",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.request_id);
_tmp.put_u8(self.result as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 24"]
#[doc = "The global position, as returned by the Global Positioning System (GPS). This is NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION_INT for the global position estimate.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct GPS_RAW_INT_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "Latitude (WGS84, EGM96 ellipsoid)."]
pub lat: i32,
#[doc = "Longitude (WGS84, EGM96 ellipsoid)."]
pub lon: i32,
#[doc = "Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.."]
pub alt: i32,
#[doc = "GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX."]
pub eph: u16,
#[doc = "GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX."]
pub epv: u16,
#[doc = "GPS ground speed. If unknown, set to: UINT16_MAX."]
pub vel: u16,
#[doc = "Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX."]
pub cog: u16,
#[doc = "GPS fix type.."]
pub fix_type: GpsFixType,
#[doc = "Number of satellites visible. If unknown, set to UINT8_MAX."]
pub satellites_visible: u8,
#[doc = "Altitude (above WGS84, EGM96 ellipsoid). Positive for up.."]
#[cfg_attr(feature = "serde", serde(default))]
pub alt_ellipsoid: i32,
#[doc = "Position uncertainty.."]
#[cfg_attr(feature = "serde", serde(default))]
pub h_acc: u32,
#[doc = "Altitude uncertainty.."]
#[cfg_attr(feature = "serde", serde(default))]
pub v_acc: u32,
#[doc = "Speed uncertainty.."]
#[cfg_attr(feature = "serde", serde(default))]
pub vel_acc: u32,
#[doc = "Heading / track uncertainty."]
#[cfg_attr(feature = "serde", serde(default))]
pub hdg_acc: u32,
#[doc = "Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.."]
#[cfg_attr(feature = "serde", serde(default))]
pub yaw: u16,
}
impl GPS_RAW_INT_DATA {
pub const ENCODED_LEN: usize = 52usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.lat = buf.get_i32_le();
_struct.lon = buf.get_i32_le();
_struct.alt = buf.get_i32_le();
_struct.eph = buf.get_u16_le();
_struct.epv = buf.get_u16_le();
_struct.vel = buf.get_u16_le();
_struct.cog = buf.get_u16_le();
let tmp = buf.get_u8();
_struct.fix_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "GpsFixType",
value: tmp as u32,
})?;
_struct.satellites_visible = buf.get_u8();
_struct.alt_ellipsoid = buf.get_i32_le();
_struct.h_acc = buf.get_u32_le();
_struct.v_acc = buf.get_u32_le();
_struct.vel_acc = buf.get_u32_le();
_struct.hdg_acc = buf.get_u32_le();
_struct.yaw = buf.get_u16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_i32_le(self.lat);
_tmp.put_i32_le(self.lon);
_tmp.put_i32_le(self.alt);
_tmp.put_u16_le(self.eph);
_tmp.put_u16_le(self.epv);
_tmp.put_u16_le(self.vel);
_tmp.put_u16_le(self.cog);
_tmp.put_u8(self.fix_type as u8);
_tmp.put_u8(self.satellites_visible);
_tmp.put_i32_le(self.alt_ellipsoid);
_tmp.put_u32_le(self.h_acc);
_tmp.put_u32_le(self.v_acc);
_tmp.put_u32_le(self.vel_acc);
_tmp.put_u32_le(self.hdg_acc);
_tmp.put_u16_le(self.yaw);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 108"]
#[doc = "Status of simulation environment, if used."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct SIM_STATE_DATA {
#[doc = "True attitude quaternion component 1, w (1 in null-rotation)."]
pub q1: f32,
#[doc = "True attitude quaternion component 2, x (0 in null-rotation)."]
pub q2: f32,
#[doc = "True attitude quaternion component 3, y (0 in null-rotation)."]
pub q3: f32,
#[doc = "True attitude quaternion component 4, z (0 in null-rotation)."]
pub q4: f32,
#[doc = "Attitude roll expressed as Euler angles, not recommended except for human-readable outputs."]
pub roll: f32,
#[doc = "Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs."]
pub pitch: f32,
#[doc = "Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs."]
pub yaw: f32,
#[doc = "X acceleration."]
pub xacc: f32,
#[doc = "Y acceleration."]
pub yacc: f32,
#[doc = "Z acceleration."]
pub zacc: f32,
#[doc = "Angular speed around X axis."]
pub xgyro: f32,
#[doc = "Angular speed around Y axis."]
pub ygyro: f32,
#[doc = "Angular speed around Z axis."]
pub zgyro: f32,
#[doc = "Latitude (lower precision). Both this and the lat_int field should be set.."]
pub lat: f32,
#[doc = "Longitude (lower precision). Both this and the lon_int field should be set.."]
pub lon: f32,
#[doc = "Altitude."]
pub alt: f32,
#[doc = "Horizontal position standard deviation."]
pub std_dev_horz: f32,
#[doc = "Vertical position standard deviation."]
pub std_dev_vert: f32,
#[doc = "True velocity in north direction in earth-fixed NED frame."]
pub vn: f32,
#[doc = "True velocity in east direction in earth-fixed NED frame."]
pub ve: f32,
#[doc = "True velocity in down direction in earth-fixed NED frame."]
pub vd: f32,
#[doc = "Latitude (higher precision). If 0, recipients should use the lat field value (otherwise this field is preferred).."]
#[cfg_attr(feature = "serde", serde(default))]
pub lat_int: i32,
#[doc = "Longitude (higher precision). If 0, recipients should use the lon field value (otherwise this field is preferred).."]
#[cfg_attr(feature = "serde", serde(default))]
pub lon_int: i32,
}
impl SIM_STATE_DATA {
pub const ENCODED_LEN: usize = 92usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.q1 = buf.get_f32_le();
_struct.q2 = buf.get_f32_le();
_struct.q3 = buf.get_f32_le();
_struct.q4 = buf.get_f32_le();
_struct.roll = buf.get_f32_le();
_struct.pitch = buf.get_f32_le();
_struct.yaw = buf.get_f32_le();
_struct.xacc = buf.get_f32_le();
_struct.yacc = buf.get_f32_le();
_struct.zacc = buf.get_f32_le();
_struct.xgyro = buf.get_f32_le();
_struct.ygyro = buf.get_f32_le();
_struct.zgyro = buf.get_f32_le();
_struct.lat = buf.get_f32_le();
_struct.lon = buf.get_f32_le();
_struct.alt = buf.get_f32_le();
_struct.std_dev_horz = buf.get_f32_le();
_struct.std_dev_vert = buf.get_f32_le();
_struct.vn = buf.get_f32_le();
_struct.ve = buf.get_f32_le();
_struct.vd = buf.get_f32_le();
_struct.lat_int = buf.get_i32_le();
_struct.lon_int = buf.get_i32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.q1);
_tmp.put_f32_le(self.q2);
_tmp.put_f32_le(self.q3);
_tmp.put_f32_le(self.q4);
_tmp.put_f32_le(self.roll);
_tmp.put_f32_le(self.pitch);
_tmp.put_f32_le(self.yaw);
_tmp.put_f32_le(self.xacc);
_tmp.put_f32_le(self.yacc);
_tmp.put_f32_le(self.zacc);
_tmp.put_f32_le(self.xgyro);
_tmp.put_f32_le(self.ygyro);
_tmp.put_f32_le(self.zgyro);
_tmp.put_f32_le(self.lat);
_tmp.put_f32_le(self.lon);
_tmp.put_f32_le(self.alt);
_tmp.put_f32_le(self.std_dev_horz);
_tmp.put_f32_le(self.std_dev_vert);
_tmp.put_f32_le(self.vn);
_tmp.put_f32_le(self.ve);
_tmp.put_f32_le(self.vd);
_tmp.put_i32_le(self.lat_int);
_tmp.put_i32_le(self.lon_int);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 77"]
#[doc = "Report status of a command. Includes feedback whether the command was executed. The command microservice is documented at https://mavlink.io/en/services/command.html."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct COMMAND_ACK_DATA {
#[doc = "Command ID (of acknowledged command).."]
pub command: MavCmd,
#[doc = "Result of command.."]
pub result: MavResult,
#[doc = "Also used as result_param1, it can be set with an enum containing the errors reasons of why the command was denied, or the progress percentage when result is MAV_RESULT_IN_PROGRESS (UINT8_MAX if the progress is unknown).."]
#[cfg_attr(feature = "serde", serde(default))]
pub progress: u8,
#[doc = "Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied.."]
#[cfg_attr(feature = "serde", serde(default))]
pub result_param2: i32,
#[doc = "System ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.."]
#[cfg_attr(feature = "serde", serde(default))]
pub target_system: u8,
#[doc = "Component ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.."]
#[cfg_attr(feature = "serde", serde(default))]
pub target_component: u8,
}
impl COMMAND_ACK_DATA {
pub const ENCODED_LEN: usize = 10usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
let tmp = buf.get_u16_le();
_struct.command = FromPrimitive::from_u16(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavCmd",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.result = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavResult",
value: tmp as u32,
})?;
_struct.progress = buf.get_u8();
_struct.result_param2 = buf.get_i32_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.command as u16);
_tmp.put_u8(self.result as u8);
_tmp.put_u8(self.progress);
_tmp.put_i32_le(self.result_param2);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 143"]
#[doc = "Barometer readings for 3rd barometer."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct SCALED_PRESSURE3_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "Absolute pressure."]
pub press_abs: f32,
#[doc = "Differential pressure."]
pub press_diff: f32,
#[doc = "Absolute pressure temperature."]
pub temperature: i16,
#[doc = "Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC.."]
#[cfg_attr(feature = "serde", serde(default))]
pub temperature_press_diff: i16,
}
impl SCALED_PRESSURE3_DATA {
pub const ENCODED_LEN: usize = 16usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.press_abs = buf.get_f32_le();
_struct.press_diff = buf.get_f32_le();
_struct.temperature = buf.get_i16_le();
_struct.temperature_press_diff = buf.get_i16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_f32_le(self.press_abs);
_tmp.put_f32_le(self.press_diff);
_tmp.put_i16_le(self.temperature);
_tmp.put_i16_le(self.temperature_press_diff);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 12915"]
#[doc = "An OpenDroneID message pack is a container for multiple encoded OpenDroneID messages (i.e. not in the format given for the above message descriptions but after encoding into the compressed OpenDroneID byte format). Used e.g. when transmitting on Bluetooth 5.0 Long Range/Extended Advertising or on WiFi Neighbor Aware Networking or on WiFi Beacon.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct OPEN_DRONE_ID_MESSAGE_PACK_DATA {
#[doc = "System ID (0 for broadcast).."]
pub target_system: u8,
#[doc = "Component ID (0 for broadcast).."]
pub target_component: u8,
#[doc = "Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.."]
pub id_or_mac: [u8; 20],
#[doc = "This field must currently always be equal to 25 (bytes), since all encoded OpenDroneID messages are specified to have this length.."]
pub single_message_size: u8,
#[doc = "Number of encoded messages in the pack (not the number of bytes). Allowed range is 1 - 9.."]
pub msg_pack_size: u8,
#[doc = "Concatenation of encoded OpenDroneID messages. Shall be filled with nulls in the unused portion of the field.."]
pub messages: Vec<u8, 225>,
}
impl OPEN_DRONE_ID_MESSAGE_PACK_DATA {
pub const ENCODED_LEN: usize = 249usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
for idx in 0..20usize {
let val = buf.get_u8();
_struct.id_or_mac[idx] = val;
}
_struct.single_message_size = buf.get_u8();
_struct.msg_pack_size = buf.get_u8();
for _ in 0..225usize {
let val = buf.get_u8();
_struct.messages.push(val).unwrap();
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
for val in &self.id_or_mac {
_tmp.put_u8(*val);
}
_tmp.put_u8(self.single_message_size);
_tmp.put_u8(self.msg_pack_size);
for val in &self.messages {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 339"]
#[doc = "RPM sensor data message.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct RAW_RPM_DATA {
#[doc = "Indicated rate."]
pub frequency: f32,
#[doc = "Index of this RPM sensor (0-indexed)."]
pub index: u8,
}
impl RAW_RPM_DATA {
pub const ENCODED_LEN: usize = 5usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.frequency = buf.get_f32_le();
_struct.index = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.frequency);
_tmp.put_u8(self.index);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 128"]
#[doc = "RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct GPS2_RTK_DATA {
#[doc = "Time since boot of last baseline message received.."]
pub time_last_baseline_ms: u32,
#[doc = "GPS Time of Week of last baseline."]
pub tow: u32,
#[doc = "Current baseline in ECEF x or NED north component.."]
pub baseline_a_mm: i32,
#[doc = "Current baseline in ECEF y or NED east component.."]
pub baseline_b_mm: i32,
#[doc = "Current baseline in ECEF z or NED down component.."]
pub baseline_c_mm: i32,
#[doc = "Current estimate of baseline accuracy.."]
pub accuracy: u32,
#[doc = "Current number of integer ambiguity hypotheses.."]
pub iar_num_hypotheses: i32,
#[doc = "GPS Week Number of last baseline."]
pub wn: u16,
#[doc = "Identification of connected RTK receiver.."]
pub rtk_receiver_id: u8,
#[doc = "GPS-specific health report for RTK data.."]
pub rtk_health: u8,
#[doc = "Rate of baseline messages being received by GPS."]
pub rtk_rate: u8,
#[doc = "Current number of sats used for RTK calculation.."]
pub nsats: u8,
#[doc = "Coordinate system of baseline."]
pub baseline_coords_type: RtkBaselineCoordinateSystem,
}
impl GPS2_RTK_DATA {
pub const ENCODED_LEN: usize = 35usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_last_baseline_ms = buf.get_u32_le();
_struct.tow = buf.get_u32_le();
_struct.baseline_a_mm = buf.get_i32_le();
_struct.baseline_b_mm = buf.get_i32_le();
_struct.baseline_c_mm = buf.get_i32_le();
_struct.accuracy = buf.get_u32_le();
_struct.iar_num_hypotheses = buf.get_i32_le();
_struct.wn = buf.get_u16_le();
_struct.rtk_receiver_id = buf.get_u8();
_struct.rtk_health = buf.get_u8();
_struct.rtk_rate = buf.get_u8();
_struct.nsats = buf.get_u8();
let tmp = buf.get_u8();
_struct.baseline_coords_type =
FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "RtkBaselineCoordinateSystem",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_last_baseline_ms);
_tmp.put_u32_le(self.tow);
_tmp.put_i32_le(self.baseline_a_mm);
_tmp.put_i32_le(self.baseline_b_mm);
_tmp.put_i32_le(self.baseline_c_mm);
_tmp.put_u32_le(self.accuracy);
_tmp.put_i32_le(self.iar_num_hypotheses);
_tmp.put_u16_le(self.wn);
_tmp.put_u8(self.rtk_receiver_id);
_tmp.put_u8(self.rtk_health);
_tmp.put_u8(self.rtk_rate);
_tmp.put_u8(self.nsats);
_tmp.put_u8(self.baseline_coords_type as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 134"]
#[doc = "Terrain data sent from GCS. The lat/lon and grid_spacing must be the same as a lat/lon from a TERRAIN_REQUEST. See terrain protocol docs: https://mavlink.io/en/services/terrain.html."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct TERRAIN_DATA_DATA {
#[doc = "Latitude of SW corner of first grid."]
pub lat: i32,
#[doc = "Longitude of SW corner of first grid."]
pub lon: i32,
#[doc = "Grid spacing."]
pub grid_spacing: u16,
#[doc = "Terrain data MSL."]
pub data: [i16; 16],
#[doc = "bit within the terrain request mask."]
pub gridbit: u8,
}
impl TERRAIN_DATA_DATA {
pub const ENCODED_LEN: usize = 43usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.lat = buf.get_i32_le();
_struct.lon = buf.get_i32_le();
_struct.grid_spacing = buf.get_u16_le();
for idx in 0..16usize {
let val = buf.get_i16_le();
_struct.data[idx] = val;
}
_struct.gridbit = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_i32_le(self.lat);
_tmp.put_i32_le(self.lon);
_tmp.put_u16_le(self.grid_spacing);
for val in &self.data {
_tmp.put_i16_le(*val);
}
_tmp.put_u8(self.gridbit);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 41"]
#[doc = "Set the mission item with sequence number seq as the current item and emit MISSION_CURRENT (whether or not the mission number changed). If a mission is currently being executed, the system will continue to this new mission item on the shortest path, skipping any intermediate mission items. Note that mission jump repeat counters are not reset (see MAV_CMD_DO_JUMP param2). This message may trigger a mission state-machine change on some systems: for example from MISSION_STATE_NOT_STARTED or MISSION_STATE_PAUSED to MISSION_STATE_ACTIVE. If the system is in mission mode, on those systems this command might therefore start, restart or resume the mission. If the system is not in mission mode this message must not trigger a switch to mission mode.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct MISSION_SET_CURRENT_DATA {
#[doc = "Sequence."]
pub seq: u16,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
}
impl MISSION_SET_CURRENT_DATA {
pub const ENCODED_LEN: usize = 4usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.seq = buf.get_u16_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.seq);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 140"]
#[doc = "Set the vehicle attitude and body angular rates.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct ACTUATOR_CONTROL_TARGET_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.."]
pub controls: [f32; 8],
#[doc = "Actuator group. The \"_mlx\" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.."]
pub group_mlx: u8,
}
impl ACTUATOR_CONTROL_TARGET_DATA {
pub const ENCODED_LEN: usize = 41usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
for idx in 0..8usize {
let val = buf.get_f32_le();
_struct.controls[idx] = val;
}
_struct.group_mlx = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
for val in &self.controls {
_tmp.put_f32_le(*val);
}
_tmp.put_u8(self.group_mlx);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 157"]
#[doc = "Message to control a camera mount, directional antenna, etc.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct MOUNT_CONTROL_DATA {
#[doc = "Pitch (centi-degrees) or lat (degE7), depending on mount mode.."]
pub input_a: i32,
#[doc = "Roll (centi-degrees) or lon (degE7) depending on mount mode.."]
pub input_b: i32,
#[doc = "Yaw (centi-degrees) or alt (cm) depending on mount mode.."]
pub input_c: i32,
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Component ID.."]
pub target_component: u8,
#[doc = "If \"1\" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING).."]
pub save_position: u8,
}
impl MOUNT_CONTROL_DATA {
pub const ENCODED_LEN: usize = 15usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.input_a = buf.get_i32_le();
_struct.input_b = buf.get_i32_le();
_struct.input_c = buf.get_i32_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
_struct.save_position = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_i32_le(self.input_a);
_tmp.put_i32_le(self.input_b);
_tmp.put_i32_le(self.input_c);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.save_position);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 132"]
#[doc = "Distance sensor information for an onboard rangefinder.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct DISTANCE_SENSOR_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "Minimum distance the sensor can measure."]
pub min_distance: u16,
#[doc = "Maximum distance the sensor can measure."]
pub max_distance: u16,
#[doc = "Current distance reading."]
pub current_distance: u16,
#[doc = "Type of distance sensor.."]
pub mavtype: MavDistanceSensor,
#[doc = "Onboard ID of the sensor."]
pub id: u8,
#[doc = "Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270."]
pub orientation: MavSensorOrientation,
#[doc = "Measurement variance. Max standard deviation is 6cm. UINT8_MAX if unknown.."]
pub covariance: u8,
#[doc = "Horizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.."]
#[cfg_attr(feature = "serde", serde(default))]
pub horizontal_fov: f32,
#[doc = "Vertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.."]
#[cfg_attr(feature = "serde", serde(default))]
pub vertical_fov: f32,
#[doc = "Quaternion of the sensor orientation in vehicle body frame (w, x, y, z order, zero-rotation is 1, 0, 0, 0). Zero-rotation is along the vehicle body x-axis. This field is required if the orientation is set to MAV_SENSOR_ROTATION_CUSTOM. Set it to 0 if invalid.\"."]
#[cfg_attr(feature = "serde", serde(default))]
pub quaternion: [f32; 4],
#[doc = "Signal quality of the sensor. Specific to each sensor type, representing the relation of the signal strength with the target reflectivity, distance, size or aspect, but normalised as a percentage. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal.."]
#[cfg_attr(feature = "serde", serde(default))]
pub signal_quality: u8,
}
impl DISTANCE_SENSOR_DATA {
pub const ENCODED_LEN: usize = 39usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.min_distance = buf.get_u16_le();
_struct.max_distance = buf.get_u16_le();
_struct.current_distance = buf.get_u16_le();
let tmp = buf.get_u8();
_struct.mavtype = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavDistanceSensor",
value: tmp as u32,
})?;
_struct.id = buf.get_u8();
let tmp = buf.get_u8();
_struct.orientation = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavSensorOrientation",
value: tmp as u32,
})?;
_struct.covariance = buf.get_u8();
_struct.horizontal_fov = buf.get_f32_le();
_struct.vertical_fov = buf.get_f32_le();
for idx in 0..4usize {
let val = buf.get_f32_le();
_struct.quaternion[idx] = val;
}
_struct.signal_quality = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_u16_le(self.min_distance);
_tmp.put_u16_le(self.max_distance);
_tmp.put_u16_le(self.current_distance);
_tmp.put_u8(self.mavtype as u8);
_tmp.put_u8(self.id);
_tmp.put_u8(self.orientation as u8);
_tmp.put_u8(self.covariance);
_tmp.put_f32_le(self.horizontal_fov);
_tmp.put_f32_le(self.vertical_fov);
for val in &self.quaternion {
_tmp.put_f32_le(*val);
}
_tmp.put_u8(self.signal_quality);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 380"]
#[doc = "Time/duration estimates for various events and actions given the current vehicle state and position.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct TIME_ESTIMATE_TO_TARGET_DATA {
#[doc = "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.."]
pub safe_return: i32,
#[doc = "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.."]
pub land: i32,
#[doc = "Estimated time for reaching/completing the currently active mission item. -1 means no time estimate available.."]
pub mission_next_item: i32,
#[doc = "Estimated time for completing the current mission. -1 means no mission active and/or no estimate available.."]
pub mission_end: i32,
#[doc = "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.."]
pub commanded_action: i32,
}
impl TIME_ESTIMATE_TO_TARGET_DATA {
pub const ENCODED_LEN: usize = 20usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.safe_return = buf.get_i32_le();
_struct.land = buf.get_i32_le();
_struct.mission_next_item = buf.get_i32_le();
_struct.mission_end = buf.get_i32_le();
_struct.commanded_action = buf.get_i32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_i32_le(self.safe_return);
_tmp.put_i32_le(self.land);
_tmp.put_i32_le(self.mission_next_item);
_tmp.put_i32_le(self.mission_end);
_tmp.put_i32_le(self.commanded_action);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 334"]
#[doc = "Report current used cellular network status."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct CELLULAR_STATUS_DATA {
#[doc = "Mobile country code. If unknown, set to UINT16_MAX."]
pub mcc: u16,
#[doc = "Mobile network code. If unknown, set to UINT16_MAX."]
pub mnc: u16,
#[doc = "Location area code. If unknown, set to 0."]
pub lac: u16,
#[doc = "Cellular modem status."]
pub status: CellularStatusFlag,
#[doc = "Failure reason when status in in CELLULAR_STATUS_FLAG_FAILED."]
pub failure_reason: CellularNetworkFailedReason,
#[doc = "Cellular network radio type: gsm, cdma, lte...."]
pub mavtype: CellularNetworkRadioType,
#[doc = "Signal quality in percent. If unknown, set to UINT8_MAX."]
pub quality: u8,
}
impl CELLULAR_STATUS_DATA {
pub const ENCODED_LEN: usize = 10usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.mcc = buf.get_u16_le();
_struct.mnc = buf.get_u16_le();
_struct.lac = buf.get_u16_le();
let tmp = buf.get_u8();
_struct.status = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "CellularStatusFlag",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.failure_reason = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "CellularNetworkFailedReason",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.mavtype = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "CellularNetworkRadioType",
value: tmp as u32,
})?;
_struct.quality = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.mcc);
_tmp.put_u16_le(self.mnc);
_tmp.put_u16_le(self.lac);
_tmp.put_u8(self.status as u8);
_tmp.put_u8(self.failure_reason as u8);
_tmp.put_u8(self.mavtype as u8);
_tmp.put_u8(self.quality);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 285"]
#[doc = "Message reporting the status of a gimbal device. \t This message should be broadcast by a gimbal device component at a low regular rate (e.g. 5 Hz). \t For the angles encoded in the quaternion and the angular velocities holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). \t If neither of these flags are set, then (for backwards compatibility) it holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), \t else they are relative to the vehicle heading (vehicle frame). \t Other conditions of the flags are not allowed. \t The quaternion and angular velocities in the other frame can be calculated from delta_yaw and delta_yaw_velocity as \t q_earth = q_delta_yaw * q_vehicle and w_earth = w_delta_yaw_velocity + w_vehicle (if not NaN). \t If neither the GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME nor the GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME flag is set, \t then (for backwards compatibility) the data in the delta_yaw and delta_yaw_velocity fields are to be ignored. \t New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME, \t and always should set delta_yaw and delta_yaw_velocity either to the proper value or NaN.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct GIMBAL_DEVICE_ATTITUDE_STATUS_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description.."]
pub q: [f32; 4],
#[doc = "X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN if unknown.."]
pub angular_velocity_x: f32,
#[doc = "Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN if unknown.."]
pub angular_velocity_y: f32,
#[doc = "Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN if unknown.."]
pub angular_velocity_z: f32,
#[doc = "Failure flags (0 for no failure)."]
pub failure_flags: GimbalDeviceErrorFlags,
#[doc = "Current gimbal flags set.."]
pub flags: GimbalDeviceFlags,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "Yaw angle relating the quaternions in earth and body frames (see message description). NaN if unknown.."]
#[cfg_attr(feature = "serde", serde(default))]
pub delta_yaw: f32,
#[doc = "Yaw angular velocity relating the angular velocities in earth and body frames (see message description). NaN if unknown.."]
#[cfg_attr(feature = "serde", serde(default))]
pub delta_yaw_velocity: f32,
}
impl GIMBAL_DEVICE_ATTITUDE_STATUS_DATA {
pub const ENCODED_LEN: usize = 48usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
for idx in 0..4usize {
let val = buf.get_f32_le();
_struct.q[idx] = val;
}
_struct.angular_velocity_x = buf.get_f32_le();
_struct.angular_velocity_y = buf.get_f32_le();
_struct.angular_velocity_z = buf.get_f32_le();
let tmp = buf.get_u32_le();
_struct.failure_flags = GimbalDeviceErrorFlags::from_bits(
tmp & GimbalDeviceErrorFlags::all().bits(),
)
.ok_or(ParserError::InvalidFlag {
flag_type: "GimbalDeviceErrorFlags",
value: tmp as u32,
})?;
let tmp = buf.get_u16_le();
_struct.flags = GimbalDeviceFlags::from_bits(tmp & GimbalDeviceFlags::all().bits()).ok_or(
ParserError::InvalidFlag {
flag_type: "GimbalDeviceFlags",
value: tmp as u32,
},
)?;
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
_struct.delta_yaw = buf.get_f32_le();
_struct.delta_yaw_velocity = buf.get_f32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
for val in &self.q {
_tmp.put_f32_le(*val);
}
_tmp.put_f32_le(self.angular_velocity_x);
_tmp.put_f32_le(self.angular_velocity_y);
_tmp.put_f32_le(self.angular_velocity_z);
_tmp.put_u32_le(self.failure_flags.bits());
_tmp.put_u16_le(self.flags.bits());
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_f32_le(self.delta_yaw);
_tmp.put_f32_le(self.delta_yaw_velocity);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 63"]
#[doc = "The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient. NOTE: This message is intended for onboard networks / companion computers and higher-bandwidth links and optimized for accuracy and completeness. Please use the GLOBAL_POSITION_INT message for a minimal subset.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct GLOBAL_POSITION_INT_COV_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "Latitude."]
pub lat: i32,
#[doc = "Longitude."]
pub lon: i32,
#[doc = "Altitude in meters above MSL."]
pub alt: i32,
#[doc = "Altitude above ground."]
pub relative_alt: i32,
#[doc = "Ground X Speed (Latitude)."]
pub vx: f32,
#[doc = "Ground Y Speed (Longitude)."]
pub vy: f32,
#[doc = "Ground Z Speed (Altitude)."]
pub vz: f32,
#[doc = "Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array.."]
pub covariance: Vec<f32, 36>,
#[doc = "Class id of the estimator this estimate originated from.."]
pub estimator_type: MavEstimatorType,
}
impl GLOBAL_POSITION_INT_COV_DATA {
pub const ENCODED_LEN: usize = 181usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.lat = buf.get_i32_le();
_struct.lon = buf.get_i32_le();
_struct.alt = buf.get_i32_le();
_struct.relative_alt = buf.get_i32_le();
_struct.vx = buf.get_f32_le();
_struct.vy = buf.get_f32_le();
_struct.vz = buf.get_f32_le();
for _ in 0..36usize {
let val = buf.get_f32_le();
_struct.covariance.push(val).unwrap();
}
let tmp = buf.get_u8();
_struct.estimator_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavEstimatorType",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_i32_le(self.lat);
_tmp.put_i32_le(self.lon);
_tmp.put_i32_le(self.alt);
_tmp.put_i32_le(self.relative_alt);
_tmp.put_f32_le(self.vx);
_tmp.put_f32_le(self.vy);
_tmp.put_f32_le(self.vz);
for val in &self.covariance {
_tmp.put_f32_le(*val);
}
_tmp.put_u8(self.estimator_type as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 34"]
#[doc = "The scaled values of the RC channels received: (-100%) -10000, (0%) 0, (100%) 10000. Channels that are inactive should be set to UINT16_MAX.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct RC_CHANNELS_SCALED_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "RC channel 1 value scaled.."]
pub chan1_scaled: i16,
#[doc = "RC channel 2 value scaled.."]
pub chan2_scaled: i16,
#[doc = "RC channel 3 value scaled.."]
pub chan3_scaled: i16,
#[doc = "RC channel 4 value scaled.."]
pub chan4_scaled: i16,
#[doc = "RC channel 5 value scaled.."]
pub chan5_scaled: i16,
#[doc = "RC channel 6 value scaled.."]
pub chan6_scaled: i16,
#[doc = "RC channel 7 value scaled.."]
pub chan7_scaled: i16,
#[doc = "RC channel 8 value scaled.."]
pub chan8_scaled: i16,
#[doc = "Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX.."]
pub port: u8,
#[doc = "Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown.."]
pub rssi: u8,
}
impl RC_CHANNELS_SCALED_DATA {
pub const ENCODED_LEN: usize = 22usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.chan1_scaled = buf.get_i16_le();
_struct.chan2_scaled = buf.get_i16_le();
_struct.chan3_scaled = buf.get_i16_le();
_struct.chan4_scaled = buf.get_i16_le();
_struct.chan5_scaled = buf.get_i16_le();
_struct.chan6_scaled = buf.get_i16_le();
_struct.chan7_scaled = buf.get_i16_le();
_struct.chan8_scaled = buf.get_i16_le();
_struct.port = buf.get_u8();
_struct.rssi = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_i16_le(self.chan1_scaled);
_tmp.put_i16_le(self.chan2_scaled);
_tmp.put_i16_le(self.chan3_scaled);
_tmp.put_i16_le(self.chan4_scaled);
_tmp.put_i16_le(self.chan5_scaled);
_tmp.put_i16_le(self.chan6_scaled);
_tmp.put_i16_le(self.chan7_scaled);
_tmp.put_i16_le(self.chan8_scaled);
_tmp.put_u8(self.port);
_tmp.put_u8(self.rssi);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 256"]
#[doc = "Setup a MAVLink2 signing key. If called with secret_key of all zero and zero initial_timestamp will disable signing."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct SETUP_SIGNING_DATA {
#[doc = "initial timestamp."]
pub initial_timestamp: u64,
#[doc = "system id of the target."]
pub target_system: u8,
#[doc = "component ID of the target."]
pub target_component: u8,
#[doc = "signing key."]
pub secret_key: [u8; 32],
}
impl SETUP_SIGNING_DATA {
pub const ENCODED_LEN: usize = 42usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.initial_timestamp = buf.get_u64_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
for idx in 0..32usize {
let val = buf.get_u8();
_struct.secret_key[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.initial_timestamp);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
for val in &self.secret_key {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 262"]
#[doc = "Information about the status of a capture. Can be requested with a MAV_CMD_REQUEST_MESSAGE command.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct CAMERA_CAPTURE_STATUS_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "Image capture interval."]
pub image_interval: f32,
#[doc = "Elapsed time since recording started (0: Not supported/available). A GCS should compute recording time and use non-zero values of this field to correct any discrepancy.."]
pub recording_time_ms: u32,
#[doc = "Available storage capacity.."]
pub available_capacity: f32,
#[doc = "Current status of image capturing (0: idle, 1: capture in progress, 2: interval set but idle, 3: interval set and capture in progress)."]
pub image_status: u8,
#[doc = "Current status of video capturing (0: idle, 1: capture in progress)."]
pub video_status: u8,
#[doc = "Total number of images captured ('forever', or until reset using MAV_CMD_STORAGE_FORMAT).."]
#[cfg_attr(feature = "serde", serde(default))]
pub image_count: i32,
}
impl CAMERA_CAPTURE_STATUS_DATA {
pub const ENCODED_LEN: usize = 22usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.image_interval = buf.get_f32_le();
_struct.recording_time_ms = buf.get_u32_le();
_struct.available_capacity = buf.get_f32_le();
_struct.image_status = buf.get_u8();
_struct.video_status = buf.get_u8();
_struct.image_count = buf.get_i32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_f32_le(self.image_interval);
_tmp.put_u32_le(self.recording_time_ms);
_tmp.put_f32_le(self.available_capacity);
_tmp.put_u8(self.image_status);
_tmp.put_u8(self.video_status);
_tmp.put_i32_le(self.image_count);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 184"]
#[doc = "Send a block of log data to remote location.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct REMOTE_LOG_DATA_BLOCK_DATA {
#[doc = "Log data block sequence number.."]
pub seqno: MavRemoteLogDataBlockCommands,
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Component ID.."]
pub target_component: u8,
#[doc = "Log data block.."]
pub data: Vec<u8, 200>,
}
impl REMOTE_LOG_DATA_BLOCK_DATA {
pub const ENCODED_LEN: usize = 206usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
let tmp = buf.get_u32_le();
_struct.seqno = FromPrimitive::from_u32(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavRemoteLogDataBlockCommands",
value: tmp as u32,
})?;
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
for _ in 0..200usize {
let val = buf.get_u8();
_struct.data.push(val).unwrap();
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.seqno as u32);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
for val in &self.data {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 258"]
#[doc = "Control vehicle tone generation (buzzer).."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PLAY_TUNE_DATA {
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "tune in board specific format."]
pub tune: [u8; 30],
#[doc = "tune extension (appended to tune)."]
#[cfg_attr(feature = "serde", serde(default))]
pub tune2: Vec<u8, 200>,
}
impl PLAY_TUNE_DATA {
pub const ENCODED_LEN: usize = 232usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
for idx in 0..30usize {
let val = buf.get_u8();
_struct.tune[idx] = val;
}
for _ in 0..200usize {
let val = buf.get_u8();
_struct.tune2.push(val).unwrap();
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
for val in &self.tune {
_tmp.put_u8(*val);
}
for val in &self.tune2 {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 178"]
#[doc = "Status of secondary AHRS filter if available.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct AHRS2_DATA {
#[doc = "Roll angle.."]
pub roll: f32,
#[doc = "Pitch angle.."]
pub pitch: f32,
#[doc = "Yaw angle.."]
pub yaw: f32,
#[doc = "Altitude (MSL).."]
pub altitude: f32,
#[doc = "Latitude.."]
pub lat: i32,
#[doc = "Longitude.."]
pub lng: i32,
}
impl AHRS2_DATA {
pub const ENCODED_LEN: usize = 24usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.roll = buf.get_f32_le();
_struct.pitch = buf.get_f32_le();
_struct.yaw = buf.get_f32_le();
_struct.altitude = buf.get_f32_le();
_struct.lat = buf.get_i32_le();
_struct.lng = buf.get_i32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.roll);
_tmp.put_f32_le(self.pitch);
_tmp.put_f32_le(self.yaw);
_tmp.put_f32_le(self.altitude);
_tmp.put_i32_le(self.lat);
_tmp.put_i32_le(self.lng);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 115"]
#[doc = "Sent from simulation to autopilot, avoids in contrast to HIL_STATE singularities. This packet is useful for high throughput applications such as hardware in the loop simulations.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct HIL_STATE_QUATERNION_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)."]
pub attitude_quaternion: [f32; 4],
#[doc = "Body frame roll / phi angular speed."]
pub rollspeed: f32,
#[doc = "Body frame pitch / theta angular speed."]
pub pitchspeed: f32,
#[doc = "Body frame yaw / psi angular speed."]
pub yawspeed: f32,
#[doc = "Latitude."]
pub lat: i32,
#[doc = "Longitude."]
pub lon: i32,
#[doc = "Altitude."]
pub alt: i32,
#[doc = "Ground X Speed (Latitude)."]
pub vx: i16,
#[doc = "Ground Y Speed (Longitude)."]
pub vy: i16,
#[doc = "Ground Z Speed (Altitude)."]
pub vz: i16,
#[doc = "Indicated airspeed."]
pub ind_airspeed: u16,
#[doc = "True airspeed."]
pub true_airspeed: u16,
#[doc = "X acceleration."]
pub xacc: i16,
#[doc = "Y acceleration."]
pub yacc: i16,
#[doc = "Z acceleration."]
pub zacc: i16,
}
impl HIL_STATE_QUATERNION_DATA {
pub const ENCODED_LEN: usize = 64usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
for idx in 0..4usize {
let val = buf.get_f32_le();
_struct.attitude_quaternion[idx] = val;
}
_struct.rollspeed = buf.get_f32_le();
_struct.pitchspeed = buf.get_f32_le();
_struct.yawspeed = buf.get_f32_le();
_struct.lat = buf.get_i32_le();
_struct.lon = buf.get_i32_le();
_struct.alt = buf.get_i32_le();
_struct.vx = buf.get_i16_le();
_struct.vy = buf.get_i16_le();
_struct.vz = buf.get_i16_le();
_struct.ind_airspeed = buf.get_u16_le();
_struct.true_airspeed = buf.get_u16_le();
_struct.xacc = buf.get_i16_le();
_struct.yacc = buf.get_i16_le();
_struct.zacc = buf.get_i16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
for val in &self.attitude_quaternion {
_tmp.put_f32_le(*val);
}
_tmp.put_f32_le(self.rollspeed);
_tmp.put_f32_le(self.pitchspeed);
_tmp.put_f32_le(self.yawspeed);
_tmp.put_i32_le(self.lat);
_tmp.put_i32_le(self.lon);
_tmp.put_i32_le(self.alt);
_tmp.put_i16_le(self.vx);
_tmp.put_i16_le(self.vy);
_tmp.put_i16_le(self.vz);
_tmp.put_u16_le(self.ind_airspeed);
_tmp.put_u16_le(self.true_airspeed);
_tmp.put_i16_le(self.xacc);
_tmp.put_i16_le(self.yacc);
_tmp.put_i16_le(self.zacc);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 28"]
#[doc = "The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct RAW_PRESSURE_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "Absolute pressure (raw)."]
pub press_abs: i16,
#[doc = "Differential pressure 1 (raw, 0 if nonexistent)."]
pub press_diff1: i16,
#[doc = "Differential pressure 2 (raw, 0 if nonexistent)."]
pub press_diff2: i16,
#[doc = "Raw Temperature measurement (raw)."]
pub temperature: i16,
}
impl RAW_PRESSURE_DATA {
pub const ENCODED_LEN: usize = 16usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.press_abs = buf.get_i16_le();
_struct.press_diff1 = buf.get_i16_le();
_struct.press_diff2 = buf.get_i16_le();
_struct.temperature = buf.get_i16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_i16_le(self.press_abs);
_tmp.put_i16_le(self.press_diff1);
_tmp.put_i16_le(self.press_diff2);
_tmp.put_i16_le(self.temperature);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 9005"]
#[doc = "Winch status.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct WINCH_STATUS_DATA {
#[doc = "Timestamp (synced to UNIX time or since system boot).."]
pub time_usec: u64,
#[doc = "Length of line released. NaN if unknown."]
pub line_length: f32,
#[doc = "Speed line is being released or retracted. Positive values if being released, negative values if being retracted, NaN if unknown."]
pub speed: f32,
#[doc = "Tension on the line. NaN if unknown."]
pub tension: f32,
#[doc = "Voltage of the battery supplying the winch. NaN if unknown."]
pub voltage: f32,
#[doc = "Current draw from the winch. NaN if unknown."]
pub current: f32,
#[doc = "Status flags."]
pub status: MavWinchStatusFlag,
#[doc = "Temperature of the motor. INT16_MAX if unknown."]
pub temperature: i16,
}
impl WINCH_STATUS_DATA {
pub const ENCODED_LEN: usize = 34usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.line_length = buf.get_f32_le();
_struct.speed = buf.get_f32_le();
_struct.tension = buf.get_f32_le();
_struct.voltage = buf.get_f32_le();
_struct.current = buf.get_f32_le();
let tmp = buf.get_u32_le();
_struct.status = MavWinchStatusFlag::from_bits(tmp & MavWinchStatusFlag::all().bits())
.ok_or(ParserError::InvalidFlag {
flag_type: "MavWinchStatusFlag",
value: tmp as u32,
})?;
_struct.temperature = buf.get_i16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_f32_le(self.line_length);
_tmp.put_f32_le(self.speed);
_tmp.put_f32_le(self.tension);
_tmp.put_f32_le(self.voltage);
_tmp.put_f32_le(self.current);
_tmp.put_u32_le(self.status.bits());
_tmp.put_i16_le(self.temperature);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 275"]
#[doc = "Camera tracking status, sent while in active tracking. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct CAMERA_TRACKING_IMAGE_STATUS_DATA {
#[doc = "Current tracked point x value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is left, 1 is right), NAN if unknown."]
pub point_x: f32,
#[doc = "Current tracked point y value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown."]
pub point_y: f32,
#[doc = "Current tracked radius if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is image left, 1 is image right), NAN if unknown."]
pub radius: f32,
#[doc = "Current tracked rectangle top x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown."]
pub rec_top_x: f32,
#[doc = "Current tracked rectangle top y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown."]
pub rec_top_y: f32,
#[doc = "Current tracked rectangle bottom x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown."]
pub rec_bottom_x: f32,
#[doc = "Current tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown."]
pub rec_bottom_y: f32,
#[doc = "Current tracking status."]
pub tracking_status: CameraTrackingStatusFlags,
#[doc = "Current tracking mode."]
pub tracking_mode: CameraTrackingMode,
#[doc = "Defines location of target data."]
pub target_data: CameraTrackingTargetData,
}
impl CAMERA_TRACKING_IMAGE_STATUS_DATA {
pub const ENCODED_LEN: usize = 31usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.point_x = buf.get_f32_le();
_struct.point_y = buf.get_f32_le();
_struct.radius = buf.get_f32_le();
_struct.rec_top_x = buf.get_f32_le();
_struct.rec_top_y = buf.get_f32_le();
_struct.rec_bottom_x = buf.get_f32_le();
_struct.rec_bottom_y = buf.get_f32_le();
let tmp = buf.get_u8();
_struct.tracking_status = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "CameraTrackingStatusFlags",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.tracking_mode = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "CameraTrackingMode",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.target_data = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "CameraTrackingTargetData",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.point_x);
_tmp.put_f32_le(self.point_y);
_tmp.put_f32_le(self.radius);
_tmp.put_f32_le(self.rec_top_x);
_tmp.put_f32_le(self.rec_top_y);
_tmp.put_f32_le(self.rec_bottom_x);
_tmp.put_f32_le(self.rec_bottom_y);
_tmp.put_u8(self.tracking_status as u8);
_tmp.put_u8(self.tracking_mode as u8);
_tmp.put_u8(self.target_data as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 20"]
#[doc = "Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also https://mavlink.io/en/services/parameter.html for a full documentation of QGroundControl and IMU code.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PARAM_REQUEST_READ_DATA {
#[doc = "Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)."]
pub param_index: i16,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string."]
pub param_id: [u8; 16],
}
impl PARAM_REQUEST_READ_DATA {
pub const ENCODED_LEN: usize = 20usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.param_index = buf.get_i16_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
for idx in 0..16usize {
let val = buf.get_u8();
_struct.param_id[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_i16_le(self.param_index);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
for val in &self.param_id {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 44"]
#[doc = "This message is emitted as response to MISSION_REQUEST_LIST by the MAV and to initiate a write transaction. The GCS can then request the individual mission item based on the knowledge of the total number of waypoints.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct MISSION_COUNT_DATA {
#[doc = "Number of mission items in the sequence."]
pub count: u16,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "Mission type.."]
#[cfg_attr(feature = "serde", serde(default))]
pub mission_type: MavMissionType,
}
impl MISSION_COUNT_DATA {
pub const ENCODED_LEN: usize = 5usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.count = buf.get_u16_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
let tmp = buf.get_u8();
_struct.mission_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavMissionType",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.count);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.mission_type as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 226"]
#[doc = "RPM sensor output.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct RPM_DATA {
#[doc = "RPM Sensor1.."]
pub rpm1: f32,
#[doc = "RPM Sensor2.."]
pub rpm2: f32,
}
impl RPM_DATA {
pub const ENCODED_LEN: usize = 8usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.rpm1 = buf.get_f32_le();
_struct.rpm2 = buf.get_f32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.rpm1);
_tmp.put_f32_le(self.rpm2);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 11032"]
#[doc = "ESC Telemetry Data for ESCs 9 to 12, matching data sent by BLHeli ESCs.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct ESC_TELEMETRY_9_TO_12_DATA {
#[doc = "Voltage.."]
pub voltage: [u16; 4],
#[doc = "Current.."]
pub current: [u16; 4],
#[doc = "Total current.."]
pub totalcurrent: [u16; 4],
#[doc = "RPM (eRPM).."]
pub rpm: [u16; 4],
#[doc = "count of telemetry packets received (wraps at 65535).."]
pub count: [u16; 4],
#[doc = "Temperature.."]
pub temperature: [u8; 4],
}
impl ESC_TELEMETRY_9_TO_12_DATA {
pub const ENCODED_LEN: usize = 44usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
for idx in 0..4usize {
let val = buf.get_u16_le();
_struct.voltage[idx] = val;
}
for idx in 0..4usize {
let val = buf.get_u16_le();
_struct.current[idx] = val;
}
for idx in 0..4usize {
let val = buf.get_u16_le();
_struct.totalcurrent[idx] = val;
}
for idx in 0..4usize {
let val = buf.get_u16_le();
_struct.rpm[idx] = val;
}
for idx in 0..4usize {
let val = buf.get_u16_le();
_struct.count[idx] = val;
}
for idx in 0..4usize {
let val = buf.get_u8();
_struct.temperature[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
for val in &self.voltage {
_tmp.put_u16_le(*val);
}
for val in &self.current {
_tmp.put_u16_le(*val);
}
for val in &self.totalcurrent {
_tmp.put_u16_le(*val);
}
for val in &self.rpm {
_tmp.put_u16_le(*val);
}
for val in &self.count {
_tmp.put_u16_le(*val);
}
for val in &self.temperature {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 9000"]
#[doc = "Cumulative distance traveled for each reported wheel.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct WHEEL_DISTANCE_DATA {
#[doc = "Timestamp (synced to UNIX time or since system boot).."]
pub time_usec: u64,
#[doc = "Distance reported by individual wheel encoders. Forward rotations increase values, reverse rotations decrease them. Not all wheels will necessarily have wheel encoders; the mapping of encoders to wheel positions must be agreed/understood by the endpoints.."]
pub distance: [f64; 16],
#[doc = "Number of wheels reported.."]
pub count: u8,
}
impl WHEEL_DISTANCE_DATA {
pub const ENCODED_LEN: usize = 137usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
for idx in 0..16usize {
let val = buf.get_f64_le();
_struct.distance[idx] = val;
}
_struct.count = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
for val in &self.distance {
_tmp.put_f64_le(*val);
}
_tmp.put_u8(self.count);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 254"]
#[doc = "Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct DEBUG_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "DEBUG value."]
pub value: f32,
#[doc = "index of debug variable."]
pub ind: u8,
}
impl DEBUG_DATA {
pub const ENCODED_LEN: usize = 9usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.value = buf.get_f32_le();
_struct.ind = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_f32_le(self.value);
_tmp.put_u8(self.ind);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 107"]
#[doc = "The IMU readings in SI units in NED body frame."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct HIL_SENSOR_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "X acceleration."]
pub xacc: f32,
#[doc = "Y acceleration."]
pub yacc: f32,
#[doc = "Z acceleration."]
pub zacc: f32,
#[doc = "Angular speed around X axis in body frame."]
pub xgyro: f32,
#[doc = "Angular speed around Y axis in body frame."]
pub ygyro: f32,
#[doc = "Angular speed around Z axis in body frame."]
pub zgyro: f32,
#[doc = "X Magnetic field."]
pub xmag: f32,
#[doc = "Y Magnetic field."]
pub ymag: f32,
#[doc = "Z Magnetic field."]
pub zmag: f32,
#[doc = "Absolute pressure."]
pub abs_pressure: f32,
#[doc = "Differential pressure (airspeed)."]
pub diff_pressure: f32,
#[doc = "Altitude calculated from pressure."]
pub pressure_alt: f32,
#[doc = "Temperature."]
pub temperature: f32,
#[doc = "Bitmap for fields that have updated since last message."]
pub fields_updated: HilSensorUpdatedFlags,
#[doc = "Sensor ID (zero indexed). Used for multiple sensor inputs."]
#[cfg_attr(feature = "serde", serde(default))]
pub id: u8,
}
impl HIL_SENSOR_DATA {
pub const ENCODED_LEN: usize = 65usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.xacc = buf.get_f32_le();
_struct.yacc = buf.get_f32_le();
_struct.zacc = buf.get_f32_le();
_struct.xgyro = buf.get_f32_le();
_struct.ygyro = buf.get_f32_le();
_struct.zgyro = buf.get_f32_le();
_struct.xmag = buf.get_f32_le();
_struct.ymag = buf.get_f32_le();
_struct.zmag = buf.get_f32_le();
_struct.abs_pressure = buf.get_f32_le();
_struct.diff_pressure = buf.get_f32_le();
_struct.pressure_alt = buf.get_f32_le();
_struct.temperature = buf.get_f32_le();
let tmp = buf.get_u32_le();
_struct.fields_updated = HilSensorUpdatedFlags::from_bits(
tmp & HilSensorUpdatedFlags::all().bits(),
)
.ok_or(ParserError::InvalidFlag {
flag_type: "HilSensorUpdatedFlags",
value: tmp as u32,
})?;
_struct.id = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_f32_le(self.xacc);
_tmp.put_f32_le(self.yacc);
_tmp.put_f32_le(self.zacc);
_tmp.put_f32_le(self.xgyro);
_tmp.put_f32_le(self.ygyro);
_tmp.put_f32_le(self.zgyro);
_tmp.put_f32_le(self.xmag);
_tmp.put_f32_le(self.ymag);
_tmp.put_f32_le(self.zmag);
_tmp.put_f32_le(self.abs_pressure);
_tmp.put_f32_le(self.diff_pressure);
_tmp.put_f32_le(self.pressure_alt);
_tmp.put_f32_le(self.temperature);
_tmp.put_u32_le(self.fields_updated.bits());
_tmp.put_u8(self.id);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 80"]
#[doc = "Cancel a long running command. The target system should respond with a COMMAND_ACK to the original command with result=MAV_RESULT_CANCELLED if the long running process was cancelled. If it has already completed, the cancel action can be ignored. The cancel action can be retried until some sort of acknowledgement to the original command has been received. The command microservice is documented at https://mavlink.io/en/services/command.html."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct COMMAND_CANCEL_DATA {
#[doc = "Command ID (of command to cancel).."]
pub command: MavCmd,
#[doc = "System executing long running command. Should not be broadcast (0).."]
pub target_system: u8,
#[doc = "Component executing long running command.."]
pub target_component: u8,
}
impl COMMAND_CANCEL_DATA {
pub const ENCODED_LEN: usize = 4usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
let tmp = buf.get_u16_le();
_struct.command = FromPrimitive::from_u16(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavCmd",
value: tmp as u32,
})?;
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.command as u16);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 162"]
#[doc = "Status of geo-fencing. Sent in extended status stream when fencing enabled.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct FENCE_STATUS_DATA {
#[doc = "Time (since boot) of last breach.."]
pub breach_time: u32,
#[doc = "Number of fence breaches.."]
pub breach_count: u16,
#[doc = "Breach status (0 if currently inside fence, 1 if outside).."]
pub breach_status: u8,
#[doc = "Last breach type.."]
pub breach_type: FenceBreach,
#[doc = "Active action to prevent fence breach."]
#[cfg_attr(feature = "serde", serde(default))]
pub breach_mitigation: FenceMitigate,
}
impl FENCE_STATUS_DATA {
pub const ENCODED_LEN: usize = 9usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.breach_time = buf.get_u32_le();
_struct.breach_count = buf.get_u16_le();
_struct.breach_status = buf.get_u8();
let tmp = buf.get_u8();
_struct.breach_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "FenceBreach",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.breach_mitigation =
FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "FenceMitigate",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.breach_time);
_tmp.put_u16_le(self.breach_count);
_tmp.put_u8(self.breach_status);
_tmp.put_u8(self.breach_type as u8);
_tmp.put_u8(self.breach_mitigation as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 330"]
#[doc = "Obstacle distances in front of the sensor, starting from the left in increment degrees to the right."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct OBSTACLE_DISTANCE_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "Distance of obstacles around the vehicle with index 0 corresponding to north + angle_offset, unless otherwise specified in the frame. A value of 0 is valid and means that the obstacle is practically touching the sensor. A value of max_distance +1 means no obstacle is present. A value of UINT16_MAX for unknown/not used. In a array element, one unit corresponds to 1cm.."]
pub distances: Vec<u16, 72>,
#[doc = "Minimum distance the sensor can measure.."]
pub min_distance: u16,
#[doc = "Maximum distance the sensor can measure.."]
pub max_distance: u16,
#[doc = "Class id of the distance sensor type.."]
pub sensor_type: MavDistanceSensor,
#[doc = "Angular width in degrees of each array element. Increment direction is clockwise. This field is ignored if increment_f is non-zero.."]
pub increment: u8,
#[doc = "Angular width in degrees of each array element as a float. If non-zero then this value is used instead of the uint8_t increment field. Positive is clockwise direction, negative is counter-clockwise.."]
#[cfg_attr(feature = "serde", serde(default))]
pub increment_f: f32,
#[doc = "Relative angle offset of the 0-index element in the distances array. Value of 0 corresponds to forward. Positive is clockwise direction, negative is counter-clockwise.."]
#[cfg_attr(feature = "serde", serde(default))]
pub angle_offset: f32,
#[doc = "Coordinate frame of reference for the yaw rotation and offset of the sensor data. Defaults to MAV_FRAME_GLOBAL, which is north aligned. For body-mounted sensors use MAV_FRAME_BODY_FRD, which is vehicle front aligned.."]
#[cfg_attr(feature = "serde", serde(default))]
pub frame: MavFrame,
}
impl OBSTACLE_DISTANCE_DATA {
pub const ENCODED_LEN: usize = 167usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
for _ in 0..72usize {
let val = buf.get_u16_le();
_struct.distances.push(val).unwrap();
}
_struct.min_distance = buf.get_u16_le();
_struct.max_distance = buf.get_u16_le();
let tmp = buf.get_u8();
_struct.sensor_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavDistanceSensor",
value: tmp as u32,
})?;
_struct.increment = buf.get_u8();
_struct.increment_f = buf.get_f32_le();
_struct.angle_offset = buf.get_f32_le();
let tmp = buf.get_u8();
_struct.frame = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavFrame",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
for val in &self.distances {
_tmp.put_u16_le(*val);
}
_tmp.put_u16_le(self.min_distance);
_tmp.put_u16_le(self.max_distance);
_tmp.put_u8(self.sensor_type as u8);
_tmp.put_u8(self.increment);
_tmp.put_f32_le(self.increment_f);
_tmp.put_f32_le(self.angle_offset);
_tmp.put_u8(self.frame as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 152"]
#[doc = "State of autopilot RAM.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct MEMINFO_DATA {
#[doc = "Heap top.."]
pub brkval: u16,
#[doc = "Free memory.."]
pub freemem: u16,
#[doc = "Free memory (32 bit).."]
#[cfg_attr(feature = "serde", serde(default))]
pub freemem32: u32,
}
impl MEMINFO_DATA {
pub const ENCODED_LEN: usize = 8usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.brkval = buf.get_u16_le();
_struct.freemem = buf.get_u16_le();
_struct.freemem32 = buf.get_u32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.brkval);
_tmp.put_u16_le(self.freemem);
_tmp.put_u32_le(self.freemem32);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 194"]
#[doc = "PID tuning information.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PID_TUNING_DATA {
#[doc = "Desired rate.."]
pub desired: f32,
#[doc = "Achieved rate.."]
pub achieved: f32,
#[doc = "FF component.."]
pub FF: f32,
#[doc = "P component.."]
pub P: f32,
#[doc = "I component.."]
pub I: f32,
#[doc = "D component.."]
pub D: f32,
#[doc = "Axis.."]
pub axis: PidTuningAxis,
#[doc = "Slew rate.."]
#[cfg_attr(feature = "serde", serde(default))]
pub SRate: f32,
#[doc = "P/D oscillation modifier.."]
#[cfg_attr(feature = "serde", serde(default))]
pub PDmod: f32,
}
impl PID_TUNING_DATA {
pub const ENCODED_LEN: usize = 33usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.desired = buf.get_f32_le();
_struct.achieved = buf.get_f32_le();
_struct.FF = buf.get_f32_le();
_struct.P = buf.get_f32_le();
_struct.I = buf.get_f32_le();
_struct.D = buf.get_f32_le();
let tmp = buf.get_u8();
_struct.axis = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "PidTuningAxis",
value: tmp as u32,
})?;
_struct.SRate = buf.get_f32_le();
_struct.PDmod = buf.get_f32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.desired);
_tmp.put_f32_le(self.achieved);
_tmp.put_f32_le(self.FF);
_tmp.put_f32_le(self.P);
_tmp.put_f32_le(self.I);
_tmp.put_f32_le(self.D);
_tmp.put_u8(self.axis as u8);
_tmp.put_f32_le(self.SRate);
_tmp.put_f32_le(self.PDmod);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 10001"]
#[doc = "Static data to configure the ADS-B transponder (send within 10 sec of a POR and every 10 sec thereafter)."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct UAVIONIX_ADSB_OUT_CFG_DATA {
#[doc = "Vehicle address (24 bit)."]
pub ICAO: u32,
#[doc = "Aircraft stall speed in cm/s."]
pub stallSpeed: u16,
#[doc = "Vehicle identifier (8 characters, null terminated, valid characters are A-Z, 0-9, \" \" only)."]
pub callsign: [u8; 9],
#[doc = "Transmitting vehicle type. See ADSB_EMITTER_TYPE enum."]
pub emitterType: AdsbEmitterType,
#[doc = "Aircraft length and width encoding (table 2-35 of DO-282B)."]
pub aircraftSize: UavionixAdsbOutCfgAircraftSize,
#[doc = "GPS antenna lateral offset (table 2-36 of DO-282B)."]
pub gpsOffsetLat: UavionixAdsbOutCfgGpsOffsetLat,
#[doc = "GPS antenna longitudinal offset from nose [if non-zero, take position (in meters) divide by 2 and add one] (table 2-37 DO-282B)."]
pub gpsOffsetLon: UavionixAdsbOutCfgGpsOffsetLon,
#[doc = "ADS-B transponder receiver and transmit enable flags."]
pub rfSelect: UavionixAdsbOutRfSelect,
}
impl UAVIONIX_ADSB_OUT_CFG_DATA {
pub const ENCODED_LEN: usize = 20usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.ICAO = buf.get_u32_le();
_struct.stallSpeed = buf.get_u16_le();
for idx in 0..9usize {
let val = buf.get_u8();
_struct.callsign[idx] = val;
}
let tmp = buf.get_u8();
_struct.emitterType = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "AdsbEmitterType",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.aircraftSize = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "UavionixAdsbOutCfgAircraftSize",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.gpsOffsetLat = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "UavionixAdsbOutCfgGpsOffsetLat",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.gpsOffsetLon = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "UavionixAdsbOutCfgGpsOffsetLon",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.rfSelect = UavionixAdsbOutRfSelect::from_bits(
tmp & UavionixAdsbOutRfSelect::all().bits(),
)
.ok_or(ParserError::InvalidFlag {
flag_type: "UavionixAdsbOutRfSelect",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.ICAO);
_tmp.put_u16_le(self.stallSpeed);
for val in &self.callsign {
_tmp.put_u8(*val);
}
_tmp.put_u8(self.emitterType as u8);
_tmp.put_u8(self.aircraftSize as u8);
_tmp.put_u8(self.gpsOffsetLat as u8);
_tmp.put_u8(self.gpsOffsetLon as u8);
_tmp.put_u8(self.rfSelect.bits());
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 397"]
#[doc = "Component metadata message, which may be requested using MAV_CMD_REQUEST_MESSAGE. This contains the MAVLink FTP URI and CRC for the component's general metadata file. The file must be hosted on the component, and may be xz compressed. The file CRC can be used for file caching. The general metadata file can be read to get the locations of other metadata files (COMP_METADATA_TYPE) and translations, which may be hosted either on the vehicle or the internet. For more information see: https://mavlink.io/en/services/component_information.html. Note: Camera components should use CAMERA_INFORMATION instead, and autopilots may use both this message and AUTOPILOT_VERSION.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct COMPONENT_METADATA_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "CRC32 of the general metadata file.."]
pub file_crc: u32,
#[doc = "MAVLink FTP URI for the general metadata file (COMP_METADATA_TYPE_GENERAL), which may be compressed with xz. The file contains general component metadata, and may contain URI links for additional metadata (see COMP_METADATA_TYPE). The information is static from boot, and may be generated at compile time. The string needs to be zero terminated.."]
pub uri: Vec<u8, 100>,
}
impl COMPONENT_METADATA_DATA {
pub const ENCODED_LEN: usize = 108usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.file_crc = buf.get_u32_le();
for _ in 0..100usize {
let val = buf.get_u8();
_struct.uri.push(val).unwrap();
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_u32_le(self.file_crc);
for val in &self.uri {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 11036"]
#[doc = "Read configured OSD parameter reply.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct OSD_PARAM_SHOW_CONFIG_REPLY_DATA {
#[doc = "Request ID - copied from request.."]
pub request_id: u32,
#[doc = "OSD parameter minimum value.."]
pub min_value: f32,
#[doc = "OSD parameter maximum value.."]
pub max_value: f32,
#[doc = "OSD parameter increment.."]
pub increment: f32,
#[doc = "Config error type.."]
pub result: OsdParamConfigError,
#[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string."]
pub param_id: [u8; 16],
#[doc = "Config type.."]
pub config_type: OsdParamConfigType,
}
impl OSD_PARAM_SHOW_CONFIG_REPLY_DATA {
pub const ENCODED_LEN: usize = 34usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.request_id = buf.get_u32_le();
_struct.min_value = buf.get_f32_le();
_struct.max_value = buf.get_f32_le();
_struct.increment = buf.get_f32_le();
let tmp = buf.get_u8();
_struct.result = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "OsdParamConfigError",
value: tmp as u32,
})?;
for idx in 0..16usize {
let val = buf.get_u8();
_struct.param_id[idx] = val;
}
let tmp = buf.get_u8();
_struct.config_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "OsdParamConfigType",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.request_id);
_tmp.put_f32_le(self.min_value);
_tmp.put_f32_le(self.max_value);
_tmp.put_f32_le(self.increment);
_tmp.put_u8(self.result as u8);
for val in &self.param_id {
_tmp.put_u8(*val);
}
_tmp.put_u8(self.config_type as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 320"]
#[doc = "Request to read the value of a parameter with either the param_id string id or param_index. PARAM_EXT_VALUE should be emitted in response.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PARAM_EXT_REQUEST_READ_DATA {
#[doc = "Parameter index. Set to -1 to use the Parameter ID field as identifier (else param_id will be ignored)."]
pub param_index: i16,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string."]
pub param_id: [u8; 16],
}
impl PARAM_EXT_REQUEST_READ_DATA {
pub const ENCODED_LEN: usize = 20usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.param_index = buf.get_i16_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
for idx in 0..16usize {
let val = buf.get_u8();
_struct.param_id[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_i16_le(self.param_index);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
for val in &self.param_id {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 335"]
#[doc = "Status of the Iridium SBD link.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct ISBD_LINK_STATUS_DATA {
#[doc = "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.."]
pub timestamp: u64,
#[doc = "Timestamp of the last successful sbd session. The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.."]
pub last_heartbeat: u64,
#[doc = "Number of failed SBD sessions.."]
pub failed_sessions: u16,
#[doc = "Number of successful SBD sessions.."]
pub successful_sessions: u16,
#[doc = "Signal quality equal to the number of bars displayed on the ISU signal strength indicator. Range is 0 to 5, where 0 indicates no signal and 5 indicates maximum signal strength.."]
pub signal_quality: u8,
#[doc = "1: Ring call pending, 0: No call pending.."]
pub ring_pending: u8,
#[doc = "1: Transmission session pending, 0: No transmission session pending.."]
pub tx_session_pending: u8,
#[doc = "1: Receiving session pending, 0: No receiving session pending.."]
pub rx_session_pending: u8,
}
impl ISBD_LINK_STATUS_DATA {
pub const ENCODED_LEN: usize = 24usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.timestamp = buf.get_u64_le();
_struct.last_heartbeat = buf.get_u64_le();
_struct.failed_sessions = buf.get_u16_le();
_struct.successful_sessions = buf.get_u16_le();
_struct.signal_quality = buf.get_u8();
_struct.ring_pending = buf.get_u8();
_struct.tx_session_pending = buf.get_u8();
_struct.rx_session_pending = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.timestamp);
_tmp.put_u64_le(self.last_heartbeat);
_tmp.put_u16_le(self.failed_sessions);
_tmp.put_u16_le(self.successful_sessions);
_tmp.put_u8(self.signal_quality);
_tmp.put_u8(self.ring_pending);
_tmp.put_u8(self.tx_session_pending);
_tmp.put_u8(self.rx_session_pending);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 331"]
#[doc = "Odometry message to communicate odometry information with an external interface. Fits ROS REP 147 standard for aerial vehicles (http://www.ros.org/reps/rep-0147.html).."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct ODOMETRY_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "X Position."]
pub x: f32,
#[doc = "Y Position."]
pub y: f32,
#[doc = "Z Position."]
pub z: f32,
#[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)."]
pub q: [f32; 4],
#[doc = "X linear speed."]
pub vx: f32,
#[doc = "Y linear speed."]
pub vy: f32,
#[doc = "Z linear speed."]
pub vz: f32,
#[doc = "Roll angular speed."]
pub rollspeed: f32,
#[doc = "Pitch angular speed."]
pub pitchspeed: f32,
#[doc = "Yaw angular speed."]
pub yawspeed: f32,
#[doc = "Row-major representation of a 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.."]
pub pose_covariance: [f32; 21],
#[doc = "Row-major representation of a 6x6 velocity cross-covariance matrix upper right triangle (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.."]
pub velocity_covariance: [f32; 21],
#[doc = "Coordinate frame of reference for the pose data.."]
pub frame_id: MavFrame,
#[doc = "Coordinate frame of reference for the velocity in free space (twist) data.."]
pub child_frame_id: MavFrame,
#[doc = "Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.."]
#[cfg_attr(feature = "serde", serde(default))]
pub reset_counter: u8,
#[doc = "Type of estimator that is providing the odometry.."]
#[cfg_attr(feature = "serde", serde(default))]
pub estimator_type: MavEstimatorType,
#[doc = "Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality."]
#[cfg_attr(feature = "serde", serde(default))]
pub quality: i8,
}
impl ODOMETRY_DATA {
pub const ENCODED_LEN: usize = 233usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.x = buf.get_f32_le();
_struct.y = buf.get_f32_le();
_struct.z = buf.get_f32_le();
for idx in 0..4usize {
let val = buf.get_f32_le();
_struct.q[idx] = val;
}
_struct.vx = buf.get_f32_le();
_struct.vy = buf.get_f32_le();
_struct.vz = buf.get_f32_le();
_struct.rollspeed = buf.get_f32_le();
_struct.pitchspeed = buf.get_f32_le();
_struct.yawspeed = buf.get_f32_le();
for idx in 0..21usize {
let val = buf.get_f32_le();
_struct.pose_covariance[idx] = val;
}
for idx in 0..21usize {
let val = buf.get_f32_le();
_struct.velocity_covariance[idx] = val;
}
let tmp = buf.get_u8();
_struct.frame_id = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavFrame",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.child_frame_id = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavFrame",
value: tmp as u32,
})?;
_struct.reset_counter = buf.get_u8();
let tmp = buf.get_u8();
_struct.estimator_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavEstimatorType",
value: tmp as u32,
})?;
_struct.quality = buf.get_i8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_f32_le(self.x);
_tmp.put_f32_le(self.y);
_tmp.put_f32_le(self.z);
for val in &self.q {
_tmp.put_f32_le(*val);
}
_tmp.put_f32_le(self.vx);
_tmp.put_f32_le(self.vy);
_tmp.put_f32_le(self.vz);
_tmp.put_f32_le(self.rollspeed);
_tmp.put_f32_le(self.pitchspeed);
_tmp.put_f32_le(self.yawspeed);
for val in &self.pose_covariance {
_tmp.put_f32_le(*val);
}
for val in &self.velocity_covariance {
_tmp.put_f32_le(*val);
}
_tmp.put_u8(self.frame_id as u8);
_tmp.put_u8(self.child_frame_id as u8);
_tmp.put_u8(self.reset_counter);
_tmp.put_u8(self.estimator_type as u8);
_tmp.put_i8(self.quality);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 113"]
#[doc = "The global position, as returned by the Global Positioning System (GPS). This is NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION_INT for the global position estimate.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct HIL_GPS_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "Latitude (WGS84)."]
pub lat: i32,
#[doc = "Longitude (WGS84)."]
pub lon: i32,
#[doc = "Altitude (MSL). Positive for up.."]
pub alt: i32,
#[doc = "GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX."]
pub eph: u16,
#[doc = "GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX."]
pub epv: u16,
#[doc = "GPS ground speed. If unknown, set to: UINT16_MAX."]
pub vel: u16,
#[doc = "GPS velocity in north direction in earth-fixed NED frame."]
pub vn: i16,
#[doc = "GPS velocity in east direction in earth-fixed NED frame."]
pub ve: i16,
#[doc = "GPS velocity in down direction in earth-fixed NED frame."]
pub vd: i16,
#[doc = "Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX."]
pub cog: u16,
#[doc = "0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.."]
pub fix_type: u8,
#[doc = "Number of satellites visible. If unknown, set to UINT8_MAX."]
pub satellites_visible: u8,
#[doc = "GPS ID (zero indexed). Used for multiple GPS inputs."]
#[cfg_attr(feature = "serde", serde(default))]
pub id: u8,
#[doc = "Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north."]
#[cfg_attr(feature = "serde", serde(default))]
pub yaw: u16,
}
impl HIL_GPS_DATA {
pub const ENCODED_LEN: usize = 39usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.lat = buf.get_i32_le();
_struct.lon = buf.get_i32_le();
_struct.alt = buf.get_i32_le();
_struct.eph = buf.get_u16_le();
_struct.epv = buf.get_u16_le();
_struct.vel = buf.get_u16_le();
_struct.vn = buf.get_i16_le();
_struct.ve = buf.get_i16_le();
_struct.vd = buf.get_i16_le();
_struct.cog = buf.get_u16_le();
_struct.fix_type = buf.get_u8();
_struct.satellites_visible = buf.get_u8();
_struct.id = buf.get_u8();
_struct.yaw = buf.get_u16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_i32_le(self.lat);
_tmp.put_i32_le(self.lon);
_tmp.put_i32_le(self.alt);
_tmp.put_u16_le(self.eph);
_tmp.put_u16_le(self.epv);
_tmp.put_u16_le(self.vel);
_tmp.put_i16_le(self.vn);
_tmp.put_i16_le(self.ve);
_tmp.put_i16_le(self.vd);
_tmp.put_u16_le(self.cog);
_tmp.put_u8(self.fix_type);
_tmp.put_u8(self.satellites_visible);
_tmp.put_u8(self.id);
_tmp.put_u16_le(self.yaw);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 64"]
#[doc = "The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct LOCAL_POSITION_NED_COV_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "X Position."]
pub x: f32,
#[doc = "Y Position."]
pub y: f32,
#[doc = "Z Position."]
pub z: f32,
#[doc = "X Speed."]
pub vx: f32,
#[doc = "Y Speed."]
pub vy: f32,
#[doc = "Z Speed."]
pub vz: f32,
#[doc = "X Acceleration."]
pub ax: f32,
#[doc = "Y Acceleration."]
pub ay: f32,
#[doc = "Z Acceleration."]
pub az: f32,
#[doc = "Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array.."]
pub covariance: Vec<f32, 45>,
#[doc = "Class id of the estimator this estimate originated from.."]
pub estimator_type: MavEstimatorType,
}
impl LOCAL_POSITION_NED_COV_DATA {
pub const ENCODED_LEN: usize = 225usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.x = buf.get_f32_le();
_struct.y = buf.get_f32_le();
_struct.z = buf.get_f32_le();
_struct.vx = buf.get_f32_le();
_struct.vy = buf.get_f32_le();
_struct.vz = buf.get_f32_le();
_struct.ax = buf.get_f32_le();
_struct.ay = buf.get_f32_le();
_struct.az = buf.get_f32_le();
for _ in 0..45usize {
let val = buf.get_f32_le();
_struct.covariance.push(val).unwrap();
}
let tmp = buf.get_u8();
_struct.estimator_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavEstimatorType",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_f32_le(self.x);
_tmp.put_f32_le(self.y);
_tmp.put_f32_le(self.z);
_tmp.put_f32_le(self.vx);
_tmp.put_f32_le(self.vy);
_tmp.put_f32_le(self.vz);
_tmp.put_f32_le(self.ax);
_tmp.put_f32_le(self.ay);
_tmp.put_f32_le(self.az);
for val in &self.covariance {
_tmp.put_f32_le(*val);
}
_tmp.put_u8(self.estimator_type as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 264"]
#[doc = "Information about flight since last arming. This can be requested using MAV_CMD_REQUEST_MESSAGE.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct FLIGHT_INFORMATION_DATA {
#[doc = "Timestamp at arming (time since UNIX epoch) in UTC, 0 for unknown."]
pub arming_time_utc: u64,
#[doc = "Timestamp at takeoff (time since UNIX epoch) in UTC, 0 for unknown."]
pub takeoff_time_utc: u64,
#[doc = "Universally unique identifier (UUID) of flight, should correspond to name of log files."]
pub flight_uuid: u64,
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
}
impl FLIGHT_INFORMATION_DATA {
pub const ENCODED_LEN: usize = 28usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.arming_time_utc = buf.get_u64_le();
_struct.takeoff_time_utc = buf.get_u64_le();
_struct.flight_uuid = buf.get_u64_le();
_struct.time_boot_ms = buf.get_u32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.arming_time_utc);
_tmp.put_u64_le(self.takeoff_time_utc);
_tmp.put_u64_le(self.flight_uuid);
_tmp.put_u32_le(self.time_boot_ms);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 117"]
#[doc = "Request a list of available logs. On some systems calling this may stop on-board logging until LOG_REQUEST_END is called. If there are no log files available this request shall be answered with one LOG_ENTRY message with id = 0 and num_logs = 0.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct LOG_REQUEST_LIST_DATA {
#[doc = "First log id (0 for first available)."]
pub start: u16,
#[doc = "Last log id (0xffff for last available)."]
pub end: u16,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
}
impl LOG_REQUEST_LIST_DATA {
pub const ENCODED_LEN: usize = 6usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.start = buf.get_u16_le();
_struct.end = buf.get_u16_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.start);
_tmp.put_u16_le(self.end);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 36"]
#[doc = "Superseded by ACTUATOR_OUTPUT_STATUS. The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct SERVO_OUTPUT_RAW_DATA {
#[doc = "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.."]
pub time_usec: u32,
#[doc = "Servo output 1 value."]
pub servo1_raw: u16,
#[doc = "Servo output 2 value."]
pub servo2_raw: u16,
#[doc = "Servo output 3 value."]
pub servo3_raw: u16,
#[doc = "Servo output 4 value."]
pub servo4_raw: u16,
#[doc = "Servo output 5 value."]
pub servo5_raw: u16,
#[doc = "Servo output 6 value."]
pub servo6_raw: u16,
#[doc = "Servo output 7 value."]
pub servo7_raw: u16,
#[doc = "Servo output 8 value."]
pub servo8_raw: u16,
#[doc = "Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX.."]
pub port: u8,
#[doc = "Servo output 9 value."]
#[cfg_attr(feature = "serde", serde(default))]
pub servo9_raw: u16,
#[doc = "Servo output 10 value."]
#[cfg_attr(feature = "serde", serde(default))]
pub servo10_raw: u16,
#[doc = "Servo output 11 value."]
#[cfg_attr(feature = "serde", serde(default))]
pub servo11_raw: u16,
#[doc = "Servo output 12 value."]
#[cfg_attr(feature = "serde", serde(default))]
pub servo12_raw: u16,
#[doc = "Servo output 13 value."]
#[cfg_attr(feature = "serde", serde(default))]
pub servo13_raw: u16,
#[doc = "Servo output 14 value."]
#[cfg_attr(feature = "serde", serde(default))]
pub servo14_raw: u16,
#[doc = "Servo output 15 value."]
#[cfg_attr(feature = "serde", serde(default))]
pub servo15_raw: u16,
#[doc = "Servo output 16 value."]
#[cfg_attr(feature = "serde", serde(default))]
pub servo16_raw: u16,
}
impl SERVO_OUTPUT_RAW_DATA {
pub const ENCODED_LEN: usize = 37usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u32_le();
_struct.servo1_raw = buf.get_u16_le();
_struct.servo2_raw = buf.get_u16_le();
_struct.servo3_raw = buf.get_u16_le();
_struct.servo4_raw = buf.get_u16_le();
_struct.servo5_raw = buf.get_u16_le();
_struct.servo6_raw = buf.get_u16_le();
_struct.servo7_raw = buf.get_u16_le();
_struct.servo8_raw = buf.get_u16_le();
_struct.port = buf.get_u8();
_struct.servo9_raw = buf.get_u16_le();
_struct.servo10_raw = buf.get_u16_le();
_struct.servo11_raw = buf.get_u16_le();
_struct.servo12_raw = buf.get_u16_le();
_struct.servo13_raw = buf.get_u16_le();
_struct.servo14_raw = buf.get_u16_le();
_struct.servo15_raw = buf.get_u16_le();
_struct.servo16_raw = buf.get_u16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_usec);
_tmp.put_u16_le(self.servo1_raw);
_tmp.put_u16_le(self.servo2_raw);
_tmp.put_u16_le(self.servo3_raw);
_tmp.put_u16_le(self.servo4_raw);
_tmp.put_u16_le(self.servo5_raw);
_tmp.put_u16_le(self.servo6_raw);
_tmp.put_u16_le(self.servo7_raw);
_tmp.put_u16_le(self.servo8_raw);
_tmp.put_u8(self.port);
_tmp.put_u16_le(self.servo9_raw);
_tmp.put_u16_le(self.servo10_raw);
_tmp.put_u16_le(self.servo11_raw);
_tmp.put_u16_le(self.servo12_raw);
_tmp.put_u16_le(self.servo13_raw);
_tmp.put_u16_le(self.servo14_raw);
_tmp.put_u16_le(self.servo15_raw);
_tmp.put_u16_le(self.servo16_raw);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 51"]
#[doc = "Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM_INT message. https://mavlink.io/en/services/mission.html."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct MISSION_REQUEST_INT_DATA {
#[doc = "Sequence."]
pub seq: u16,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "Mission type.."]
#[cfg_attr(feature = "serde", serde(default))]
pub mission_type: MavMissionType,
}
impl MISSION_REQUEST_INT_DATA {
pub const ENCODED_LEN: usize = 5usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.seq = buf.get_u16_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
let tmp = buf.get_u8();
_struct.mission_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavMissionType",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.seq);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.mission_type as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 83"]
#[doc = "Reports the current commanded attitude of the vehicle as specified by the autopilot. This should match the commands sent in a SET_ATTITUDE_TARGET message if the vehicle is being controlled this way.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct ATTITUDE_TARGET_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)."]
pub q: [f32; 4],
#[doc = "Body roll rate."]
pub body_roll_rate: f32,
#[doc = "Body pitch rate."]
pub body_pitch_rate: f32,
#[doc = "Body yaw rate."]
pub body_yaw_rate: f32,
#[doc = "Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)."]
pub thrust: f32,
#[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle.."]
pub type_mask: AttitudeTargetTypemask,
}
impl ATTITUDE_TARGET_DATA {
pub const ENCODED_LEN: usize = 37usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
for idx in 0..4usize {
let val = buf.get_f32_le();
_struct.q[idx] = val;
}
_struct.body_roll_rate = buf.get_f32_le();
_struct.body_pitch_rate = buf.get_f32_le();
_struct.body_yaw_rate = buf.get_f32_le();
_struct.thrust = buf.get_f32_le();
let tmp = buf.get_u8();
_struct.type_mask = AttitudeTargetTypemask::from_bits(
tmp & AttitudeTargetTypemask::all().bits(),
)
.ok_or(ParserError::InvalidFlag {
flag_type: "AttitudeTargetTypemask",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
for val in &self.q {
_tmp.put_f32_le(*val);
}
_tmp.put_f32_le(self.body_roll_rate);
_tmp.put_f32_le(self.body_pitch_rate);
_tmp.put_f32_le(self.body_yaw_rate);
_tmp.put_f32_le(self.thrust);
_tmp.put_u8(self.type_mask.bits());
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 125"]
#[doc = "Power supply status."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct POWER_STATUS_DATA {
#[doc = "5V rail voltage.."]
pub Vcc: u16,
#[doc = "Servo rail voltage.."]
pub Vservo: u16,
#[doc = "Bitmap of power supply status flags.."]
pub flags: MavPowerStatus,
}
impl POWER_STATUS_DATA {
pub const ENCODED_LEN: usize = 6usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.Vcc = buf.get_u16_le();
_struct.Vservo = buf.get_u16_le();
let tmp = buf.get_u16_le();
_struct.flags = MavPowerStatus::from_bits(tmp & MavPowerStatus::all().bits()).ok_or(
ParserError::InvalidFlag {
flag_type: "MavPowerStatus",
value: tmp as u32,
},
)?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.Vcc);
_tmp.put_u16_le(self.Vservo);
_tmp.put_u16_le(self.flags.bits());
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 146"]
#[doc = "The smoothed, monotonic system state used to feed the control loops of the system.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct CONTROL_SYSTEM_STATE_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "X acceleration in body frame."]
pub x_acc: f32,
#[doc = "Y acceleration in body frame."]
pub y_acc: f32,
#[doc = "Z acceleration in body frame."]
pub z_acc: f32,
#[doc = "X velocity in body frame."]
pub x_vel: f32,
#[doc = "Y velocity in body frame."]
pub y_vel: f32,
#[doc = "Z velocity in body frame."]
pub z_vel: f32,
#[doc = "X position in local frame."]
pub x_pos: f32,
#[doc = "Y position in local frame."]
pub y_pos: f32,
#[doc = "Z position in local frame."]
pub z_pos: f32,
#[doc = "Airspeed, set to -1 if unknown."]
pub airspeed: f32,
#[doc = "Variance of body velocity estimate."]
pub vel_variance: [f32; 3],
#[doc = "Variance in local position."]
pub pos_variance: [f32; 3],
#[doc = "The attitude, represented as Quaternion."]
pub q: [f32; 4],
#[doc = "Angular rate in roll axis."]
pub roll_rate: f32,
#[doc = "Angular rate in pitch axis."]
pub pitch_rate: f32,
#[doc = "Angular rate in yaw axis."]
pub yaw_rate: f32,
}
impl CONTROL_SYSTEM_STATE_DATA {
pub const ENCODED_LEN: usize = 100usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.x_acc = buf.get_f32_le();
_struct.y_acc = buf.get_f32_le();
_struct.z_acc = buf.get_f32_le();
_struct.x_vel = buf.get_f32_le();
_struct.y_vel = buf.get_f32_le();
_struct.z_vel = buf.get_f32_le();
_struct.x_pos = buf.get_f32_le();
_struct.y_pos = buf.get_f32_le();
_struct.z_pos = buf.get_f32_le();
_struct.airspeed = buf.get_f32_le();
for idx in 0..3usize {
let val = buf.get_f32_le();
_struct.vel_variance[idx] = val;
}
for idx in 0..3usize {
let val = buf.get_f32_le();
_struct.pos_variance[idx] = val;
}
for idx in 0..4usize {
let val = buf.get_f32_le();
_struct.q[idx] = val;
}
_struct.roll_rate = buf.get_f32_le();
_struct.pitch_rate = buf.get_f32_le();
_struct.yaw_rate = buf.get_f32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_f32_le(self.x_acc);
_tmp.put_f32_le(self.y_acc);
_tmp.put_f32_le(self.z_acc);
_tmp.put_f32_le(self.x_vel);
_tmp.put_f32_le(self.y_vel);
_tmp.put_f32_le(self.z_vel);
_tmp.put_f32_le(self.x_pos);
_tmp.put_f32_le(self.y_pos);
_tmp.put_f32_le(self.z_pos);
_tmp.put_f32_le(self.airspeed);
for val in &self.vel_variance {
_tmp.put_f32_le(*val);
}
for val in &self.pos_variance {
_tmp.put_f32_le(*val);
}
for val in &self.q {
_tmp.put_f32_le(*val);
}
_tmp.put_f32_le(self.roll_rate);
_tmp.put_f32_le(self.pitch_rate);
_tmp.put_f32_le(self.yaw_rate);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 11030"]
#[doc = "ESC Telemetry Data for ESCs 1 to 4, matching data sent by BLHeli ESCs.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct ESC_TELEMETRY_1_TO_4_DATA {
#[doc = "Voltage.."]
pub voltage: [u16; 4],
#[doc = "Current.."]
pub current: [u16; 4],
#[doc = "Total current.."]
pub totalcurrent: [u16; 4],
#[doc = "RPM (eRPM).."]
pub rpm: [u16; 4],
#[doc = "count of telemetry packets received (wraps at 65535).."]
pub count: [u16; 4],
#[doc = "Temperature.."]
pub temperature: [u8; 4],
}
impl ESC_TELEMETRY_1_TO_4_DATA {
pub const ENCODED_LEN: usize = 44usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
for idx in 0..4usize {
let val = buf.get_u16_le();
_struct.voltage[idx] = val;
}
for idx in 0..4usize {
let val = buf.get_u16_le();
_struct.current[idx] = val;
}
for idx in 0..4usize {
let val = buf.get_u16_le();
_struct.totalcurrent[idx] = val;
}
for idx in 0..4usize {
let val = buf.get_u16_le();
_struct.rpm[idx] = val;
}
for idx in 0..4usize {
let val = buf.get_u16_le();
_struct.count[idx] = val;
}
for idx in 0..4usize {
let val = buf.get_u8();
_struct.temperature[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
for val in &self.voltage {
_tmp.put_u16_le(*val);
}
for val in &self.current {
_tmp.put_u16_le(*val);
}
for val in &self.totalcurrent {
_tmp.put_u16_le(*val);
}
for val in &self.rpm {
_tmp.put_u16_le(*val);
}
for val in &self.count {
_tmp.put_u16_le(*val);
}
for val in &self.temperature {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 73"]
#[doc = "Message encoding a mission item. This message is emitted to announce the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). 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). See also https://mavlink.io/en/services/mission.html.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct MISSION_ITEM_INT_DATA {
#[doc = "PARAM1, see MAV_CMD enum."]
pub param1: f32,
#[doc = "PARAM2, see MAV_CMD enum."]
pub param2: f32,
#[doc = "PARAM3, see MAV_CMD enum."]
pub param3: f32,
#[doc = "PARAM4, see MAV_CMD enum."]
pub param4: f32,
#[doc = "PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7."]
pub x: i32,
#[doc = "PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7."]
pub y: i32,
#[doc = "PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.."]
pub z: f32,
#[doc = "Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4).."]
pub seq: u16,
#[doc = "The scheduled action for the waypoint.."]
pub command: MavCmd,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "The coordinate system of the waypoint.."]
pub frame: MavFrame,
#[doc = "false:0, true:1."]
pub current: u8,
#[doc = "Autocontinue to next waypoint. 0: false, 1: true. Set false to pause mission after the item completes.."]
pub autocontinue: u8,
#[doc = "Mission type.."]
#[cfg_attr(feature = "serde", serde(default))]
pub mission_type: MavMissionType,
}
impl MISSION_ITEM_INT_DATA {
pub const ENCODED_LEN: usize = 38usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.param1 = buf.get_f32_le();
_struct.param2 = buf.get_f32_le();
_struct.param3 = buf.get_f32_le();
_struct.param4 = buf.get_f32_le();
_struct.x = buf.get_i32_le();
_struct.y = buf.get_i32_le();
_struct.z = buf.get_f32_le();
_struct.seq = buf.get_u16_le();
let tmp = buf.get_u16_le();
_struct.command = FromPrimitive::from_u16(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavCmd",
value: tmp as u32,
})?;
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
let tmp = buf.get_u8();
_struct.frame = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavFrame",
value: tmp as u32,
})?;
_struct.current = buf.get_u8();
_struct.autocontinue = buf.get_u8();
let tmp = buf.get_u8();
_struct.mission_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavMissionType",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.param1);
_tmp.put_f32_le(self.param2);
_tmp.put_f32_le(self.param3);
_tmp.put_f32_le(self.param4);
_tmp.put_i32_le(self.x);
_tmp.put_i32_le(self.y);
_tmp.put_f32_le(self.z);
_tmp.put_u16_le(self.seq);
_tmp.put_u16_le(self.command as u16);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.frame as u8);
_tmp.put_u8(self.current);
_tmp.put_u8(self.autocontinue);
_tmp.put_u8(self.mission_type as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 253"]
#[doc = "Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz).."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct STATUSTEXT_DATA {
#[doc = "Severity of status. Relies on the definitions within RFC-5424.."]
pub severity: MavSeverity,
#[doc = "Status text message, without null termination character."]
pub text: Vec<u8, 50>,
#[doc = "Unique (opaque) identifier for this statustext message. May be used to reassemble a logical long-statustext message from a sequence of chunks. A value of zero indicates this is the only chunk in the sequence and the message can be emitted immediately.."]
#[cfg_attr(feature = "serde", serde(default))]
pub id: u16,
#[doc = "This chunk's sequence number; indexing is from zero. Any null character in the text field is taken to mean this was the last chunk.."]
#[cfg_attr(feature = "serde", serde(default))]
pub chunk_seq: u8,
}
impl STATUSTEXT_DATA {
pub const ENCODED_LEN: usize = 54usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
let tmp = buf.get_u8();
_struct.severity = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavSeverity",
value: tmp as u32,
})?;
for _ in 0..50usize {
let val = buf.get_u8();
_struct.text.push(val).unwrap();
}
_struct.id = buf.get_u16_le();
_struct.chunk_seq = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.severity as u8);
for val in &self.text {
_tmp.put_u8(*val);
}
_tmp.put_u16_le(self.id);
_tmp.put_u8(self.chunk_seq);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 12905"]
#[doc = "Data for filling the OpenDroneID Operator ID message, which contains the CAA (Civil Aviation Authority) issued operator ID.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct OPEN_DRONE_ID_OPERATOR_ID_DATA {
#[doc = "System ID (0 for broadcast).."]
pub target_system: u8,
#[doc = "Component ID (0 for broadcast).."]
pub target_component: u8,
#[doc = "Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.."]
pub id_or_mac: [u8; 20],
#[doc = "Indicates the type of the operator_id field.."]
pub operator_id_type: MavOdidOperatorIdType,
#[doc = "Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field.."]
pub operator_id: [u8; 20],
}
impl OPEN_DRONE_ID_OPERATOR_ID_DATA {
pub const ENCODED_LEN: usize = 43usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
for idx in 0..20usize {
let val = buf.get_u8();
_struct.id_or_mac[idx] = val;
}
let tmp = buf.get_u8();
_struct.operator_id_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavOdidOperatorIdType",
value: tmp as u32,
})?;
for idx in 0..20usize {
let val = buf.get_u8();
_struct.operator_id[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
for val in &self.id_or_mac {
_tmp.put_u8(*val);
}
_tmp.put_u8(self.operator_id_type as u8);
for val in &self.operator_id {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 2"]
#[doc = "The system time is the time of the master clock, typically the computer clock of the main onboard computer.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct SYSTEM_TIME_DATA {
#[doc = "Timestamp (UNIX epoch time).."]
pub time_unix_usec: u64,
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
}
impl SYSTEM_TIME_DATA {
pub const ENCODED_LEN: usize = 12usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_unix_usec = buf.get_u64_le();
_struct.time_boot_ms = buf.get_u32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_unix_usec);
_tmp.put_u32_le(self.time_boot_ms);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 70"]
#[doc = "The RAW values of the RC channels sent to the MAV to override info received from the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. Note carefully the semantic differences between the first 8 channels and the subsequent channels."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct RC_CHANNELS_OVERRIDE_DATA {
#[doc = "RC channel 1 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.."]
pub chan1_raw: u16,
#[doc = "RC channel 2 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.."]
pub chan2_raw: u16,
#[doc = "RC channel 3 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.."]
pub chan3_raw: u16,
#[doc = "RC channel 4 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.."]
pub chan4_raw: u16,
#[doc = "RC channel 5 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.."]
pub chan5_raw: u16,
#[doc = "RC channel 6 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.."]
pub chan6_raw: u16,
#[doc = "RC channel 7 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.."]
pub chan7_raw: u16,
#[doc = "RC channel 8 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.."]
pub chan8_raw: u16,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "RC channel 9 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.."]
#[cfg_attr(feature = "serde", serde(default))]
pub chan9_raw: u16,
#[doc = "RC channel 10 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.."]
#[cfg_attr(feature = "serde", serde(default))]
pub chan10_raw: u16,
#[doc = "RC channel 11 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.."]
#[cfg_attr(feature = "serde", serde(default))]
pub chan11_raw: u16,
#[doc = "RC channel 12 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.."]
#[cfg_attr(feature = "serde", serde(default))]
pub chan12_raw: u16,
#[doc = "RC channel 13 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.."]
#[cfg_attr(feature = "serde", serde(default))]
pub chan13_raw: u16,
#[doc = "RC channel 14 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.."]
#[cfg_attr(feature = "serde", serde(default))]
pub chan14_raw: u16,
#[doc = "RC channel 15 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.."]
#[cfg_attr(feature = "serde", serde(default))]
pub chan15_raw: u16,
#[doc = "RC channel 16 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.."]
#[cfg_attr(feature = "serde", serde(default))]
pub chan16_raw: u16,
#[doc = "RC channel 17 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.."]
#[cfg_attr(feature = "serde", serde(default))]
pub chan17_raw: u16,
#[doc = "RC channel 18 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.."]
#[cfg_attr(feature = "serde", serde(default))]
pub chan18_raw: u16,
}
impl RC_CHANNELS_OVERRIDE_DATA {
pub const ENCODED_LEN: usize = 38usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.chan1_raw = buf.get_u16_le();
_struct.chan2_raw = buf.get_u16_le();
_struct.chan3_raw = buf.get_u16_le();
_struct.chan4_raw = buf.get_u16_le();
_struct.chan5_raw = buf.get_u16_le();
_struct.chan6_raw = buf.get_u16_le();
_struct.chan7_raw = buf.get_u16_le();
_struct.chan8_raw = buf.get_u16_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
_struct.chan9_raw = buf.get_u16_le();
_struct.chan10_raw = buf.get_u16_le();
_struct.chan11_raw = buf.get_u16_le();
_struct.chan12_raw = buf.get_u16_le();
_struct.chan13_raw = buf.get_u16_le();
_struct.chan14_raw = buf.get_u16_le();
_struct.chan15_raw = buf.get_u16_le();
_struct.chan16_raw = buf.get_u16_le();
_struct.chan17_raw = buf.get_u16_le();
_struct.chan18_raw = buf.get_u16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.chan1_raw);
_tmp.put_u16_le(self.chan2_raw);
_tmp.put_u16_le(self.chan3_raw);
_tmp.put_u16_le(self.chan4_raw);
_tmp.put_u16_le(self.chan5_raw);
_tmp.put_u16_le(self.chan6_raw);
_tmp.put_u16_le(self.chan7_raw);
_tmp.put_u16_le(self.chan8_raw);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u16_le(self.chan9_raw);
_tmp.put_u16_le(self.chan10_raw);
_tmp.put_u16_le(self.chan11_raw);
_tmp.put_u16_le(self.chan12_raw);
_tmp.put_u16_le(self.chan13_raw);
_tmp.put_u16_le(self.chan14_raw);
_tmp.put_u16_le(self.chan15_raw);
_tmp.put_u16_le(self.chan16_raw);
_tmp.put_u16_le(self.chan17_raw);
_tmp.put_u16_le(self.chan18_raw);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 11038"]
#[doc = "Water depth."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct WATER_DEPTH_DATA {
#[doc = "Timestamp (time since system boot)."]
pub time_boot_ms: u32,
#[doc = "Latitude."]
pub lat: i32,
#[doc = "Longitude."]
pub lng: i32,
#[doc = "Altitude (MSL) of vehicle."]
pub alt: f32,
#[doc = "Roll angle."]
pub roll: f32,
#[doc = "Pitch angle."]
pub pitch: f32,
#[doc = "Yaw angle."]
pub yaw: f32,
#[doc = "Distance (uncorrected)."]
pub distance: f32,
#[doc = "Water temperature."]
pub temperature: f32,
#[doc = "Onboard ID of the sensor."]
pub id: u8,
#[doc = "Sensor data healthy (0=unhealthy, 1=healthy)."]
pub healthy: u8,
}
impl WATER_DEPTH_DATA {
pub const ENCODED_LEN: usize = 38usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.lat = buf.get_i32_le();
_struct.lng = buf.get_i32_le();
_struct.alt = buf.get_f32_le();
_struct.roll = buf.get_f32_le();
_struct.pitch = buf.get_f32_le();
_struct.yaw = buf.get_f32_le();
_struct.distance = buf.get_f32_le();
_struct.temperature = buf.get_f32_le();
_struct.id = buf.get_u8();
_struct.healthy = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_i32_le(self.lat);
_tmp.put_i32_le(self.lng);
_tmp.put_f32_le(self.alt);
_tmp.put_f32_le(self.roll);
_tmp.put_f32_le(self.pitch);
_tmp.put_f32_le(self.yaw);
_tmp.put_f32_le(self.distance);
_tmp.put_f32_le(self.temperature);
_tmp.put_u8(self.id);
_tmp.put_u8(self.healthy);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 21"]
#[doc = "Request all parameters of this component. After this request, all parameters are emitted. The parameter microservice is documented at https://mavlink.io/en/services/parameter.html."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PARAM_REQUEST_LIST_DATA {
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
}
impl PARAM_REQUEST_LIST_DATA {
pub const ENCODED_LEN: usize = 2usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 61"]
#[doc = "The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0).."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct ATTITUDE_QUATERNION_COV_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)."]
pub q: [f32; 4],
#[doc = "Roll angular speed."]
pub rollspeed: f32,
#[doc = "Pitch angular speed."]
pub pitchspeed: f32,
#[doc = "Yaw angular speed."]
pub yawspeed: f32,
#[doc = "Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array.."]
pub covariance: [f32; 9],
}
impl ATTITUDE_QUATERNION_COV_DATA {
pub const ENCODED_LEN: usize = 72usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
for idx in 0..4usize {
let val = buf.get_f32_le();
_struct.q[idx] = val;
}
_struct.rollspeed = buf.get_f32_le();
_struct.pitchspeed = buf.get_f32_le();
_struct.yawspeed = buf.get_f32_le();
for idx in 0..9usize {
let val = buf.get_f32_le();
_struct.covariance[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
for val in &self.q {
_tmp.put_f32_le(*val);
}
_tmp.put_f32_le(self.rollspeed);
_tmp.put_f32_le(self.pitchspeed);
_tmp.put_f32_le(self.yawspeed);
for val in &self.covariance {
_tmp.put_f32_le(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 131"]
#[doc = "Data packet for images sent using the Image Transmission Protocol: https://mavlink.io/en/services/image_transmission.html.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct ENCAPSULATED_DATA_DATA {
#[doc = "sequence number (starting with 0 on every transmission)."]
pub seqnr: u16,
#[doc = "image data bytes."]
pub data: Vec<u8, 253>,
}
impl ENCAPSULATED_DATA_DATA {
pub const ENCODED_LEN: usize = 255usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.seqnr = buf.get_u16_le();
for _ in 0..253usize {
let val = buf.get_u8();
_struct.data.push(val).unwrap();
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.seqnr);
for val in &self.data {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 22"]
#[doc = "Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout. The parameter microservice is documented at https://mavlink.io/en/services/parameter.html."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PARAM_VALUE_DATA {
#[doc = "Onboard parameter value."]
pub param_value: f32,
#[doc = "Total number of onboard parameters."]
pub param_count: u16,
#[doc = "Index of this onboard parameter."]
pub param_index: u16,
#[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string."]
pub param_id: [u8; 16],
#[doc = "Onboard parameter type.."]
pub param_type: MavParamType,
}
impl PARAM_VALUE_DATA {
pub const ENCODED_LEN: usize = 25usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.param_value = buf.get_f32_le();
_struct.param_count = buf.get_u16_le();
_struct.param_index = buf.get_u16_le();
for idx in 0..16usize {
let val = buf.get_u8();
_struct.param_id[idx] = val;
}
let tmp = buf.get_u8();
_struct.param_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavParamType",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.param_value);
_tmp.put_u16_le(self.param_count);
_tmp.put_u16_le(self.param_index);
for val in &self.param_id {
_tmp.put_u8(*val);
}
_tmp.put_u8(self.param_type as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 6"]
#[doc = "Accept / deny control of this MAV."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct CHANGE_OPERATOR_CONTROL_ACK_DATA {
#[doc = "ID of the GCS this message."]
pub gcs_system_id: u8,
#[doc = "0: request control of this MAV, 1: Release control of this MAV."]
pub control_request: u8,
#[doc = "0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control."]
pub ack: u8,
}
impl CHANGE_OPERATOR_CONTROL_ACK_DATA {
pub const ENCODED_LEN: usize = 3usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.gcs_system_id = buf.get_u8();
_struct.control_request = buf.get_u8();
_struct.ack = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.gcs_system_id);
_tmp.put_u8(self.control_request);
_tmp.put_u8(self.ack);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 4"]
#[doc = "A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections. The ping microservice is documented at https://mavlink.io/en/services/ping.html."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PING_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "PING sequence."]
pub seq: u32,
#[doc = "0: request ping from all receiving systems. If greater than 0: message is a ping response and number is the system id of the requesting system."]
pub target_system: u8,
#[doc = "0: request ping from all receiving components. If greater than 0: message is a ping response and number is the component id of the requesting component.."]
pub target_component: u8,
}
impl PING_DATA {
pub const ENCODED_LEN: usize = 14usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.seq = buf.get_u32_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_u32_le(self.seq);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 48"]
#[doc = "Sets the GPS coordinates of the vehicle local origin (0,0,0) position. Vehicle should emit GPS_GLOBAL_ORIGIN irrespective of whether the origin is changed. This enables transform between the local coordinate frame and the global (GPS) coordinate frame, which may be necessary when (for example) indoor and outdoor settings are connected and the MAV should move from in- to outdoor.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct SET_GPS_GLOBAL_ORIGIN_DATA {
#[doc = "Latitude (WGS84)."]
pub latitude: i32,
#[doc = "Longitude (WGS84)."]
pub longitude: i32,
#[doc = "Altitude (MSL). Positive for up.."]
pub altitude: i32,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "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.."]
#[cfg_attr(feature = "serde", serde(default))]
pub time_usec: u64,
}
impl SET_GPS_GLOBAL_ORIGIN_DATA {
pub const ENCODED_LEN: usize = 21usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.latitude = buf.get_i32_le();
_struct.longitude = buf.get_i32_le();
_struct.altitude = buf.get_i32_le();
_struct.target_system = buf.get_u8();
_struct.time_usec = buf.get_u64_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_i32_le(self.latitude);
_tmp.put_i32_le(self.longitude);
_tmp.put_i32_le(self.altitude);
_tmp.put_u8(self.target_system);
_tmp.put_u64_le(self.time_usec);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 195"]
#[doc = "Deepstall path planning.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct DEEPSTALL_DATA {
#[doc = "Landing latitude.."]
pub landing_lat: i32,
#[doc = "Landing longitude.."]
pub landing_lon: i32,
#[doc = "Final heading start point, latitude.."]
pub path_lat: i32,
#[doc = "Final heading start point, longitude.."]
pub path_lon: i32,
#[doc = "Arc entry point, latitude.."]
pub arc_entry_lat: i32,
#[doc = "Arc entry point, longitude.."]
pub arc_entry_lon: i32,
#[doc = "Altitude.."]
pub altitude: f32,
#[doc = "Distance the aircraft expects to travel during the deepstall.."]
pub expected_travel_distance: f32,
#[doc = "Deepstall cross track error (only valid when in DEEPSTALL_STAGE_LAND).."]
pub cross_track_error: f32,
#[doc = "Deepstall stage.."]
pub stage: DeepstallStage,
}
impl DEEPSTALL_DATA {
pub const ENCODED_LEN: usize = 37usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.landing_lat = buf.get_i32_le();
_struct.landing_lon = buf.get_i32_le();
_struct.path_lat = buf.get_i32_le();
_struct.path_lon = buf.get_i32_le();
_struct.arc_entry_lat = buf.get_i32_le();
_struct.arc_entry_lon = buf.get_i32_le();
_struct.altitude = buf.get_f32_le();
_struct.expected_travel_distance = buf.get_f32_le();
_struct.cross_track_error = buf.get_f32_le();
let tmp = buf.get_u8();
_struct.stage = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "DeepstallStage",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_i32_le(self.landing_lat);
_tmp.put_i32_le(self.landing_lon);
_tmp.put_i32_le(self.path_lat);
_tmp.put_i32_le(self.path_lon);
_tmp.put_i32_le(self.arc_entry_lat);
_tmp.put_i32_le(self.arc_entry_lon);
_tmp.put_f32_le(self.altitude);
_tmp.put_f32_le(self.expected_travel_distance);
_tmp.put_f32_le(self.cross_track_error);
_tmp.put_u8(self.stage as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 218"]
#[doc = "Request to set a GOPRO_COMMAND with a desired.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct GOPRO_SET_REQUEST_DATA {
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Component ID.."]
pub target_component: u8,
#[doc = "Command ID.."]
pub cmd_id: GoproCommand,
#[doc = "Value.."]
pub value: [u8; 4],
}
impl GOPRO_SET_REQUEST_DATA {
pub const ENCODED_LEN: usize = 7usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
let tmp = buf.get_u8();
_struct.cmd_id = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "GoproCommand",
value: tmp as u32,
})?;
for idx in 0..4usize {
let val = buf.get_u8();
_struct.value[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.cmd_id as u8);
for val in &self.value {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 193"]
#[doc = "EKF Status message including flags and variances.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct EKF_STATUS_REPORT_DATA {
#[doc = "Velocity variance.."]
pub velocity_variance: f32,
#[doc = "Horizontal Position variance.."]
pub pos_horiz_variance: f32,
#[doc = "Vertical Position variance.."]
pub pos_vert_variance: f32,
#[doc = "Compass variance.."]
pub compass_variance: f32,
#[doc = "Terrain Altitude variance.."]
pub terrain_alt_variance: f32,
#[doc = "Flags.."]
pub flags: EkfStatusFlags,
#[doc = "Airspeed variance.."]
#[cfg_attr(feature = "serde", serde(default))]
pub airspeed_variance: f32,
}
impl EKF_STATUS_REPORT_DATA {
pub const ENCODED_LEN: usize = 26usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.velocity_variance = buf.get_f32_le();
_struct.pos_horiz_variance = buf.get_f32_le();
_struct.pos_vert_variance = buf.get_f32_le();
_struct.compass_variance = buf.get_f32_le();
_struct.terrain_alt_variance = buf.get_f32_le();
let tmp = buf.get_u16_le();
_struct.flags = EkfStatusFlags::from_bits(tmp & EkfStatusFlags::all().bits()).ok_or(
ParserError::InvalidFlag {
flag_type: "EkfStatusFlags",
value: tmp as u32,
},
)?;
_struct.airspeed_variance = buf.get_f32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.velocity_variance);
_tmp.put_f32_le(self.pos_horiz_variance);
_tmp.put_f32_le(self.pos_vert_variance);
_tmp.put_f32_le(self.compass_variance);
_tmp.put_f32_le(self.terrain_alt_variance);
_tmp.put_u16_le(self.flags.bits());
_tmp.put_f32_le(self.airspeed_variance);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 11033"]
#[doc = "Configure an OSD parameter slot.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct OSD_PARAM_CONFIG_DATA {
#[doc = "Request ID - copied to reply.."]
pub request_id: u32,
#[doc = "OSD parameter minimum value.."]
pub min_value: f32,
#[doc = "OSD parameter maximum value.."]
pub max_value: f32,
#[doc = "OSD parameter increment.."]
pub increment: f32,
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Component ID.."]
pub target_component: u8,
#[doc = "OSD parameter screen index.."]
pub osd_screen: u8,
#[doc = "OSD parameter display index.."]
pub osd_index: u8,
#[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string."]
pub param_id: [u8; 16],
#[doc = "Config type.."]
pub config_type: OsdParamConfigType,
}
impl OSD_PARAM_CONFIG_DATA {
pub const ENCODED_LEN: usize = 37usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.request_id = buf.get_u32_le();
_struct.min_value = buf.get_f32_le();
_struct.max_value = buf.get_f32_le();
_struct.increment = buf.get_f32_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
_struct.osd_screen = buf.get_u8();
_struct.osd_index = buf.get_u8();
for idx in 0..16usize {
let val = buf.get_u8();
_struct.param_id[idx] = val;
}
let tmp = buf.get_u8();
_struct.config_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "OsdParamConfigType",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.request_id);
_tmp.put_f32_le(self.min_value);
_tmp.put_f32_le(self.max_value);
_tmp.put_f32_le(self.increment);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.osd_screen);
_tmp.put_u8(self.osd_index);
for val in &self.param_id {
_tmp.put_u8(*val);
}
_tmp.put_u8(self.config_type as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 321"]
#[doc = "Request all parameters of this component. All parameters should be emitted in response as PARAM_EXT_VALUE.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PARAM_EXT_REQUEST_LIST_DATA {
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
}
impl PARAM_EXT_REQUEST_LIST_DATA {
pub const ENCODED_LEN: usize = 2usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 62"]
#[doc = "The state of the navigation and position controller.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct NAV_CONTROLLER_OUTPUT_DATA {
#[doc = "Current desired roll."]
pub nav_roll: f32,
#[doc = "Current desired pitch."]
pub nav_pitch: f32,
#[doc = "Current altitude error."]
pub alt_error: f32,
#[doc = "Current airspeed error."]
pub aspd_error: f32,
#[doc = "Current crosstrack error on x-y plane."]
pub xtrack_error: f32,
#[doc = "Current desired heading."]
pub nav_bearing: i16,
#[doc = "Bearing to current waypoint/target."]
pub target_bearing: i16,
#[doc = "Distance to active waypoint."]
pub wp_dist: u16,
}
impl NAV_CONTROLLER_OUTPUT_DATA {
pub const ENCODED_LEN: usize = 26usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.nav_roll = buf.get_f32_le();
_struct.nav_pitch = buf.get_f32_le();
_struct.alt_error = buf.get_f32_le();
_struct.aspd_error = buf.get_f32_le();
_struct.xtrack_error = buf.get_f32_le();
_struct.nav_bearing = buf.get_i16_le();
_struct.target_bearing = buf.get_i16_le();
_struct.wp_dist = buf.get_u16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.nav_roll);
_tmp.put_f32_le(self.nav_pitch);
_tmp.put_f32_le(self.alt_error);
_tmp.put_f32_le(self.aspd_error);
_tmp.put_f32_le(self.xtrack_error);
_tmp.put_i16_le(self.nav_bearing);
_tmp.put_i16_le(self.target_bearing);
_tmp.put_u16_le(self.wp_dist);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 10002"]
#[doc = "Dynamic data used to generate ADS-B out transponder data (send at 5Hz)."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct UAVIONIX_ADSB_OUT_DYNAMIC_DATA {
#[doc = "UTC time in seconds since GPS epoch (Jan 6, 1980). If unknown set to UINT32_MAX."]
pub utcTime: u32,
#[doc = "Latitude WGS84 (deg * 1E7). If unknown set to INT32_MAX."]
pub gpsLat: i32,
#[doc = "Longitude WGS84 (deg * 1E7). If unknown set to INT32_MAX."]
pub gpsLon: i32,
#[doc = "Altitude (WGS84). UP +ve. If unknown set to INT32_MAX."]
pub gpsAlt: i32,
#[doc = "Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX."]
pub baroAltMSL: i32,
#[doc = "Horizontal accuracy in mm (m * 1E-3). If unknown set to UINT32_MAX."]
pub accuracyHor: u32,
#[doc = "Vertical accuracy in cm. If unknown set to UINT16_MAX."]
pub accuracyVert: u16,
#[doc = "Velocity accuracy in mm/s (m * 1E-3). If unknown set to UINT16_MAX."]
pub accuracyVel: u16,
#[doc = "GPS vertical speed in cm/s. If unknown set to INT16_MAX."]
pub velVert: i16,
#[doc = "North-South velocity over ground in cm/s North +ve. If unknown set to INT16_MAX."]
pub velNS: i16,
#[doc = "East-West velocity over ground in cm/s East +ve. If unknown set to INT16_MAX."]
pub VelEW: i16,
#[doc = "ADS-B transponder dynamic input state flags."]
pub state: UavionixAdsbOutDynamicState,
#[doc = "Mode A code (typically 1200 [0x04B0] for VFR)."]
pub squawk: u16,
#[doc = "0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK."]
pub gpsFix: UavionixAdsbOutDynamicGpsFix,
#[doc = "Number of satellites visible. If unknown set to UINT8_MAX."]
pub numSats: u8,
#[doc = "Emergency status."]
pub emergencyStatus: UavionixAdsbEmergencyStatus,
}
impl UAVIONIX_ADSB_OUT_DYNAMIC_DATA {
pub const ENCODED_LEN: usize = 41usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.utcTime = buf.get_u32_le();
_struct.gpsLat = buf.get_i32_le();
_struct.gpsLon = buf.get_i32_le();
_struct.gpsAlt = buf.get_i32_le();
_struct.baroAltMSL = buf.get_i32_le();
_struct.accuracyHor = buf.get_u32_le();
_struct.accuracyVert = buf.get_u16_le();
_struct.accuracyVel = buf.get_u16_le();
_struct.velVert = buf.get_i16_le();
_struct.velNS = buf.get_i16_le();
_struct.VelEW = buf.get_i16_le();
let tmp = buf.get_u16_le();
_struct.state =
UavionixAdsbOutDynamicState::from_bits(tmp & UavionixAdsbOutDynamicState::all().bits())
.ok_or(ParserError::InvalidFlag {
flag_type: "UavionixAdsbOutDynamicState",
value: tmp as u32,
})?;
_struct.squawk = buf.get_u16_le();
let tmp = buf.get_u8();
_struct.gpsFix = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "UavionixAdsbOutDynamicGpsFix",
value: tmp as u32,
})?;
_struct.numSats = buf.get_u8();
let tmp = buf.get_u8();
_struct.emergencyStatus = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "UavionixAdsbEmergencyStatus",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.utcTime);
_tmp.put_i32_le(self.gpsLat);
_tmp.put_i32_le(self.gpsLon);
_tmp.put_i32_le(self.gpsAlt);
_tmp.put_i32_le(self.baroAltMSL);
_tmp.put_u32_le(self.accuracyHor);
_tmp.put_u16_le(self.accuracyVert);
_tmp.put_u16_le(self.accuracyVel);
_tmp.put_i16_le(self.velVert);
_tmp.put_i16_le(self.velNS);
_tmp.put_i16_le(self.VelEW);
_tmp.put_u16_le(self.state.bits());
_tmp.put_u16_le(self.squawk);
_tmp.put_u8(self.gpsFix as u8);
_tmp.put_u8(self.numSats);
_tmp.put_u8(self.emergencyStatus as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 116"]
#[doc = "The RAW IMU readings for secondary 9DOF sensor setup. This message should contain the scaled values to the described units."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct SCALED_IMU2_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "X acceleration."]
pub xacc: i16,
#[doc = "Y acceleration."]
pub yacc: i16,
#[doc = "Z acceleration."]
pub zacc: i16,
#[doc = "Angular speed around X axis."]
pub xgyro: i16,
#[doc = "Angular speed around Y axis."]
pub ygyro: i16,
#[doc = "Angular speed around Z axis."]
pub zgyro: i16,
#[doc = "X Magnetic field."]
pub xmag: i16,
#[doc = "Y Magnetic field."]
pub ymag: i16,
#[doc = "Z Magnetic field."]
pub zmag: i16,
#[doc = "Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C).."]
#[cfg_attr(feature = "serde", serde(default))]
pub temperature: i16,
}
impl SCALED_IMU2_DATA {
pub const ENCODED_LEN: usize = 24usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.xacc = buf.get_i16_le();
_struct.yacc = buf.get_i16_le();
_struct.zacc = buf.get_i16_le();
_struct.xgyro = buf.get_i16_le();
_struct.ygyro = buf.get_i16_le();
_struct.zgyro = buf.get_i16_le();
_struct.xmag = buf.get_i16_le();
_struct.ymag = buf.get_i16_le();
_struct.zmag = buf.get_i16_le();
_struct.temperature = buf.get_i16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_i16_le(self.xacc);
_tmp.put_i16_le(self.yacc);
_tmp.put_i16_le(self.zacc);
_tmp.put_i16_le(self.xgyro);
_tmp.put_i16_le(self.ygyro);
_tmp.put_i16_le(self.zgyro);
_tmp.put_i16_le(self.xmag);
_tmp.put_i16_le(self.ymag);
_tmp.put_i16_le(self.zmag);
_tmp.put_i16_le(self.temperature);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 160"]
#[doc = "A fence point. Used to set a point when from GCS -> MAV. Also used to return a point from MAV -> GCS.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct FENCE_POINT_DATA {
#[doc = "Latitude of point.."]
pub lat: f32,
#[doc = "Longitude of point.."]
pub lng: f32,
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Component ID.."]
pub target_component: u8,
#[doc = "Point index (first point is 1, 0 is for return point).."]
pub idx: u8,
#[doc = "Total number of points (for sanity checking).."]
pub count: u8,
}
impl FENCE_POINT_DATA {
pub const ENCODED_LEN: usize = 12usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.lat = buf.get_f32_le();
_struct.lng = buf.get_f32_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
_struct.idx = buf.get_u8();
_struct.count = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.lat);
_tmp.put_f32_le(self.lng);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.idx);
_tmp.put_u8(self.count);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 139"]
#[doc = "Set the vehicle attitude and body angular rates.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct SET_ACTUATOR_CONTROL_TARGET_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.."]
pub controls: [f32; 8],
#[doc = "Actuator group. The \"_mlx\" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.."]
pub group_mlx: u8,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
}
impl SET_ACTUATOR_CONTROL_TARGET_DATA {
pub const ENCODED_LEN: usize = 43usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
for idx in 0..8usize {
let val = buf.get_f32_le();
_struct.controls[idx] = val;
}
_struct.group_mlx = buf.get_u8();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
for val in &self.controls {
_tmp.put_f32_le(*val);
}
_tmp.put_u8(self.group_mlx);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 11020"]
#[doc = "Angle of Attack and Side Slip Angle.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct AOA_SSA_DATA {
#[doc = "Timestamp (since boot or Unix epoch).."]
pub time_usec: u64,
#[doc = "Angle of Attack.."]
pub AOA: f32,
#[doc = "Side Slip Angle.."]
pub SSA: f32,
}
impl AOA_SSA_DATA {
pub const ENCODED_LEN: usize = 16usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.AOA = buf.get_f32_le();
_struct.SSA = buf.get_f32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_f32_le(self.AOA);
_tmp.put_f32_le(self.SSA);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 106"]
#[doc = "Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse sensor)."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct OPTICAL_FLOW_RAD_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.."]
pub integration_time_us: u32,
#[doc = "Flow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)."]
pub integrated_x: f32,
#[doc = "Flow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)."]
pub integrated_y: f32,
#[doc = "RH rotation around X axis."]
pub integrated_xgyro: f32,
#[doc = "RH rotation around Y axis."]
pub integrated_ygyro: f32,
#[doc = "RH rotation around Z axis."]
pub integrated_zgyro: f32,
#[doc = "Time since the distance was sampled.."]
pub time_delta_distance_us: u32,
#[doc = "Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.."]
pub distance: f32,
#[doc = "Temperature."]
pub temperature: i16,
#[doc = "Sensor ID."]
pub sensor_id: u8,
#[doc = "Optical flow quality / confidence. 0: no valid flow, 255: maximum quality."]
pub quality: u8,
}
impl OPTICAL_FLOW_RAD_DATA {
pub const ENCODED_LEN: usize = 44usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.integration_time_us = buf.get_u32_le();
_struct.integrated_x = buf.get_f32_le();
_struct.integrated_y = buf.get_f32_le();
_struct.integrated_xgyro = buf.get_f32_le();
_struct.integrated_ygyro = buf.get_f32_le();
_struct.integrated_zgyro = buf.get_f32_le();
_struct.time_delta_distance_us = buf.get_u32_le();
_struct.distance = buf.get_f32_le();
_struct.temperature = buf.get_i16_le();
_struct.sensor_id = buf.get_u8();
_struct.quality = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_u32_le(self.integration_time_us);
_tmp.put_f32_le(self.integrated_x);
_tmp.put_f32_le(self.integrated_y);
_tmp.put_f32_le(self.integrated_xgyro);
_tmp.put_f32_le(self.integrated_ygyro);
_tmp.put_f32_le(self.integrated_zgyro);
_tmp.put_u32_le(self.time_delta_distance_us);
_tmp.put_f32_le(self.distance);
_tmp.put_i16_le(self.temperature);
_tmp.put_u8(self.sensor_id);
_tmp.put_u8(self.quality);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 104"]
#[doc = "Global position estimate from a Vicon motion system source.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct VICON_POSITION_ESTIMATE_DATA {
#[doc = "Timestamp (UNIX time or time since system boot)."]
pub usec: u64,
#[doc = "Global X position."]
pub x: f32,
#[doc = "Global Y position."]
pub y: f32,
#[doc = "Global Z position."]
pub z: f32,
#[doc = "Roll angle."]
pub roll: f32,
#[doc = "Pitch angle."]
pub pitch: f32,
#[doc = "Yaw angle."]
pub yaw: f32,
#[doc = "Row-major representation of 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.."]
#[cfg_attr(feature = "serde", serde(default))]
pub covariance: [f32; 21],
}
impl VICON_POSITION_ESTIMATE_DATA {
pub const ENCODED_LEN: usize = 116usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.usec = buf.get_u64_le();
_struct.x = buf.get_f32_le();
_struct.y = buf.get_f32_le();
_struct.z = buf.get_f32_le();
_struct.roll = buf.get_f32_le();
_struct.pitch = buf.get_f32_le();
_struct.yaw = buf.get_f32_le();
for idx in 0..21usize {
let val = buf.get_f32_le();
_struct.covariance[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.usec);
_tmp.put_f32_le(self.x);
_tmp.put_f32_le(self.y);
_tmp.put_f32_le(self.z);
_tmp.put_f32_le(self.roll);
_tmp.put_f32_le(self.pitch);
_tmp.put_f32_le(self.yaw);
for val in &self.covariance {
_tmp.put_f32_le(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 241"]
#[doc = "Vibration levels and accelerometer clipping."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct VIBRATION_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "Vibration levels on X-axis."]
pub vibration_x: f32,
#[doc = "Vibration levels on Y-axis."]
pub vibration_y: f32,
#[doc = "Vibration levels on Z-axis."]
pub vibration_z: f32,
#[doc = "first accelerometer clipping count."]
pub clipping_0: u32,
#[doc = "second accelerometer clipping count."]
pub clipping_1: u32,
#[doc = "third accelerometer clipping count."]
pub clipping_2: u32,
}
impl VIBRATION_DATA {
pub const ENCODED_LEN: usize = 32usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.vibration_x = buf.get_f32_le();
_struct.vibration_y = buf.get_f32_le();
_struct.vibration_z = buf.get_f32_le();
_struct.clipping_0 = buf.get_u32_le();
_struct.clipping_1 = buf.get_u32_le();
_struct.clipping_2 = buf.get_u32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_f32_le(self.vibration_x);
_tmp.put_f32_le(self.vibration_y);
_tmp.put_f32_le(self.vibration_z);
_tmp.put_u32_le(self.clipping_0);
_tmp.put_u32_le(self.clipping_1);
_tmp.put_u32_le(self.clipping_2);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 149"]
#[doc = "The location of a landing target. See: https://mavlink.io/en/services/landing_target.html."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct LANDING_TARGET_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "X-axis angular offset of the target from the center of the image."]
pub angle_x: f32,
#[doc = "Y-axis angular offset of the target from the center of the image."]
pub angle_y: f32,
#[doc = "Distance to the target from the vehicle."]
pub distance: f32,
#[doc = "Size of target along x-axis."]
pub size_x: f32,
#[doc = "Size of target along y-axis."]
pub size_y: f32,
#[doc = "The ID of the target if multiple targets are present."]
pub target_num: u8,
#[doc = "Coordinate frame used for following fields.."]
pub frame: MavFrame,
#[doc = "X Position of the landing target in MAV_FRAME."]
#[cfg_attr(feature = "serde", serde(default))]
pub x: f32,
#[doc = "Y Position of the landing target in MAV_FRAME."]
#[cfg_attr(feature = "serde", serde(default))]
pub y: f32,
#[doc = "Z Position of the landing target in MAV_FRAME."]
#[cfg_attr(feature = "serde", serde(default))]
pub z: f32,
#[doc = "Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)."]
#[cfg_attr(feature = "serde", serde(default))]
pub q: [f32; 4],
#[doc = "Type of landing target."]
#[cfg_attr(feature = "serde", serde(default))]
pub mavtype: LandingTargetType,
#[doc = "Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid).."]
#[cfg_attr(feature = "serde", serde(default))]
pub position_valid: u8,
}
impl LANDING_TARGET_DATA {
pub const ENCODED_LEN: usize = 60usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.angle_x = buf.get_f32_le();
_struct.angle_y = buf.get_f32_le();
_struct.distance = buf.get_f32_le();
_struct.size_x = buf.get_f32_le();
_struct.size_y = buf.get_f32_le();
_struct.target_num = buf.get_u8();
let tmp = buf.get_u8();
_struct.frame = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavFrame",
value: tmp as u32,
})?;
_struct.x = buf.get_f32_le();
_struct.y = buf.get_f32_le();
_struct.z = buf.get_f32_le();
for idx in 0..4usize {
let val = buf.get_f32_le();
_struct.q[idx] = val;
}
let tmp = buf.get_u8();
_struct.mavtype = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "LandingTargetType",
value: tmp as u32,
})?;
_struct.position_valid = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_f32_le(self.angle_x);
_tmp.put_f32_le(self.angle_y);
_tmp.put_f32_le(self.distance);
_tmp.put_f32_le(self.size_x);
_tmp.put_f32_le(self.size_y);
_tmp.put_u8(self.target_num);
_tmp.put_u8(self.frame as u8);
_tmp.put_f32_le(self.x);
_tmp.put_f32_le(self.y);
_tmp.put_f32_le(self.z);
for val in &self.q {
_tmp.put_f32_le(*val);
}
_tmp.put_u8(self.mavtype as u8);
_tmp.put_u8(self.position_valid);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 42"]
#[doc = "Message that announces the sequence number of the current target mission item (that the system will fly towards/execute when the mission is running). This message should be streamed all the time (nominally at 1Hz). This message should be emitted following a call to MAV_CMD_DO_SET_MISSION_CURRENT or SET_MISSION_CURRENT.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct MISSION_CURRENT_DATA {
#[doc = "Sequence."]
pub seq: u16,
#[doc = "Total number of mission items. 0: Not supported, UINT16_MAX if no mission is present on the vehicle.."]
#[cfg_attr(feature = "serde", serde(default))]
pub total: u16,
#[doc = "Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported.."]
#[cfg_attr(feature = "serde", serde(default))]
pub mission_state: MissionState,
#[doc = "Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode).."]
#[cfg_attr(feature = "serde", serde(default))]
pub mission_mode: u8,
}
impl MISSION_CURRENT_DATA {
pub const ENCODED_LEN: usize = 6usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.seq = buf.get_u16_le();
_struct.total = buf.get_u16_le();
let tmp = buf.get_u8();
_struct.mission_state = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MissionState",
value: tmp as u32,
})?;
_struct.mission_mode = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.seq);
_tmp.put_u16_le(self.total);
_tmp.put_u8(self.mission_state as u8);
_tmp.put_u8(self.mission_mode);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 171"]
#[doc = "Data packet, size 64.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct DATA64_DATA {
#[doc = "Data type.."]
pub mavtype: u8,
#[doc = "Data length.."]
pub len: u8,
#[doc = "Raw data.."]
pub data: Vec<u8, 64>,
}
impl DATA64_DATA {
pub const ENCODED_LEN: usize = 66usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.mavtype = buf.get_u8();
_struct.len = buf.get_u8();
for _ in 0..64usize {
let val = buf.get_u8();
_struct.data.push(val).unwrap();
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.mavtype);
_tmp.put_u8(self.len);
for val in &self.data {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 111"]
#[doc = "Time synchronization message. The message is used for both timesync requests and responses. The request is sent with `ts1=syncing component timestamp` and `tc1=0`, and may be broadcast or targeted to a specific system/component. The response is sent with `ts1=syncing component timestamp` (mirror back unchanged), and `tc1=responding component timestamp`, with the `target_system` and `target_component` set to ids of the original request. Systems can determine if they are receiving a request or response based on the value of `tc`. If the response has `target_system==target_component==0` the remote system has not been updated to use the component IDs and cannot reliably timesync; the requestor may report an error. Timestamps are UNIX Epoch time or time since system boot in nanoseconds (the timestamp format can be inferred by checking for the magnitude of the number; generally it doesn't matter as only the offset is used). The message sequence is repeated numerous times with results being filtered/averaged to estimate the offset.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct TIMESYNC_DATA {
#[doc = "Time sync timestamp 1. Syncing: 0. Responding: Timestamp of responding component.."]
pub tc1: i64,
#[doc = "Time sync timestamp 2. Timestamp of syncing component (mirrored in response).."]
pub ts1: i64,
#[doc = "Target system id. Request: 0 (broadcast) or id of specific system. Response must contain system id of the requesting component.."]
#[cfg_attr(feature = "serde", serde(default))]
pub target_system: u8,
#[doc = "Target component id. Request: 0 (broadcast) or id of specific component. Response must contain component id of the requesting component.."]
#[cfg_attr(feature = "serde", serde(default))]
pub target_component: u8,
}
impl TIMESYNC_DATA {
pub const ENCODED_LEN: usize = 18usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.tc1 = buf.get_i64_le();
_struct.ts1 = buf.get_i64_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_i64_le(self.tc1);
_tmp.put_i64_le(self.ts1);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 251"]
#[doc = "Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct NAMED_VALUE_FLOAT_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "Floating point value."]
pub value: f32,
#[doc = "Name of the debug variable."]
pub name: [u8; 10],
}
impl NAMED_VALUE_FLOAT_DATA {
pub const ENCODED_LEN: usize = 18usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.value = buf.get_f32_le();
for idx in 0..10usize {
let val = buf.get_u8();
_struct.name[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_f32_le(self.value);
for val in &self.name {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 141"]
#[doc = "The current system altitude.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct ALTITUDE_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.."]
pub altitude_monotonic: f32,
#[doc = "This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude.."]
pub altitude_amsl: f32,
#[doc = "This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.."]
pub altitude_local: f32,
#[doc = "This is the altitude above the home position. It resets on each change of the current home position.."]
pub altitude_relative: f32,
#[doc = "This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.."]
pub altitude_terrain: f32,
#[doc = "This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.."]
pub bottom_clearance: f32,
}
impl ALTITUDE_DATA {
pub const ENCODED_LEN: usize = 32usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.altitude_monotonic = buf.get_f32_le();
_struct.altitude_amsl = buf.get_f32_le();
_struct.altitude_local = buf.get_f32_le();
_struct.altitude_relative = buf.get_f32_le();
_struct.altitude_terrain = buf.get_f32_le();
_struct.bottom_clearance = buf.get_f32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_f32_le(self.altitude_monotonic);
_tmp.put_f32_le(self.altitude_amsl);
_tmp.put_f32_le(self.altitude_local);
_tmp.put_f32_le(self.altitude_relative);
_tmp.put_f32_le(self.altitude_terrain);
_tmp.put_f32_le(self.bottom_clearance);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 114"]
#[doc = "Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical mouse sensor)."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct HIL_OPTICAL_FLOW_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.."]
pub integration_time_us: u32,
#[doc = "Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)."]
pub integrated_x: f32,
#[doc = "Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)."]
pub integrated_y: f32,
#[doc = "RH rotation around X axis."]
pub integrated_xgyro: f32,
#[doc = "RH rotation around Y axis."]
pub integrated_ygyro: f32,
#[doc = "RH rotation around Z axis."]
pub integrated_zgyro: f32,
#[doc = "Time since the distance was sampled.."]
pub time_delta_distance_us: u32,
#[doc = "Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.."]
pub distance: f32,
#[doc = "Temperature."]
pub temperature: i16,
#[doc = "Sensor ID."]
pub sensor_id: u8,
#[doc = "Optical flow quality / confidence. 0: no valid flow, 255: maximum quality."]
pub quality: u8,
}
impl HIL_OPTICAL_FLOW_DATA {
pub const ENCODED_LEN: usize = 44usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.integration_time_us = buf.get_u32_le();
_struct.integrated_x = buf.get_f32_le();
_struct.integrated_y = buf.get_f32_le();
_struct.integrated_xgyro = buf.get_f32_le();
_struct.integrated_ygyro = buf.get_f32_le();
_struct.integrated_zgyro = buf.get_f32_le();
_struct.time_delta_distance_us = buf.get_u32_le();
_struct.distance = buf.get_f32_le();
_struct.temperature = buf.get_i16_le();
_struct.sensor_id = buf.get_u8();
_struct.quality = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_u32_le(self.integration_time_us);
_tmp.put_f32_le(self.integrated_x);
_tmp.put_f32_le(self.integrated_y);
_tmp.put_f32_le(self.integrated_xgyro);
_tmp.put_f32_le(self.integrated_ygyro);
_tmp.put_f32_le(self.integrated_zgyro);
_tmp.put_u32_le(self.time_delta_distance_us);
_tmp.put_f32_le(self.distance);
_tmp.put_i16_le(self.temperature);
_tmp.put_u8(self.sensor_id);
_tmp.put_u8(self.quality);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 247"]
#[doc = "Information about a potential collision."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct COLLISION_DATA {
#[doc = "Unique identifier, domain based on src field."]
pub id: u32,
#[doc = "Estimated time until collision occurs."]
pub time_to_minimum_delta: f32,
#[doc = "Closest vertical distance between vehicle and object."]
pub altitude_minimum_delta: f32,
#[doc = "Closest horizontal distance between vehicle and object."]
pub horizontal_minimum_delta: f32,
#[doc = "Collision data source."]
pub src: MavCollisionSrc,
#[doc = "Action that is being taken to avoid this collision."]
pub action: MavCollisionAction,
#[doc = "How concerned the aircraft is about this collision."]
pub threat_level: MavCollisionThreatLevel,
}
impl COLLISION_DATA {
pub const ENCODED_LEN: usize = 19usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.id = buf.get_u32_le();
_struct.time_to_minimum_delta = buf.get_f32_le();
_struct.altitude_minimum_delta = buf.get_f32_le();
_struct.horizontal_minimum_delta = buf.get_f32_le();
let tmp = buf.get_u8();
_struct.src = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavCollisionSrc",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.action = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavCollisionAction",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.threat_level = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavCollisionThreatLevel",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.id);
_tmp.put_f32_le(self.time_to_minimum_delta);
_tmp.put_f32_le(self.altitude_minimum_delta);
_tmp.put_f32_le(self.horizontal_minimum_delta);
_tmp.put_u8(self.src as u8);
_tmp.put_u8(self.action as u8);
_tmp.put_u8(self.threat_level as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 412"]
#[doc = "Request one or more events to be (re-)sent. If first_sequence==last_sequence, only a single event is requested. Note that first_sequence can be larger than last_sequence (because the sequence number can wrap). Each sequence will trigger an EVENT or EVENT_ERROR response.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct REQUEST_EVENT_DATA {
#[doc = "First sequence number of the requested event.."]
pub first_sequence: u16,
#[doc = "Last sequence number of the requested event.."]
pub last_sequence: u16,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
}
impl REQUEST_EVENT_DATA {
pub const ENCODED_LEN: usize = 6usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.first_sequence = buf.get_u16_le();
_struct.last_sequence = buf.get_u16_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.first_sequence);
_tmp.put_u16_le(self.last_sequence);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 180"]
#[doc = "Camera Capture Feedback.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct CAMERA_FEEDBACK_DATA {
#[doc = "Image timestamp (since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB).."]
pub time_usec: u64,
#[doc = "Latitude.."]
pub lat: i32,
#[doc = "Longitude.."]
pub lng: i32,
#[doc = "Altitude (MSL).."]
pub alt_msl: f32,
#[doc = "Altitude (Relative to HOME location).."]
pub alt_rel: f32,
#[doc = "Camera Roll angle (earth frame, +-180).."]
pub roll: f32,
#[doc = "Camera Pitch angle (earth frame, +-180).."]
pub pitch: f32,
#[doc = "Camera Yaw (earth frame, 0-360, true).."]
pub yaw: f32,
#[doc = "Focal Length.."]
pub foc_len: f32,
#[doc = "Image index.."]
pub img_idx: u16,
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Camera ID.."]
pub cam_idx: u8,
#[doc = "Feedback flags.."]
pub flags: CameraFeedbackFlags,
#[doc = "Completed image captures.."]
#[cfg_attr(feature = "serde", serde(default))]
pub completed_captures: u16,
}
impl CAMERA_FEEDBACK_DATA {
pub const ENCODED_LEN: usize = 47usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.lat = buf.get_i32_le();
_struct.lng = buf.get_i32_le();
_struct.alt_msl = buf.get_f32_le();
_struct.alt_rel = buf.get_f32_le();
_struct.roll = buf.get_f32_le();
_struct.pitch = buf.get_f32_le();
_struct.yaw = buf.get_f32_le();
_struct.foc_len = buf.get_f32_le();
_struct.img_idx = buf.get_u16_le();
_struct.target_system = buf.get_u8();
_struct.cam_idx = buf.get_u8();
let tmp = buf.get_u8();
_struct.flags = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "CameraFeedbackFlags",
value: tmp as u32,
})?;
_struct.completed_captures = buf.get_u16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_i32_le(self.lat);
_tmp.put_i32_le(self.lng);
_tmp.put_f32_le(self.alt_msl);
_tmp.put_f32_le(self.alt_rel);
_tmp.put_f32_le(self.roll);
_tmp.put_f32_le(self.pitch);
_tmp.put_f32_le(self.yaw);
_tmp.put_f32_le(self.foc_len);
_tmp.put_u16_le(self.img_idx);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.cam_idx);
_tmp.put_u8(self.flags as u8);
_tmp.put_u16_le(self.completed_captures);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 216"]
#[doc = "Request a GOPRO_COMMAND response from the GoPro.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct GOPRO_GET_REQUEST_DATA {
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Component ID.."]
pub target_component: u8,
#[doc = "Command ID.."]
pub cmd_id: GoproCommand,
}
impl GOPRO_GET_REQUEST_DATA {
pub const ENCODED_LEN: usize = 3usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
let tmp = buf.get_u8();
_struct.cmd_id = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "GoproCommand",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.cmd_id as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 142"]
#[doc = "The autopilot is requesting a resource (file, binary, other type of data)."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct RESOURCE_REQUEST_DATA {
#[doc = "Request ID. This ID should be re-used when sending back URI contents."]
pub request_id: u8,
#[doc = "The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary."]
pub uri_type: u8,
#[doc = "The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum)."]
pub uri: Vec<u8, 120>,
#[doc = "The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream.."]
pub transfer_type: u8,
#[doc = "The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP).."]
pub storage: Vec<u8, 120>,
}
impl RESOURCE_REQUEST_DATA {
pub const ENCODED_LEN: usize = 243usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.request_id = buf.get_u8();
_struct.uri_type = buf.get_u8();
for _ in 0..120usize {
let val = buf.get_u8();
_struct.uri.push(val).unwrap();
}
_struct.transfer_type = buf.get_u8();
for _ in 0..120usize {
let val = buf.get_u8();
_struct.storage.push(val).unwrap();
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.request_id);
_tmp.put_u8(self.uri_type);
for val in &self.uri {
_tmp.put_u8(*val);
}
_tmp.put_u8(self.transfer_type);
for val in &self.storage {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 248"]
#[doc = "Message implementing parts of the V2 payload specs in V1 frames for transitional support.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct V2_EXTENSION_DATA {
#[doc = "A code that identifies the software component that understands this message (analogous to USB device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/definition_files/extension_message_ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.."]
pub message_type: u16,
#[doc = "Network ID (0 for broadcast)."]
pub target_network: u8,
#[doc = "System ID (0 for broadcast)."]
pub target_system: u8,
#[doc = "Component ID (0 for broadcast)."]
pub target_component: u8,
#[doc = "Variable length payload. The length must be encoded in the payload as part of the message_type protocol, e.g. by including the length as payload data, or by terminating the payload data with a non-zero marker. This is required in order to reconstruct zero-terminated payloads that are (or otherwise would be) trimmed by MAVLink 2 empty-byte truncation. The entire content of the payload block is opaque unless you understand the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the MAVLink specification.."]
pub payload: Vec<u8, 249>,
}
impl V2_EXTENSION_DATA {
pub const ENCODED_LEN: usize = 254usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.message_type = buf.get_u16_le();
_struct.target_network = buf.get_u8();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
for _ in 0..249usize {
let val = buf.get_u8();
_struct.payload.push(val).unwrap();
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.message_type);
_tmp.put_u8(self.target_network);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
for val in &self.payload {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 300"]
#[doc = "Version and capability of protocol version. This message can be requested with MAV_CMD_REQUEST_MESSAGE and is used as part of the handshaking to establish which MAVLink version should be used on the network. Every node should respond to a request for PROTOCOL_VERSION to enable the handshaking. Library implementers should consider adding this into the default decoding state machine to allow the protocol core to respond directly.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PROTOCOL_VERSION_DATA {
#[doc = "Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc.."]
pub version: u16,
#[doc = "Minimum MAVLink version supported."]
pub min_version: u16,
#[doc = "Maximum MAVLink version supported (set to the same value as version by default)."]
pub max_version: u16,
#[doc = "The first 8 bytes (not characters printed in hex!) of the git hash.."]
pub spec_version_hash: [u8; 8],
#[doc = "The first 8 bytes (not characters printed in hex!) of the git hash.."]
pub library_version_hash: [u8; 8],
}
impl PROTOCOL_VERSION_DATA {
pub const ENCODED_LEN: usize = 22usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.version = buf.get_u16_le();
_struct.min_version = buf.get_u16_le();
_struct.max_version = buf.get_u16_le();
for idx in 0..8usize {
let val = buf.get_u8();
_struct.spec_version_hash[idx] = val;
}
for idx in 0..8usize {
let val = buf.get_u8();
_struct.library_version_hash[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.version);
_tmp.put_u16_le(self.min_version);
_tmp.put_u16_le(self.max_version);
for val in &self.spec_version_hash {
_tmp.put_u8(*val);
}
for val in &self.library_version_hash {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 50"]
#[doc = "Bind a RC channel to a parameter. The parameter should change according to the RC channel value.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PARAM_MAP_RC_DATA {
#[doc = "Initial parameter value."]
pub param_value0: f32,
#[doc = "Scale, maps the RC range [-1, 1] to a parameter value."]
pub scale: f32,
#[doc = "Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)."]
pub param_value_min: f32,
#[doc = "Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation)."]
pub param_value_max: f32,
#[doc = "Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index.."]
pub param_index: i16,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string."]
pub param_id: [u8; 16],
#[doc = "Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC.."]
pub parameter_rc_channel_index: u8,
}
impl PARAM_MAP_RC_DATA {
pub const ENCODED_LEN: usize = 37usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.param_value0 = buf.get_f32_le();
_struct.scale = buf.get_f32_le();
_struct.param_value_min = buf.get_f32_le();
_struct.param_value_max = buf.get_f32_le();
_struct.param_index = buf.get_i16_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
for idx in 0..16usize {
let val = buf.get_u8();
_struct.param_id[idx] = val;
}
_struct.parameter_rc_channel_index = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.param_value0);
_tmp.put_f32_le(self.scale);
_tmp.put_f32_le(self.param_value_min);
_tmp.put_f32_le(self.param_value_max);
_tmp.put_i16_le(self.param_index);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
for val in &self.param_id {
_tmp.put_u8(*val);
}
_tmp.put_u8(self.parameter_rc_channel_index);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 333"]
#[doc = "Describe a trajectory using an array of up-to 5 bezier control points in the local frame (MAV_FRAME_LOCAL_NED).."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct TRAJECTORY_REPRESENTATION_BEZIER_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "X-coordinate of bezier control points. Set to NaN if not being used."]
pub pos_x: [f32; 5],
#[doc = "Y-coordinate of bezier control points. Set to NaN if not being used."]
pub pos_y: [f32; 5],
#[doc = "Z-coordinate of bezier control points. Set to NaN if not being used."]
pub pos_z: [f32; 5],
#[doc = "Bezier time horizon. Set to NaN if velocity/acceleration should not be incorporated."]
pub delta: [f32; 5],
#[doc = "Yaw. Set to NaN for unchanged."]
pub pos_yaw: [f32; 5],
#[doc = "Number of valid control points (up-to 5 points are possible)."]
pub valid_points: u8,
}
impl TRAJECTORY_REPRESENTATION_BEZIER_DATA {
pub const ENCODED_LEN: usize = 109usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
for idx in 0..5usize {
let val = buf.get_f32_le();
_struct.pos_x[idx] = val;
}
for idx in 0..5usize {
let val = buf.get_f32_le();
_struct.pos_y[idx] = val;
}
for idx in 0..5usize {
let val = buf.get_f32_le();
_struct.pos_z[idx] = val;
}
for idx in 0..5usize {
let val = buf.get_f32_le();
_struct.delta[idx] = val;
}
for idx in 0..5usize {
let val = buf.get_f32_le();
_struct.pos_yaw[idx] = val;
}
_struct.valid_points = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
for val in &self.pos_x {
_tmp.put_f32_le(*val);
}
for val in &self.pos_y {
_tmp.put_f32_le(*val);
}
for val in &self.pos_z {
_tmp.put_f32_le(*val);
}
for val in &self.delta {
_tmp.put_f32_le(*val);
}
for val in &self.pos_yaw {
_tmp.put_f32_le(*val);
}
_tmp.put_u8(self.valid_points);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 23"]
#[doc = "Set a parameter value (write new value to permanent storage). The receiving component should acknowledge the new parameter value by broadcasting a PARAM_VALUE message (broadcasting ensures that multiple GCS all have an up-to-date list of all parameters). If the sending GCS did not receive a PARAM_VALUE within its timeout time, it should re-send the PARAM_SET message. The parameter microservice is documented at https://mavlink.io/en/services/parameter.html. PARAM_SET may also be called within the context of a transaction (started with MAV_CMD_PARAM_TRANSACTION). Within a transaction the receiving component should respond with PARAM_ACK_TRANSACTION to the setter component (instead of broadcasting PARAM_VALUE), and PARAM_SET should be re-sent if this is ACK not received.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PARAM_SET_DATA {
#[doc = "Onboard parameter value."]
pub param_value: f32,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string."]
pub param_id: [u8; 16],
#[doc = "Onboard parameter type.."]
pub param_type: MavParamType,
}
impl PARAM_SET_DATA {
pub const ENCODED_LEN: usize = 23usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.param_value = buf.get_f32_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
for idx in 0..16usize {
let val = buf.get_u8();
_struct.param_id[idx] = val;
}
let tmp = buf.get_u8();
_struct.param_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavParamType",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.param_value);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
for val in &self.param_id {
_tmp.put_u8(*val);
}
_tmp.put_u8(self.param_type as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 42000"]
#[doc = "ICAROUS heartbeat."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct ICAROUS_HEARTBEAT_DATA {
#[doc = "See the FMS_STATE enum.."]
pub status: IcarousFmsState,
}
impl ICAROUS_HEARTBEAT_DATA {
pub const ENCODED_LEN: usize = 1usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
let tmp = buf.get_u8();
_struct.status = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "IcarousFmsState",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.status as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 182"]
#[doc = "Status of third AHRS filter if available. This is for ANU research group (Ali and Sean).."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct AHRS3_DATA {
#[doc = "Roll angle.."]
pub roll: f32,
#[doc = "Pitch angle.."]
pub pitch: f32,
#[doc = "Yaw angle.."]
pub yaw: f32,
#[doc = "Altitude (MSL).."]
pub altitude: f32,
#[doc = "Latitude.."]
pub lat: i32,
#[doc = "Longitude.."]
pub lng: i32,
#[doc = "Test variable1.."]
pub v1: f32,
#[doc = "Test variable2.."]
pub v2: f32,
#[doc = "Test variable3.."]
pub v3: f32,
#[doc = "Test variable4.."]
pub v4: f32,
}
impl AHRS3_DATA {
pub const ENCODED_LEN: usize = 40usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.roll = buf.get_f32_le();
_struct.pitch = buf.get_f32_le();
_struct.yaw = buf.get_f32_le();
_struct.altitude = buf.get_f32_le();
_struct.lat = buf.get_i32_le();
_struct.lng = buf.get_i32_le();
_struct.v1 = buf.get_f32_le();
_struct.v2 = buf.get_f32_le();
_struct.v3 = buf.get_f32_le();
_struct.v4 = buf.get_f32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.roll);
_tmp.put_f32_le(self.pitch);
_tmp.put_f32_le(self.yaw);
_tmp.put_f32_le(self.altitude);
_tmp.put_i32_le(self.lat);
_tmp.put_i32_le(self.lng);
_tmp.put_f32_le(self.v1);
_tmp.put_f32_le(self.v2);
_tmp.put_f32_le(self.v3);
_tmp.put_f32_le(self.v4);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 385"]
#[doc = "Message for transporting \"arbitrary\" variable-length data from one component to another (broadcast is not forbidden, but discouraged). The encoding of the data is usually extension specific, i.e. determined by the source, and is usually not documented as part of the MAVLink specification.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct TUNNEL_DATA {
#[doc = "A code that identifies the content of the payload (0 for unknown, which is the default). If this code is less than 32768, it is a 'registered' payload type and the corresponding code should be added to the MAV_TUNNEL_PAYLOAD_TYPE enum. Software creators can register blocks of types as needed. Codes greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.."]
pub payload_type: MavTunnelPayloadType,
#[doc = "System ID (can be 0 for broadcast, but this is discouraged)."]
pub target_system: u8,
#[doc = "Component ID (can be 0 for broadcast, but this is discouraged)."]
pub target_component: u8,
#[doc = "Length of the data transported in payload."]
pub payload_length: u8,
#[doc = "Variable length payload. The payload length is defined by payload_length. The entire content of this block is opaque unless you understand the encoding specified by payload_type.."]
pub payload: Vec<u8, 128>,
}
impl TUNNEL_DATA {
pub const ENCODED_LEN: usize = 133usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
let tmp = buf.get_u16_le();
_struct.payload_type = FromPrimitive::from_u16(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavTunnelPayloadType",
value: tmp as u32,
})?;
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
_struct.payload_length = buf.get_u8();
for _ in 0..128usize {
let val = buf.get_u8();
_struct.payload.push(val).unwrap();
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.payload_type as u16);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.payload_length);
for val in &self.payload {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 11039"]
#[doc = "The MCU status, giving MCU temperature and voltage. The min and max voltages are to allow for detecting power supply instability.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct MCU_STATUS_DATA {
#[doc = "MCU Internal temperature."]
pub MCU_temperature: i16,
#[doc = "MCU voltage."]
pub MCU_voltage: u16,
#[doc = "MCU voltage minimum."]
pub MCU_voltage_min: u16,
#[doc = "MCU voltage maximum."]
pub MCU_voltage_max: u16,
#[doc = "MCU instance."]
pub id: u8,
}
impl MCU_STATUS_DATA {
pub const ENCODED_LEN: usize = 9usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.MCU_temperature = buf.get_i16_le();
_struct.MCU_voltage = buf.get_u16_le();
_struct.MCU_voltage_min = buf.get_u16_le();
_struct.MCU_voltage_max = buf.get_u16_le();
_struct.id = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_i16_le(self.MCU_temperature);
_tmp.put_u16_le(self.MCU_voltage);
_tmp.put_u16_le(self.MCU_voltage_min);
_tmp.put_u16_le(self.MCU_voltage_max);
_tmp.put_u8(self.id);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 410"]
#[doc = "Event message. Each new event from a particular component gets a new sequence number. The same message might be sent multiple times if (re-)requested. Most events are broadcast, some can be specific to a target component (as receivers keep track of the sequence for missed events, all events need to be broadcast. Thus we use destination_component instead of target_component).."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct EVENT_DATA {
#[doc = "Event ID (as defined in the component metadata)."]
pub id: u32,
#[doc = "Timestamp (time since system boot when the event happened).."]
pub event_time_boot_ms: u32,
#[doc = "Sequence number.."]
pub sequence: u16,
#[doc = "Component ID."]
pub destination_component: u8,
#[doc = "System ID."]
pub destination_system: u8,
#[doc = "Log levels: 4 bits MSB: internal (for logging purposes), 4 bits LSB: external. Levels: Emergency = 0, Alert = 1, Critical = 2, Error = 3, Warning = 4, Notice = 5, Info = 6, Debug = 7, Protocol = 8, Disabled = 9."]
pub log_levels: u8,
#[doc = "Arguments (depend on event ID).."]
pub arguments: Vec<u8, 40>,
}
impl EVENT_DATA {
pub const ENCODED_LEN: usize = 53usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.id = buf.get_u32_le();
_struct.event_time_boot_ms = buf.get_u32_le();
_struct.sequence = buf.get_u16_le();
_struct.destination_component = buf.get_u8();
_struct.destination_system = buf.get_u8();
_struct.log_levels = buf.get_u8();
for _ in 0..40usize {
let val = buf.get_u8();
_struct.arguments.push(val).unwrap();
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.id);
_tmp.put_u32_le(self.event_time_boot_ms);
_tmp.put_u16_le(self.sequence);
_tmp.put_u8(self.destination_component);
_tmp.put_u8(self.destination_system);
_tmp.put_u8(self.log_levels);
for val in &self.arguments {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 126"]
#[doc = "Control a serial port. This can be used for raw access to an onboard serial peripheral such as a GPS or telemetry radio. It is designed to make it possible to update the devices firmware via MAVLink messages or change the devices settings. A message with zero bytes can be used to change just the baudrate.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct SERIAL_CONTROL_DATA {
#[doc = "Baudrate of transfer. Zero means no change.."]
pub baudrate: u32,
#[doc = "Timeout for reply data."]
pub timeout: u16,
#[doc = "Serial control device type.."]
pub device: SerialControlDev,
#[doc = "Bitmap of serial control flags.."]
pub flags: SerialControlFlag,
#[doc = "how many bytes in this transfer."]
pub count: u8,
#[doc = "serial data."]
pub data: Vec<u8, 70>,
#[doc = "System ID."]
#[cfg_attr(feature = "serde", serde(default))]
pub target_system: u8,
#[doc = "Component ID."]
#[cfg_attr(feature = "serde", serde(default))]
pub target_component: u8,
}
impl SERIAL_CONTROL_DATA {
pub const ENCODED_LEN: usize = 81usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.baudrate = buf.get_u32_le();
_struct.timeout = buf.get_u16_le();
let tmp = buf.get_u8();
_struct.device = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "SerialControlDev",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.flags = SerialControlFlag::from_bits(tmp & SerialControlFlag::all().bits()).ok_or(
ParserError::InvalidFlag {
flag_type: "SerialControlFlag",
value: tmp as u32,
},
)?;
_struct.count = buf.get_u8();
for _ in 0..70usize {
let val = buf.get_u8();
_struct.data.push(val).unwrap();
}
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.baudrate);
_tmp.put_u16_le(self.timeout);
_tmp.put_u8(self.device as u8);
_tmp.put_u8(self.flags.bits());
_tmp.put_u8(self.count);
for val in &self.data {
_tmp.put_u8(*val);
}
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 7"]
#[doc = "Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct AUTH_KEY_DATA {
#[doc = "key."]
pub key: [u8; 32],
}
impl AUTH_KEY_DATA {
pub const ENCODED_LEN: usize = 32usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
for idx in 0..32usize {
let val = buf.get_u8();
_struct.key[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
for val in &self.key {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 246"]
#[doc = "The location and information of an ADSB vehicle."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct ADSB_VEHICLE_DATA {
#[doc = "ICAO address."]
pub ICAO_address: u32,
#[doc = "Latitude."]
pub lat: i32,
#[doc = "Longitude."]
pub lon: i32,
#[doc = "Altitude(ASL)."]
pub altitude: i32,
#[doc = "Course over ground."]
pub heading: u16,
#[doc = "The horizontal velocity."]
pub hor_velocity: u16,
#[doc = "The vertical velocity. Positive is up."]
pub ver_velocity: i16,
#[doc = "Bitmap to indicate various statuses including valid data fields."]
pub flags: AdsbFlags,
#[doc = "Squawk code."]
pub squawk: u16,
#[doc = "ADSB altitude type.."]
pub altitude_type: AdsbAltitudeType,
#[doc = "The callsign, 8+null."]
pub callsign: [u8; 9],
#[doc = "ADSB emitter type.."]
pub emitter_type: AdsbEmitterType,
#[doc = "Time since last communication in seconds."]
pub tslc: u8,
}
impl ADSB_VEHICLE_DATA {
pub const ENCODED_LEN: usize = 38usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.ICAO_address = buf.get_u32_le();
_struct.lat = buf.get_i32_le();
_struct.lon = buf.get_i32_le();
_struct.altitude = buf.get_i32_le();
_struct.heading = buf.get_u16_le();
_struct.hor_velocity = buf.get_u16_le();
_struct.ver_velocity = buf.get_i16_le();
let tmp = buf.get_u16_le();
_struct.flags = AdsbFlags::from_bits(tmp & AdsbFlags::all().bits()).ok_or(
ParserError::InvalidFlag {
flag_type: "AdsbFlags",
value: tmp as u32,
},
)?;
_struct.squawk = buf.get_u16_le();
let tmp = buf.get_u8();
_struct.altitude_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "AdsbAltitudeType",
value: tmp as u32,
})?;
for idx in 0..9usize {
let val = buf.get_u8();
_struct.callsign[idx] = val;
}
let tmp = buf.get_u8();
_struct.emitter_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "AdsbEmitterType",
value: tmp as u32,
})?;
_struct.tslc = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.ICAO_address);
_tmp.put_i32_le(self.lat);
_tmp.put_i32_le(self.lon);
_tmp.put_i32_le(self.altitude);
_tmp.put_u16_le(self.heading);
_tmp.put_u16_le(self.hor_velocity);
_tmp.put_i16_le(self.ver_velocity);
_tmp.put_u16_le(self.flags.bits());
_tmp.put_u16_le(self.squawk);
_tmp.put_u8(self.altitude_type as u8);
for val in &self.callsign {
_tmp.put_u8(*val);
}
_tmp.put_u8(self.emitter_type as u8);
_tmp.put_u8(self.tslc);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 84"]
#[doc = "Sets a desired vehicle position in a local north-east-down coordinate frame. Used by an external controller to command the vehicle (manual controller or other system).."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct SET_POSITION_TARGET_LOCAL_NED_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "X Position in NED frame."]
pub x: f32,
#[doc = "Y Position in NED frame."]
pub y: f32,
#[doc = "Z Position in NED frame (note, altitude is negative in NED)."]
pub z: f32,
#[doc = "X velocity in NED frame."]
pub vx: f32,
#[doc = "Y velocity in NED frame."]
pub vy: f32,
#[doc = "Z velocity in NED frame."]
pub vz: f32,
#[doc = "X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N."]
pub afx: f32,
#[doc = "Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N."]
pub afy: f32,
#[doc = "Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N."]
pub afz: f32,
#[doc = "yaw setpoint."]
pub yaw: f32,
#[doc = "yaw rate setpoint."]
pub yaw_rate: f32,
#[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle.."]
pub type_mask: PositionTargetTypemask,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9."]
pub coordinate_frame: MavFrame,
}
impl SET_POSITION_TARGET_LOCAL_NED_DATA {
pub const ENCODED_LEN: usize = 53usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.x = buf.get_f32_le();
_struct.y = buf.get_f32_le();
_struct.z = buf.get_f32_le();
_struct.vx = buf.get_f32_le();
_struct.vy = buf.get_f32_le();
_struct.vz = buf.get_f32_le();
_struct.afx = buf.get_f32_le();
_struct.afy = buf.get_f32_le();
_struct.afz = buf.get_f32_le();
_struct.yaw = buf.get_f32_le();
_struct.yaw_rate = buf.get_f32_le();
let tmp = buf.get_u16_le();
_struct.type_mask = PositionTargetTypemask::from_bits(
tmp & PositionTargetTypemask::all().bits(),
)
.ok_or(ParserError::InvalidFlag {
flag_type: "PositionTargetTypemask",
value: tmp as u32,
})?;
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
let tmp = buf.get_u8();
_struct.coordinate_frame = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavFrame",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_f32_le(self.x);
_tmp.put_f32_le(self.y);
_tmp.put_f32_le(self.z);
_tmp.put_f32_le(self.vx);
_tmp.put_f32_le(self.vy);
_tmp.put_f32_le(self.vz);
_tmp.put_f32_le(self.afx);
_tmp.put_f32_le(self.afy);
_tmp.put_f32_le(self.afz);
_tmp.put_f32_le(self.yaw);
_tmp.put_f32_le(self.yaw_rate);
_tmp.put_u16_le(self.type_mask.bits());
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.coordinate_frame as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 232"]
#[doc = "GPS sensor input message. This is a raw sensor value sent by the GPS. This is NOT the global position estimate of the system.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct GPS_INPUT_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "GPS time (from start of GPS week)."]
pub time_week_ms: u32,
#[doc = "Latitude (WGS84)."]
pub lat: i32,
#[doc = "Longitude (WGS84)."]
pub lon: i32,
#[doc = "Altitude (MSL). Positive for up.."]
pub alt: f32,
#[doc = "GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX."]
pub hdop: f32,
#[doc = "GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX."]
pub vdop: f32,
#[doc = "GPS velocity in north direction in earth-fixed NED frame."]
pub vn: f32,
#[doc = "GPS velocity in east direction in earth-fixed NED frame."]
pub ve: f32,
#[doc = "GPS velocity in down direction in earth-fixed NED frame."]
pub vd: f32,
#[doc = "GPS speed accuracy."]
pub speed_accuracy: f32,
#[doc = "GPS horizontal accuracy."]
pub horiz_accuracy: f32,
#[doc = "GPS vertical accuracy."]
pub vert_accuracy: f32,
#[doc = "Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided.."]
pub ignore_flags: GpsInputIgnoreFlags,
#[doc = "GPS week number."]
pub time_week: u16,
#[doc = "ID of the GPS for multiple GPS inputs."]
pub gps_id: u8,
#[doc = "0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK."]
pub fix_type: u8,
#[doc = "Number of satellites visible.."]
pub satellites_visible: u8,
#[doc = "Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north."]
#[cfg_attr(feature = "serde", serde(default))]
pub yaw: u16,
}
impl GPS_INPUT_DATA {
pub const ENCODED_LEN: usize = 65usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.time_week_ms = buf.get_u32_le();
_struct.lat = buf.get_i32_le();
_struct.lon = buf.get_i32_le();
_struct.alt = buf.get_f32_le();
_struct.hdop = buf.get_f32_le();
_struct.vdop = buf.get_f32_le();
_struct.vn = buf.get_f32_le();
_struct.ve = buf.get_f32_le();
_struct.vd = buf.get_f32_le();
_struct.speed_accuracy = buf.get_f32_le();
_struct.horiz_accuracy = buf.get_f32_le();
_struct.vert_accuracy = buf.get_f32_le();
let tmp = buf.get_u16_le();
_struct.ignore_flags = GpsInputIgnoreFlags::from_bits(
tmp & GpsInputIgnoreFlags::all().bits(),
)
.ok_or(ParserError::InvalidFlag {
flag_type: "GpsInputIgnoreFlags",
value: tmp as u32,
})?;
_struct.time_week = buf.get_u16_le();
_struct.gps_id = buf.get_u8();
_struct.fix_type = buf.get_u8();
_struct.satellites_visible = buf.get_u8();
_struct.yaw = buf.get_u16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_u32_le(self.time_week_ms);
_tmp.put_i32_le(self.lat);
_tmp.put_i32_le(self.lon);
_tmp.put_f32_le(self.alt);
_tmp.put_f32_le(self.hdop);
_tmp.put_f32_le(self.vdop);
_tmp.put_f32_le(self.vn);
_tmp.put_f32_le(self.ve);
_tmp.put_f32_le(self.vd);
_tmp.put_f32_le(self.speed_accuracy);
_tmp.put_f32_le(self.horiz_accuracy);
_tmp.put_f32_le(self.vert_accuracy);
_tmp.put_u16_le(self.ignore_flags.bits());
_tmp.put_u16_le(self.time_week);
_tmp.put_u8(self.gps_id);
_tmp.put_u8(self.fix_type);
_tmp.put_u8(self.satellites_visible);
_tmp.put_u16_le(self.yaw);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 244"]
#[doc = "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). \tIt may also be sent in response to MAV_CMD_GET_MESSAGE_INTERVAL. \tThis interface replaces DATA_STREAM.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct MESSAGE_INTERVAL_DATA {
#[doc = "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.."]
pub interval_us: i32,
#[doc = "The ID of the requested MAVLink message. v1.0 is limited to 254 messages.."]
pub message_id: u16,
}
impl MESSAGE_INTERVAL_DATA {
pub const ENCODED_LEN: usize = 6usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.interval_us = buf.get_i32_le();
_struct.message_id = buf.get_u16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_i32_le(self.interval_us);
_tmp.put_u16_le(self.message_id);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 267"]
#[doc = "A message containing logged data which requires a LOGGING_ACK to be sent back."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct LOGGING_DATA_ACKED_DATA {
#[doc = "sequence number (can wrap)."]
pub sequence: u16,
#[doc = "system ID of the target."]
pub target_system: u8,
#[doc = "component ID of the target."]
pub target_component: u8,
#[doc = "data length."]
pub length: u8,
#[doc = "offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to UINT8_MAX if no start exists).."]
pub first_message_offset: u8,
#[doc = "logged data."]
pub data: Vec<u8, 249>,
}
impl LOGGING_DATA_ACKED_DATA {
pub const ENCODED_LEN: usize = 255usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.sequence = buf.get_u16_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
_struct.length = buf.get_u8();
_struct.first_message_offset = buf.get_u8();
for _ in 0..249usize {
let val = buf.get_u8();
_struct.data.push(val).unwrap();
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.sequence);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.length);
_tmp.put_u8(self.first_message_offset);
for val in &self.data {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 50002"]
#[doc = "Information about video stream."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct HERELINK_VIDEO_STREAM_INFORMATION_DATA {
#[doc = "Frame rate.."]
pub framerate: f32,
#[doc = "Bit rate.."]
pub bitrate: u32,
#[doc = "Horizontal resolution.."]
pub resolution_h: u16,
#[doc = "Vertical resolution.."]
pub resolution_v: u16,
#[doc = "Video image rotation clockwise.."]
pub rotation: u16,
#[doc = "Video Stream ID (1 for first, 2 for second, etc.)."]
pub camera_id: u8,
#[doc = "Number of streams available.."]
pub status: u8,
#[doc = "Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to).."]
pub uri: Vec<u8, 230>,
}
impl HERELINK_VIDEO_STREAM_INFORMATION_DATA {
pub const ENCODED_LEN: usize = 246usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.framerate = buf.get_f32_le();
_struct.bitrate = buf.get_u32_le();
_struct.resolution_h = buf.get_u16_le();
_struct.resolution_v = buf.get_u16_le();
_struct.rotation = buf.get_u16_le();
_struct.camera_id = buf.get_u8();
_struct.status = buf.get_u8();
for _ in 0..230usize {
let val = buf.get_u8();
_struct.uri.push(val).unwrap();
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.framerate);
_tmp.put_u32_le(self.bitrate);
_tmp.put_u16_le(self.resolution_h);
_tmp.put_u16_le(self.resolution_v);
_tmp.put_u16_le(self.rotation);
_tmp.put_u8(self.camera_id);
_tmp.put_u8(self.status);
for val in &self.uri {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 151"]
#[doc = "Set the magnetometer offsets."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct SET_MAG_OFFSETS_DATA {
#[doc = "Magnetometer X offset.."]
pub mag_ofs_x: i16,
#[doc = "Magnetometer Y offset.."]
pub mag_ofs_y: i16,
#[doc = "Magnetometer Z offset.."]
pub mag_ofs_z: i16,
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Component ID.."]
pub target_component: u8,
}
impl SET_MAG_OFFSETS_DATA {
pub const ENCODED_LEN: usize = 8usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.mag_ofs_x = buf.get_i16_le();
_struct.mag_ofs_y = buf.get_i16_le();
_struct.mag_ofs_z = buf.get_i16_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_i16_le(self.mag_ofs_x);
_tmp.put_i16_le(self.mag_ofs_y);
_tmp.put_i16_le(self.mag_ofs_z);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 130"]
#[doc = "Handshake message to initiate, control and stop image streaming when using the Image Transmission Protocol: https://mavlink.io/en/services/image_transmission.html.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct DATA_TRANSMISSION_HANDSHAKE_DATA {
#[doc = "total data size (set on ACK only).."]
pub size: u32,
#[doc = "Width of a matrix or image.."]
pub width: u16,
#[doc = "Height of a matrix or image.."]
pub height: u16,
#[doc = "Number of packets being sent (set on ACK only).."]
pub packets: u16,
#[doc = "Type of requested/acknowledged data.."]
pub mavtype: MavlinkDataStreamType,
#[doc = "Payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only).."]
pub payload: u8,
#[doc = "JPEG quality. Values: [1-100].."]
pub jpg_quality: u8,
}
impl DATA_TRANSMISSION_HANDSHAKE_DATA {
pub const ENCODED_LEN: usize = 13usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.size = buf.get_u32_le();
_struct.width = buf.get_u16_le();
_struct.height = buf.get_u16_le();
_struct.packets = buf.get_u16_le();
let tmp = buf.get_u8();
_struct.mavtype = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavlinkDataStreamType",
value: tmp as u32,
})?;
_struct.payload = buf.get_u8();
_struct.jpg_quality = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.size);
_tmp.put_u16_le(self.width);
_tmp.put_u16_le(self.height);
_tmp.put_u16_le(self.packets);
_tmp.put_u8(self.mavtype as u8);
_tmp.put_u8(self.payload);
_tmp.put_u8(self.jpg_quality);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 91"]
#[doc = "Sent from autopilot to simulation. Hardware in the loop control outputs."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct HIL_CONTROLS_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "Control output -1 .. 1."]
pub roll_ailerons: f32,
#[doc = "Control output -1 .. 1."]
pub pitch_elevator: f32,
#[doc = "Control output -1 .. 1."]
pub yaw_rudder: f32,
#[doc = "Throttle 0 .. 1."]
pub throttle: f32,
#[doc = "Aux 1, -1 .. 1."]
pub aux1: f32,
#[doc = "Aux 2, -1 .. 1."]
pub aux2: f32,
#[doc = "Aux 3, -1 .. 1."]
pub aux3: f32,
#[doc = "Aux 4, -1 .. 1."]
pub aux4: f32,
#[doc = "System mode.."]
pub mode: MavMode,
#[doc = "Navigation mode (MAV_NAV_MODE)."]
pub nav_mode: u8,
}
impl HIL_CONTROLS_DATA {
pub const ENCODED_LEN: usize = 42usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.roll_ailerons = buf.get_f32_le();
_struct.pitch_elevator = buf.get_f32_le();
_struct.yaw_rudder = buf.get_f32_le();
_struct.throttle = buf.get_f32_le();
_struct.aux1 = buf.get_f32_le();
_struct.aux2 = buf.get_f32_le();
_struct.aux3 = buf.get_f32_le();
_struct.aux4 = buf.get_f32_le();
let tmp = buf.get_u8();
_struct.mode = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavMode",
value: tmp as u32,
})?;
_struct.nav_mode = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_f32_le(self.roll_ailerons);
_tmp.put_f32_le(self.pitch_elevator);
_tmp.put_f32_le(self.yaw_rudder);
_tmp.put_f32_le(self.throttle);
_tmp.put_f32_le(self.aux1);
_tmp.put_f32_le(self.aux2);
_tmp.put_f32_le(self.aux3);
_tmp.put_f32_le(self.aux4);
_tmp.put_u8(self.mode as u8);
_tmp.put_u8(self.nav_mode);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 173"]
#[doc = "Rangefinder reporting.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct RANGEFINDER_DATA {
#[doc = "Distance.."]
pub distance: f32,
#[doc = "Raw voltage if available, zero otherwise.."]
pub voltage: f32,
}
impl RANGEFINDER_DATA {
pub const ENCODED_LEN: usize = 8usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.distance = buf.get_f32_le();
_struct.voltage = buf.get_f32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.distance);
_tmp.put_f32_le(self.voltage);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 10003"]
#[doc = "Transceiver heartbeat with health report (updated every 10s)."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA {
#[doc = "ADS-B transponder messages."]
pub rfHealth: UavionixAdsbRfHealth,
}
impl UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA {
pub const ENCODED_LEN: usize = 1usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
let tmp = buf.get_u8();
_struct.rfHealth = UavionixAdsbRfHealth::from_bits(
tmp & UavionixAdsbRfHealth::all().bits(),
)
.ok_or(ParserError::InvalidFlag {
flag_type: "UavionixAdsbRfHealth",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.rfHealth.bits());
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 268"]
#[doc = "An ack for a LOGGING_DATA_ACKED message."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct LOGGING_ACK_DATA {
#[doc = "sequence number (must match the one in LOGGING_DATA_ACKED)."]
pub sequence: u16,
#[doc = "system ID of the target."]
pub target_system: u8,
#[doc = "component ID of the target."]
pub target_component: u8,
}
impl LOGGING_ACK_DATA {
pub const ENCODED_LEN: usize = 4usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.sequence = buf.get_u16_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.sequence);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 55"]
#[doc = "Read out the safety zone the MAV currently assumes.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct SAFETY_ALLOWED_AREA_DATA {
#[doc = "x position 1 / Latitude 1."]
pub p1x: f32,
#[doc = "y position 1 / Longitude 1."]
pub p1y: f32,
#[doc = "z position 1 / Altitude 1."]
pub p1z: f32,
#[doc = "x position 2 / Latitude 2."]
pub p2x: f32,
#[doc = "y position 2 / Longitude 2."]
pub p2y: f32,
#[doc = "z position 2 / Altitude 2."]
pub p2z: f32,
#[doc = "Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.."]
pub frame: MavFrame,
}
impl SAFETY_ALLOWED_AREA_DATA {
pub const ENCODED_LEN: usize = 25usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.p1x = buf.get_f32_le();
_struct.p1y = buf.get_f32_le();
_struct.p1z = buf.get_f32_le();
_struct.p2x = buf.get_f32_le();
_struct.p2y = buf.get_f32_le();
_struct.p2z = buf.get_f32_le();
let tmp = buf.get_u8();
_struct.frame = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavFrame",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.p1x);
_tmp.put_f32_le(self.p1y);
_tmp.put_f32_le(self.p1z);
_tmp.put_f32_le(self.p2x);
_tmp.put_f32_le(self.p2y);
_tmp.put_f32_le(self.p2z);
_tmp.put_u8(self.frame as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 387"]
#[doc = "A forwarded CANFD frame as requested by MAV_CMD_CAN_FORWARD. These are separated from CAN_FRAME as they need different handling (eg. TAO handling)."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct CANFD_FRAME_DATA {
#[doc = "Frame ID."]
pub id: u32,
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Component ID.."]
pub target_component: u8,
#[doc = "bus number."]
pub bus: u8,
#[doc = "Frame length."]
pub len: u8,
#[doc = "Frame data."]
pub data: Vec<u8, 64>,
}
impl CANFD_FRAME_DATA {
pub const ENCODED_LEN: usize = 72usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.id = buf.get_u32_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
_struct.bus = buf.get_u8();
_struct.len = buf.get_u8();
for _ in 0..64usize {
let val = buf.get_u8();
_struct.data.push(val).unwrap();
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.id);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.bus);
_tmp.put_u8(self.len);
for val in &self.data {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 43"]
#[doc = "Request the overall list of mission items from the system/component.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct MISSION_REQUEST_LIST_DATA {
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "Mission type.."]
#[cfg_attr(feature = "serde", serde(default))]
pub mission_type: MavMissionType,
}
impl MISSION_REQUEST_LIST_DATA {
pub const ENCODED_LEN: usize = 3usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
let tmp = buf.get_u8();
_struct.mission_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavMissionType",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.mission_type as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 86"]
#[doc = "Sets a desired vehicle position, velocity, and/or acceleration in a global coordinate system (WGS84). Used by an external controller to command the vehicle (manual controller or other system).."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct SET_POSITION_TARGET_GLOBAL_INT_DATA {
#[doc = "Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.."]
pub time_boot_ms: u32,
#[doc = "X Position in WGS84 frame."]
pub lat_int: i32,
#[doc = "Y Position in WGS84 frame."]
pub lon_int: i32,
#[doc = "Altitude (MSL, Relative to home, or AGL - depending on frame)."]
pub alt: f32,
#[doc = "X velocity in NED frame."]
pub vx: f32,
#[doc = "Y velocity in NED frame."]
pub vy: f32,
#[doc = "Z velocity in NED frame."]
pub vz: f32,
#[doc = "X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N."]
pub afx: f32,
#[doc = "Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N."]
pub afy: f32,
#[doc = "Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N."]
pub afz: f32,
#[doc = "yaw setpoint."]
pub yaw: f32,
#[doc = "yaw rate setpoint."]
pub yaw_rate: f32,
#[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle.."]
pub type_mask: PositionTargetTypemask,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11."]
pub coordinate_frame: MavFrame,
}
impl SET_POSITION_TARGET_GLOBAL_INT_DATA {
pub const ENCODED_LEN: usize = 53usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.lat_int = buf.get_i32_le();
_struct.lon_int = buf.get_i32_le();
_struct.alt = buf.get_f32_le();
_struct.vx = buf.get_f32_le();
_struct.vy = buf.get_f32_le();
_struct.vz = buf.get_f32_le();
_struct.afx = buf.get_f32_le();
_struct.afy = buf.get_f32_le();
_struct.afz = buf.get_f32_le();
_struct.yaw = buf.get_f32_le();
_struct.yaw_rate = buf.get_f32_le();
let tmp = buf.get_u16_le();
_struct.type_mask = PositionTargetTypemask::from_bits(
tmp & PositionTargetTypemask::all().bits(),
)
.ok_or(ParserError::InvalidFlag {
flag_type: "PositionTargetTypemask",
value: tmp as u32,
})?;
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
let tmp = buf.get_u8();
_struct.coordinate_frame = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavFrame",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_i32_le(self.lat_int);
_tmp.put_i32_le(self.lon_int);
_tmp.put_f32_le(self.alt);
_tmp.put_f32_le(self.vx);
_tmp.put_f32_le(self.vy);
_tmp.put_f32_le(self.vz);
_tmp.put_f32_le(self.afx);
_tmp.put_f32_le(self.afy);
_tmp.put_f32_le(self.afz);
_tmp.put_f32_le(self.yaw);
_tmp.put_f32_le(self.yaw_rate);
_tmp.put_u16_le(self.type_mask.bits());
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.coordinate_frame as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 263"]
#[doc = "Information about a captured image. This is emitted every time a message is captured. MAV_CMD_REQUEST_MESSAGE can be used to (re)request this message for a specific sequence number or range of sequence numbers: MAV_CMD_REQUEST_MESSAGE.param2 indicates the sequence number the first image to send, or set to -1 to send the message for all sequence numbers. MAV_CMD_REQUEST_MESSAGE.param3 is used to specify a range of messages to send: set to 0 (default) to send just the the message for the sequence number in param 2, set to -1 to send the message for the sequence number in param 2 and all the following sequence numbers, set to the sequence number of the final message in the range.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct CAMERA_IMAGE_CAPTURED_DATA {
#[doc = "Timestamp (time since UNIX epoch) in UTC. 0 for unknown.."]
pub time_utc: u64,
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "Latitude where image was taken."]
pub lat: i32,
#[doc = "Longitude where capture was taken."]
pub lon: i32,
#[doc = "Altitude (MSL) where image was taken."]
pub alt: i32,
#[doc = "Altitude above ground."]
pub relative_alt: i32,
#[doc = "Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)."]
pub q: [f32; 4],
#[doc = "Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1)."]
pub image_index: i32,
#[doc = "Deprecated/unused. Component IDs are used to differentiate multiple cameras.."]
pub camera_id: u8,
#[doc = "Boolean indicating success (1) or failure (0) while capturing this image.."]
pub capture_result: i8,
#[doc = "URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface.."]
pub file_url: Vec<u8, 205>,
}
impl CAMERA_IMAGE_CAPTURED_DATA {
pub const ENCODED_LEN: usize = 255usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_utc = buf.get_u64_le();
_struct.time_boot_ms = buf.get_u32_le();
_struct.lat = buf.get_i32_le();
_struct.lon = buf.get_i32_le();
_struct.alt = buf.get_i32_le();
_struct.relative_alt = buf.get_i32_le();
for idx in 0..4usize {
let val = buf.get_f32_le();
_struct.q[idx] = val;
}
_struct.image_index = buf.get_i32_le();
_struct.camera_id = buf.get_u8();
_struct.capture_result = buf.get_i8();
for _ in 0..205usize {
let val = buf.get_u8();
_struct.file_url.push(val).unwrap();
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_utc);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_i32_le(self.lat);
_tmp.put_i32_le(self.lon);
_tmp.put_i32_le(self.alt);
_tmp.put_i32_le(self.relative_alt);
for val in &self.q {
_tmp.put_f32_le(*val);
}
_tmp.put_i32_le(self.image_index);
_tmp.put_u8(self.camera_id);
_tmp.put_i8(self.capture_result);
for val in &self.file_url {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 75"]
#[doc = "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."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct COMMAND_INT_DATA {
#[doc = "PARAM1, see MAV_CMD enum."]
pub param1: f32,
#[doc = "PARAM2, see MAV_CMD enum."]
pub param2: f32,
#[doc = "PARAM3, see MAV_CMD enum."]
pub param3: f32,
#[doc = "PARAM4, see MAV_CMD enum."]
pub param4: f32,
#[doc = "PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7."]
pub x: i32,
#[doc = "PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7."]
pub y: i32,
#[doc = "PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame).."]
pub z: f32,
#[doc = "The scheduled action for the mission item.."]
pub command: MavCmd,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "The coordinate system of the COMMAND.."]
pub frame: MavFrame,
#[doc = "Not used.."]
pub current: u8,
#[doc = "Not used (set 0).."]
pub autocontinue: u8,
}
impl COMMAND_INT_DATA {
pub const ENCODED_LEN: usize = 35usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.param1 = buf.get_f32_le();
_struct.param2 = buf.get_f32_le();
_struct.param3 = buf.get_f32_le();
_struct.param4 = buf.get_f32_le();
_struct.x = buf.get_i32_le();
_struct.y = buf.get_i32_le();
_struct.z = buf.get_f32_le();
let tmp = buf.get_u16_le();
_struct.command = FromPrimitive::from_u16(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavCmd",
value: tmp as u32,
})?;
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
let tmp = buf.get_u8();
_struct.frame = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavFrame",
value: tmp as u32,
})?;
_struct.current = buf.get_u8();
_struct.autocontinue = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.param1);
_tmp.put_f32_le(self.param2);
_tmp.put_f32_le(self.param3);
_tmp.put_f32_le(self.param4);
_tmp.put_i32_le(self.x);
_tmp.put_i32_le(self.y);
_tmp.put_f32_le(self.z);
_tmp.put_u16_le(self.command as u16);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.frame as u8);
_tmp.put_u8(self.current);
_tmp.put_u8(self.autocontinue);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 170"]
#[doc = "Data packet, size 32.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct DATA32_DATA {
#[doc = "Data type.."]
pub mavtype: u8,
#[doc = "Data length.."]
pub len: u8,
#[doc = "Raw data.."]
pub data: [u8; 32],
}
impl DATA32_DATA {
pub const ENCODED_LEN: usize = 34usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.mavtype = buf.get_u8();
_struct.len = buf.get_u8();
for idx in 0..32usize {
let val = buf.get_u8();
_struct.data[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.mavtype);
_tmp.put_u8(self.len);
for val in &self.data {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 33"]
#[doc = "The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct GLOBAL_POSITION_INT_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "Latitude, expressed."]
pub lat: i32,
#[doc = "Longitude, expressed."]
pub lon: i32,
#[doc = "Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL.."]
pub alt: i32,
#[doc = "Altitude above ground."]
pub relative_alt: i32,
#[doc = "Ground X Speed (Latitude, positive north)."]
pub vx: i16,
#[doc = "Ground Y Speed (Longitude, positive east)."]
pub vy: i16,
#[doc = "Ground Z Speed (Altitude, positive down)."]
pub vz: i16,
#[doc = "Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX."]
pub hdg: u16,
}
impl GLOBAL_POSITION_INT_DATA {
pub const ENCODED_LEN: usize = 28usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.lat = buf.get_i32_le();
_struct.lon = buf.get_i32_le();
_struct.alt = buf.get_i32_le();
_struct.relative_alt = buf.get_i32_le();
_struct.vx = buf.get_i16_le();
_struct.vy = buf.get_i16_le();
_struct.vz = buf.get_i16_le();
_struct.hdg = buf.get_u16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_i32_le(self.lat);
_tmp.put_i32_le(self.lon);
_tmp.put_i32_le(self.alt);
_tmp.put_i32_le(self.relative_alt);
_tmp.put_i16_le(self.vx);
_tmp.put_i16_le(self.vy);
_tmp.put_i16_le(self.vz);
_tmp.put_u16_le(self.hdg);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 92"]
#[doc = "Sent from simulation to autopilot. The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct HIL_RC_INPUTS_RAW_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "RC channel 1 value."]
pub chan1_raw: u16,
#[doc = "RC channel 2 value."]
pub chan2_raw: u16,
#[doc = "RC channel 3 value."]
pub chan3_raw: u16,
#[doc = "RC channel 4 value."]
pub chan4_raw: u16,
#[doc = "RC channel 5 value."]
pub chan5_raw: u16,
#[doc = "RC channel 6 value."]
pub chan6_raw: u16,
#[doc = "RC channel 7 value."]
pub chan7_raw: u16,
#[doc = "RC channel 8 value."]
pub chan8_raw: u16,
#[doc = "RC channel 9 value."]
pub chan9_raw: u16,
#[doc = "RC channel 10 value."]
pub chan10_raw: u16,
#[doc = "RC channel 11 value."]
pub chan11_raw: u16,
#[doc = "RC channel 12 value."]
pub chan12_raw: u16,
#[doc = "Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown.."]
pub rssi: u8,
}
impl HIL_RC_INPUTS_RAW_DATA {
pub const ENCODED_LEN: usize = 33usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.chan1_raw = buf.get_u16_le();
_struct.chan2_raw = buf.get_u16_le();
_struct.chan3_raw = buf.get_u16_le();
_struct.chan4_raw = buf.get_u16_le();
_struct.chan5_raw = buf.get_u16_le();
_struct.chan6_raw = buf.get_u16_le();
_struct.chan7_raw = buf.get_u16_le();
_struct.chan8_raw = buf.get_u16_le();
_struct.chan9_raw = buf.get_u16_le();
_struct.chan10_raw = buf.get_u16_le();
_struct.chan11_raw = buf.get_u16_le();
_struct.chan12_raw = buf.get_u16_le();
_struct.rssi = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_u16_le(self.chan1_raw);
_tmp.put_u16_le(self.chan2_raw);
_tmp.put_u16_le(self.chan3_raw);
_tmp.put_u16_le(self.chan4_raw);
_tmp.put_u16_le(self.chan5_raw);
_tmp.put_u16_le(self.chan6_raw);
_tmp.put_u16_le(self.chan7_raw);
_tmp.put_u16_le(self.chan8_raw);
_tmp.put_u16_le(self.chan9_raw);
_tmp.put_u16_le(self.chan10_raw);
_tmp.put_u16_le(self.chan11_raw);
_tmp.put_u16_le(self.chan12_raw);
_tmp.put_u8(self.rssi);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 12918"]
#[doc = "Transmitter (remote ID system) is enabled and ready to start sending location and other required information. This is streamed by transmitter. A flight controller uses it as a condition to arm.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct OPEN_DRONE_ID_ARM_STATUS_DATA {
#[doc = "Status level indicating if arming is allowed.."]
pub status: MavOdidArmStatus,
#[doc = "Text error message, should be empty if status is good to arm. Fill with nulls in unused portion.."]
pub error: Vec<u8, 50>,
}
impl OPEN_DRONE_ID_ARM_STATUS_DATA {
pub const ENCODED_LEN: usize = 51usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
let tmp = buf.get_u8();
_struct.status = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavOdidArmStatus",
value: tmp as u32,
})?;
for _ in 0..50usize {
let val = buf.get_u8();
_struct.error.push(val).unwrap();
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.status as u8);
for val in &self.error {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 287"]
#[doc = "High level message to control a gimbal's pitch and yaw angles. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct GIMBAL_MANAGER_SET_PITCHYAW_DATA {
#[doc = "High level gimbal manager flags to use.."]
pub flags: GimbalManagerFlags,
#[doc = "Pitch angle (positive: up, negative: down, NaN to be ignored).."]
pub pitch: f32,
#[doc = "Yaw angle (positive: to the right, negative: to the left, NaN to be ignored).."]
pub yaw: f32,
#[doc = "Pitch angular rate (positive: up, negative: down, NaN to be ignored).."]
pub pitch_rate: f32,
#[doc = "Yaw angular rate (positive: to the right, negative: to the left, NaN to be ignored).."]
pub yaw_rate: f32,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).."]
pub gimbal_device_id: u8,
}
impl GIMBAL_MANAGER_SET_PITCHYAW_DATA {
pub const ENCODED_LEN: usize = 23usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
let tmp = buf.get_u32_le();
_struct.flags = FromPrimitive::from_u32(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "GimbalManagerFlags",
value: tmp as u32,
})?;
_struct.pitch = buf.get_f32_le();
_struct.yaw = buf.get_f32_le();
_struct.pitch_rate = buf.get_f32_le();
_struct.yaw_rate = buf.get_f32_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
_struct.gimbal_device_id = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.flags as u32);
_tmp.put_f32_le(self.pitch);
_tmp.put_f32_le(self.yaw);
_tmp.put_f32_le(self.pitch_rate);
_tmp.put_f32_le(self.yaw_rate);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.gimbal_device_id);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 166"]
#[doc = "Status generated by radio.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct RADIO_DATA {
#[doc = "Receive errors.."]
pub rxerrors: u16,
#[doc = "Count of error corrected packets.."]
pub fixed: u16,
#[doc = "Local signal strength.."]
pub rssi: u8,
#[doc = "Remote signal strength.."]
pub remrssi: u8,
#[doc = "How full the tx buffer is.."]
pub txbuf: u8,
#[doc = "Background noise level.."]
pub noise: u8,
#[doc = "Remote background noise level.."]
pub remnoise: u8,
}
impl RADIO_DATA {
pub const ENCODED_LEN: usize = 9usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.rxerrors = buf.get_u16_le();
_struct.fixed = buf.get_u16_le();
_struct.rssi = buf.get_u8();
_struct.remrssi = buf.get_u8();
_struct.txbuf = buf.get_u8();
_struct.noise = buf.get_u8();
_struct.remnoise = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.rxerrors);
_tmp.put_u16_le(self.fixed);
_tmp.put_u8(self.rssi);
_tmp.put_u8(self.remrssi);
_tmp.put_u8(self.txbuf);
_tmp.put_u8(self.noise);
_tmp.put_u8(self.remnoise);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 49"]
#[doc = "Publishes the GPS coordinates of the vehicle local origin (0,0,0) position. Emitted whenever a new GPS-Local position mapping is requested or set - e.g. following SET_GPS_GLOBAL_ORIGIN message.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct GPS_GLOBAL_ORIGIN_DATA {
#[doc = "Latitude (WGS84)."]
pub latitude: i32,
#[doc = "Longitude (WGS84)."]
pub longitude: i32,
#[doc = "Altitude (MSL). Positive for up.."]
pub altitude: i32,
#[doc = "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.."]
#[cfg_attr(feature = "serde", serde(default))]
pub time_usec: u64,
}
impl GPS_GLOBAL_ORIGIN_DATA {
pub const ENCODED_LEN: usize = 20usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.latitude = buf.get_i32_le();
_struct.longitude = buf.get_i32_le();
_struct.altitude = buf.get_i32_le();
_struct.time_usec = buf.get_u64_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_i32_le(self.latitude);
_tmp.put_i32_le(self.longitude);
_tmp.put_i32_le(self.altitude);
_tmp.put_u64_le(self.time_usec);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 37"]
#[doc = "Request a partial list of mission items from the system/component. https://mavlink.io/en/services/mission.html. If start and end index are the same, just send one waypoint.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct MISSION_REQUEST_PARTIAL_LIST_DATA {
#[doc = "Start index."]
pub start_index: i16,
#[doc = "End index, -1 by default (-1: send list to end). Else a valid index of the list."]
pub end_index: i16,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "Mission type.."]
#[cfg_attr(feature = "serde", serde(default))]
pub mission_type: MavMissionType,
}
impl MISSION_REQUEST_PARTIAL_LIST_DATA {
pub const ENCODED_LEN: usize = 7usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.start_index = buf.get_i16_le();
_struct.end_index = buf.get_i16_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
let tmp = buf.get_u8();
_struct.mission_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavMissionType",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_i16_le(self.start_index);
_tmp.put_i16_le(self.end_index);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.mission_type as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 122"]
#[doc = "Stop log transfer and resume normal logging."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct LOG_REQUEST_END_DATA {
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
}
impl LOG_REQUEST_END_DATA {
pub const ENCODED_LEN: usize = 2usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 119"]
#[doc = "Request a chunk of a log."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct LOG_REQUEST_DATA_DATA {
#[doc = "Offset into the log."]
pub ofs: u32,
#[doc = "Number of bytes."]
pub count: u32,
#[doc = "Log id (from LOG_ENTRY reply)."]
pub id: u16,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
}
impl LOG_REQUEST_DATA_DATA {
pub const ENCODED_LEN: usize = 12usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.ofs = buf.get_u32_le();
_struct.count = buf.get_u32_le();
_struct.id = buf.get_u16_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.ofs);
_tmp.put_u32_le(self.count);
_tmp.put_u16_le(self.id);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 54"]
#[doc = "Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/waypoints to accept and which to reject. Safety areas are often enforced by national or competition regulations.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct SAFETY_SET_ALLOWED_AREA_DATA {
#[doc = "x position 1 / Latitude 1."]
pub p1x: f32,
#[doc = "y position 1 / Longitude 1."]
pub p1y: f32,
#[doc = "z position 1 / Altitude 1."]
pub p1z: f32,
#[doc = "x position 2 / Latitude 2."]
pub p2x: f32,
#[doc = "y position 2 / Longitude 2."]
pub p2y: f32,
#[doc = "z position 2 / Altitude 2."]
pub p2z: f32,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.."]
pub frame: MavFrame,
}
impl SAFETY_SET_ALLOWED_AREA_DATA {
pub const ENCODED_LEN: usize = 27usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.p1x = buf.get_f32_le();
_struct.p1y = buf.get_f32_le();
_struct.p1z = buf.get_f32_le();
_struct.p2x = buf.get_f32_le();
_struct.p2y = buf.get_f32_le();
_struct.p2z = buf.get_f32_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
let tmp = buf.get_u8();
_struct.frame = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavFrame",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.p1x);
_tmp.put_f32_le(self.p1y);
_tmp.put_f32_le(self.p1z);
_tmp.put_f32_le(self.p2x);
_tmp.put_f32_le(self.p2y);
_tmp.put_f32_le(self.p2z);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.frame as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 401"]
#[doc = "Tune formats supported by vehicle. This should be emitted as response to MAV_CMD_REQUEST_MESSAGE.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct SUPPORTED_TUNES_DATA {
#[doc = "Bitfield of supported tune formats.."]
pub format: TuneFormat,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
}
impl SUPPORTED_TUNES_DATA {
pub const ENCODED_LEN: usize = 6usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
let tmp = buf.get_u32_le();
_struct.format = TuneFormat::from_bits(tmp & TuneFormat::all().bits()).ok_or(
ParserError::InvalidFlag {
flag_type: "TuneFormat",
value: tmp as u32,
},
)?;
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.format.bits());
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 245"]
#[doc = "Provides state for additional features."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct EXTENDED_SYS_STATE_DATA {
#[doc = "The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration.."]
pub vtol_state: MavVtolState,
#[doc = "The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.."]
pub landed_state: MavLandedState,
}
impl EXTENDED_SYS_STATE_DATA {
pub const ENCODED_LEN: usize = 2usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
let tmp = buf.get_u8();
_struct.vtol_state = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavVtolState",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.landed_state = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavLandedState",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.vtol_state as u8);
_tmp.put_u8(self.landed_state as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 11002"]
#[doc = "Write registers for a device.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct DEVICE_OP_WRITE_DATA {
#[doc = "Request ID - copied to reply.."]
pub request_id: u32,
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Component ID.."]
pub target_component: u8,
#[doc = "The bus type.."]
pub bustype: DeviceOpBustype,
#[doc = "Bus number.."]
pub bus: u8,
#[doc = "Bus address.."]
pub address: u8,
#[doc = "Name of device on bus (for SPI).."]
pub busname: Vec<u8, 40>,
#[doc = "First register to write.."]
pub regstart: u8,
#[doc = "Count of registers to write.."]
pub count: u8,
#[doc = "Write data.."]
pub data: Vec<u8, 128>,
#[doc = "Bank number.."]
#[cfg_attr(feature = "serde", serde(default))]
pub bank: u8,
}
impl DEVICE_OP_WRITE_DATA {
pub const ENCODED_LEN: usize = 180usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.request_id = buf.get_u32_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
let tmp = buf.get_u8();
_struct.bustype = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "DeviceOpBustype",
value: tmp as u32,
})?;
_struct.bus = buf.get_u8();
_struct.address = buf.get_u8();
for _ in 0..40usize {
let val = buf.get_u8();
_struct.busname.push(val).unwrap();
}
_struct.regstart = buf.get_u8();
_struct.count = buf.get_u8();
for _ in 0..128usize {
let val = buf.get_u8();
_struct.data.push(val).unwrap();
}
_struct.bank = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.request_id);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.bustype as u8);
_tmp.put_u8(self.bus);
_tmp.put_u8(self.address);
for val in &self.busname {
_tmp.put_u8(*val);
}
_tmp.put_u8(self.regstart);
_tmp.put_u8(self.count);
for val in &self.data {
_tmp.put_u8(*val);
}
_tmp.put_u8(self.bank);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 373"]
#[doc = "Telemetry of power generation system. Alternator or mechanical generator.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct GENERATOR_STATUS_DATA {
#[doc = "Status flags.."]
pub status: MavGeneratorStatusFlag,
#[doc = "Current into/out of battery. Positive for out. Negative for in. NaN: field not provided.."]
pub battery_current: f32,
#[doc = "Current going to the UAV. If battery current not available this is the DC current from the generator. Positive for out. Negative for in. NaN: field not provided."]
pub load_current: f32,
#[doc = "The power being generated. NaN: field not provided."]
pub power_generated: f32,
#[doc = "Voltage of the bus seen at the generator, or battery bus if battery bus is controlled by generator and at a different voltage to main bus.."]
pub bus_voltage: f32,
#[doc = "The target battery current. Positive for out. Negative for in. NaN: field not provided."]
pub bat_current_setpoint: f32,
#[doc = "Seconds this generator has run since it was rebooted. UINT32_MAX: field not provided.."]
pub runtime: u32,
#[doc = "Seconds until this generator requires maintenance. A negative value indicates maintenance is past-due. INT32_MAX: field not provided.."]
pub time_until_maintenance: i32,
#[doc = "Speed of electrical generator or alternator. UINT16_MAX: field not provided.."]
pub generator_speed: u16,
#[doc = "The temperature of the rectifier or power converter. INT16_MAX: field not provided.."]
pub rectifier_temperature: i16,
#[doc = "The temperature of the mechanical motor, fuel cell core or generator. INT16_MAX: field not provided.."]
pub generator_temperature: i16,
}
impl GENERATOR_STATUS_DATA {
pub const ENCODED_LEN: usize = 42usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
let tmp = buf.get_u64_le();
_struct.status = MavGeneratorStatusFlag::from_bits(
tmp & MavGeneratorStatusFlag::all().bits(),
)
.ok_or(ParserError::InvalidFlag {
flag_type: "MavGeneratorStatusFlag",
value: tmp as u32,
})?;
_struct.battery_current = buf.get_f32_le();
_struct.load_current = buf.get_f32_le();
_struct.power_generated = buf.get_f32_le();
_struct.bus_voltage = buf.get_f32_le();
_struct.bat_current_setpoint = buf.get_f32_le();
_struct.runtime = buf.get_u32_le();
_struct.time_until_maintenance = buf.get_i32_le();
_struct.generator_speed = buf.get_u16_le();
_struct.rectifier_temperature = buf.get_i16_le();
_struct.generator_temperature = buf.get_i16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.status.bits());
_tmp.put_f32_le(self.battery_current);
_tmp.put_f32_le(self.load_current);
_tmp.put_f32_le(self.power_generated);
_tmp.put_f32_le(self.bus_voltage);
_tmp.put_f32_le(self.bat_current_setpoint);
_tmp.put_u32_le(self.runtime);
_tmp.put_i32_le(self.time_until_maintenance);
_tmp.put_u16_le(self.generator_speed);
_tmp.put_i16_le(self.rectifier_temperature);
_tmp.put_i16_le(self.generator_temperature);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 31"]
#[doc = "The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0).."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct ATTITUDE_QUATERNION_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "Quaternion component 1, w (1 in null-rotation)."]
pub q1: f32,
#[doc = "Quaternion component 2, x (0 in null-rotation)."]
pub q2: f32,
#[doc = "Quaternion component 3, y (0 in null-rotation)."]
pub q3: f32,
#[doc = "Quaternion component 4, z (0 in null-rotation)."]
pub q4: f32,
#[doc = "Roll angular speed."]
pub rollspeed: f32,
#[doc = "Pitch angular speed."]
pub pitchspeed: f32,
#[doc = "Yaw angular speed."]
pub yawspeed: f32,
#[doc = "Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode.."]
#[cfg_attr(feature = "serde", serde(default))]
pub repr_offset_q: [f32; 4],
}
impl ATTITUDE_QUATERNION_DATA {
pub const ENCODED_LEN: usize = 48usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.q1 = buf.get_f32_le();
_struct.q2 = buf.get_f32_le();
_struct.q3 = buf.get_f32_le();
_struct.q4 = buf.get_f32_le();
_struct.rollspeed = buf.get_f32_le();
_struct.pitchspeed = buf.get_f32_le();
_struct.yawspeed = buf.get_f32_le();
for idx in 0..4usize {
let val = buf.get_f32_le();
_struct.repr_offset_q[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_f32_le(self.q1);
_tmp.put_f32_le(self.q2);
_tmp.put_f32_le(self.q3);
_tmp.put_f32_le(self.q4);
_tmp.put_f32_le(self.rollspeed);
_tmp.put_f32_le(self.pitchspeed);
_tmp.put_f32_le(self.yawspeed);
for val in &self.repr_offset_q {
_tmp.put_f32_le(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 163"]
#[doc = "Status of DCM attitude estimator.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct AHRS_DATA {
#[doc = "X gyro drift estimate.."]
pub omegaIx: f32,
#[doc = "Y gyro drift estimate.."]
pub omegaIy: f32,
#[doc = "Z gyro drift estimate.."]
pub omegaIz: f32,
#[doc = "Average accel_weight.."]
pub accel_weight: f32,
#[doc = "Average renormalisation value.."]
pub renorm_val: f32,
#[doc = "Average error_roll_pitch value.."]
pub error_rp: f32,
#[doc = "Average error_yaw value.."]
pub error_yaw: f32,
}
impl AHRS_DATA {
pub const ENCODED_LEN: usize = 28usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.omegaIx = buf.get_f32_le();
_struct.omegaIy = buf.get_f32_le();
_struct.omegaIz = buf.get_f32_le();
_struct.accel_weight = buf.get_f32_le();
_struct.renorm_val = buf.get_f32_le();
_struct.error_rp = buf.get_f32_le();
_struct.error_yaw = buf.get_f32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.omegaIx);
_tmp.put_f32_le(self.omegaIy);
_tmp.put_f32_le(self.omegaIz);
_tmp.put_f32_le(self.accel_weight);
_tmp.put_f32_le(self.renorm_val);
_tmp.put_f32_le(self.error_rp);
_tmp.put_f32_le(self.error_yaw);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 136"]
#[doc = "Streamed from drone to report progress of terrain map download (initiated by TERRAIN_REQUEST), or sent as a response to a TERRAIN_CHECK request. See terrain protocol docs: https://mavlink.io/en/services/terrain.html."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct TERRAIN_REPORT_DATA {
#[doc = "Latitude."]
pub lat: i32,
#[doc = "Longitude."]
pub lon: i32,
#[doc = "Terrain height MSL."]
pub terrain_height: f32,
#[doc = "Current vehicle height above lat/lon terrain height."]
pub current_height: f32,
#[doc = "grid spacing (zero if terrain at this location unavailable)."]
pub spacing: u16,
#[doc = "Number of 4x4 terrain blocks waiting to be received or read from disk."]
pub pending: u16,
#[doc = "Number of 4x4 terrain blocks in memory."]
pub loaded: u16,
}
impl TERRAIN_REPORT_DATA {
pub const ENCODED_LEN: usize = 22usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.lat = buf.get_i32_le();
_struct.lon = buf.get_i32_le();
_struct.terrain_height = buf.get_f32_le();
_struct.current_height = buf.get_f32_le();
_struct.spacing = buf.get_u16_le();
_struct.pending = buf.get_u16_le();
_struct.loaded = buf.get_u16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_i32_le(self.lat);
_tmp.put_i32_le(self.lon);
_tmp.put_f32_le(self.terrain_height);
_tmp.put_f32_le(self.current_height);
_tmp.put_u16_le(self.spacing);
_tmp.put_u16_le(self.pending);
_tmp.put_u16_le(self.loaded);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 12902"]
#[doc = "Data for filling the OpenDroneID Authentication message. The Authentication Message defines a field that can provide a means of authenticity for the identity of the UAS (Unmanned Aircraft System). The Authentication message can have two different formats. For data page 0, the fields PageCount, Length and TimeStamp are present and AuthData is only 17 bytes. For data page 1 through 15, PageCount, Length and TimeStamp are not present and the size of AuthData is 23 bytes.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct OPEN_DRONE_ID_AUTHENTICATION_DATA {
#[doc = "This field is only present for page 0. 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019.."]
pub timestamp: u32,
#[doc = "System ID (0 for broadcast).."]
pub target_system: u8,
#[doc = "Component ID (0 for broadcast).."]
pub target_component: u8,
#[doc = "Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.."]
pub id_or_mac: [u8; 20],
#[doc = "Indicates the type of authentication.."]
pub authentication_type: MavOdidAuthType,
#[doc = "Allowed range is 0 - 15.."]
pub data_page: u8,
#[doc = "This field is only present for page 0. Allowed range is 0 - 15. See the description of struct ODID_Auth_data at https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h.."]
pub last_page_index: u8,
#[doc = "This field is only present for page 0. Total bytes of authentication_data from all data pages. See the description of struct ODID_Auth_data at https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h.."]
pub length: u8,
#[doc = "Opaque authentication data. For page 0, the size is only 17 bytes. For other pages, the size is 23 bytes. Shall be filled with nulls in the unused portion of the field.."]
pub authentication_data: [u8; 23],
}
impl OPEN_DRONE_ID_AUTHENTICATION_DATA {
pub const ENCODED_LEN: usize = 53usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.timestamp = buf.get_u32_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
for idx in 0..20usize {
let val = buf.get_u8();
_struct.id_or_mac[idx] = val;
}
let tmp = buf.get_u8();
_struct.authentication_type =
FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavOdidAuthType",
value: tmp as u32,
})?;
_struct.data_page = buf.get_u8();
_struct.last_page_index = buf.get_u8();
_struct.length = buf.get_u8();
for idx in 0..23usize {
let val = buf.get_u8();
_struct.authentication_data[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.timestamp);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
for val in &self.id_or_mac {
_tmp.put_u8(*val);
}
_tmp.put_u8(self.authentication_type as u8);
_tmp.put_u8(self.data_page);
_tmp.put_u8(self.last_page_index);
_tmp.put_u8(self.length);
for val in &self.authentication_data {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 413"]
#[doc = "Response to a REQUEST_EVENT in case of an error (e.g. the event is not available anymore).."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct RESPONSE_EVENT_ERROR_DATA {
#[doc = "Sequence number.."]
pub sequence: u16,
#[doc = "Oldest Sequence number that is still available after the sequence set in REQUEST_EVENT.."]
pub sequence_oldest_available: u16,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "Error reason.."]
pub reason: MavEventErrorReason,
}
impl RESPONSE_EVENT_ERROR_DATA {
pub const ENCODED_LEN: usize = 7usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.sequence = buf.get_u16_le();
_struct.sequence_oldest_available = buf.get_u16_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
let tmp = buf.get_u8();
_struct.reason = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavEventErrorReason",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.sequence);
_tmp.put_u16_le(self.sequence_oldest_available);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.reason as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 129"]
#[doc = "The RAW IMU readings for 3rd 9DOF sensor setup. This message should contain the scaled values to the described units."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct SCALED_IMU3_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "X acceleration."]
pub xacc: i16,
#[doc = "Y acceleration."]
pub yacc: i16,
#[doc = "Z acceleration."]
pub zacc: i16,
#[doc = "Angular speed around X axis."]
pub xgyro: i16,
#[doc = "Angular speed around Y axis."]
pub ygyro: i16,
#[doc = "Angular speed around Z axis."]
pub zgyro: i16,
#[doc = "X Magnetic field."]
pub xmag: i16,
#[doc = "Y Magnetic field."]
pub ymag: i16,
#[doc = "Z Magnetic field."]
pub zmag: i16,
#[doc = "Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C).."]
#[cfg_attr(feature = "serde", serde(default))]
pub temperature: i16,
}
impl SCALED_IMU3_DATA {
pub const ENCODED_LEN: usize = 24usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.xacc = buf.get_i16_le();
_struct.yacc = buf.get_i16_le();
_struct.zacc = buf.get_i16_le();
_struct.xgyro = buf.get_i16_le();
_struct.ygyro = buf.get_i16_le();
_struct.zgyro = buf.get_i16_le();
_struct.xmag = buf.get_i16_le();
_struct.ymag = buf.get_i16_le();
_struct.zmag = buf.get_i16_le();
_struct.temperature = buf.get_i16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_i16_le(self.xacc);
_tmp.put_i16_le(self.yacc);
_tmp.put_i16_le(self.zacc);
_tmp.put_i16_le(self.xgyro);
_tmp.put_i16_le(self.ygyro);
_tmp.put_i16_le(self.zgyro);
_tmp.put_i16_le(self.xmag);
_tmp.put_i16_le(self.ymag);
_tmp.put_i16_le(self.zmag);
_tmp.put_i16_le(self.temperature);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 87"]
#[doc = "Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being controlled this way.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct POSITION_TARGET_GLOBAL_INT_DATA {
#[doc = "Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.."]
pub time_boot_ms: u32,
#[doc = "X Position in WGS84 frame."]
pub lat_int: i32,
#[doc = "Y Position in WGS84 frame."]
pub lon_int: i32,
#[doc = "Altitude (MSL, AGL or relative to home altitude, depending on frame)."]
pub alt: f32,
#[doc = "X velocity in NED frame."]
pub vx: f32,
#[doc = "Y velocity in NED frame."]
pub vy: f32,
#[doc = "Z velocity in NED frame."]
pub vz: f32,
#[doc = "X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N."]
pub afx: f32,
#[doc = "Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N."]
pub afy: f32,
#[doc = "Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N."]
pub afz: f32,
#[doc = "yaw setpoint."]
pub yaw: f32,
#[doc = "yaw rate setpoint."]
pub yaw_rate: f32,
#[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle.."]
pub type_mask: PositionTargetTypemask,
#[doc = "Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11."]
pub coordinate_frame: MavFrame,
}
impl POSITION_TARGET_GLOBAL_INT_DATA {
pub const ENCODED_LEN: usize = 51usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.lat_int = buf.get_i32_le();
_struct.lon_int = buf.get_i32_le();
_struct.alt = buf.get_f32_le();
_struct.vx = buf.get_f32_le();
_struct.vy = buf.get_f32_le();
_struct.vz = buf.get_f32_le();
_struct.afx = buf.get_f32_le();
_struct.afy = buf.get_f32_le();
_struct.afz = buf.get_f32_le();
_struct.yaw = buf.get_f32_le();
_struct.yaw_rate = buf.get_f32_le();
let tmp = buf.get_u16_le();
_struct.type_mask = PositionTargetTypemask::from_bits(
tmp & PositionTargetTypemask::all().bits(),
)
.ok_or(ParserError::InvalidFlag {
flag_type: "PositionTargetTypemask",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.coordinate_frame = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavFrame",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_i32_le(self.lat_int);
_tmp.put_i32_le(self.lon_int);
_tmp.put_f32_le(self.alt);
_tmp.put_f32_le(self.vx);
_tmp.put_f32_le(self.vy);
_tmp.put_f32_le(self.vz);
_tmp.put_f32_le(self.afx);
_tmp.put_f32_le(self.afy);
_tmp.put_f32_le(self.afz);
_tmp.put_f32_le(self.yaw);
_tmp.put_f32_le(self.yaw_rate);
_tmp.put_u16_le(self.type_mask.bits());
_tmp.put_u8(self.coordinate_frame as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 25"]
#[doc = "The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION_INT for the global position estimate. This message can contain information for up to 20 satellites.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct GPS_STATUS_DATA {
#[doc = "Number of satellites visible."]
pub satellites_visible: u8,
#[doc = "Global satellite ID."]
pub satellite_prn: [u8; 20],
#[doc = "0: Satellite not used, 1: used for localization."]
pub satellite_used: [u8; 20],
#[doc = "Elevation (0: right on top of receiver, 90: on the horizon) of satellite."]
pub satellite_elevation: [u8; 20],
#[doc = "Direction of satellite, 0: 0 deg, 255: 360 deg.."]
pub satellite_azimuth: [u8; 20],
#[doc = "Signal to noise ratio of satellite."]
pub satellite_snr: [u8; 20],
}
impl GPS_STATUS_DATA {
pub const ENCODED_LEN: usize = 101usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.satellites_visible = buf.get_u8();
for idx in 0..20usize {
let val = buf.get_u8();
_struct.satellite_prn[idx] = val;
}
for idx in 0..20usize {
let val = buf.get_u8();
_struct.satellite_used[idx] = val;
}
for idx in 0..20usize {
let val = buf.get_u8();
_struct.satellite_elevation[idx] = val;
}
for idx in 0..20usize {
let val = buf.get_u8();
_struct.satellite_azimuth[idx] = val;
}
for idx in 0..20usize {
let val = buf.get_u8();
_struct.satellite_snr[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.satellites_visible);
for val in &self.satellite_prn {
_tmp.put_u8(*val);
}
for val in &self.satellite_used {
_tmp.put_u8(*val);
}
for val in &self.satellite_elevation {
_tmp.put_u8(*val);
}
for val in &self.satellite_azimuth {
_tmp.put_u8(*val);
}
for val in &self.satellite_snr {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 310"]
#[doc = "General status information of an UAVCAN node. Please refer to the definition of the UAVCAN message \"uavcan.protocol.NodeStatus\" for the background information. The UAVCAN specification is available at http://uavcan.org.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct UAVCAN_NODE_STATUS_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "Time since the start-up of the node.."]
pub uptime_sec: u32,
#[doc = "Vendor-specific status information.."]
pub vendor_specific_status_code: u16,
#[doc = "Generalized node health status.."]
pub health: UavcanNodeHealth,
#[doc = "Generalized operating mode.."]
pub mode: UavcanNodeMode,
#[doc = "Not used currently.."]
pub sub_mode: u8,
}
impl UAVCAN_NODE_STATUS_DATA {
pub const ENCODED_LEN: usize = 17usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.uptime_sec = buf.get_u32_le();
_struct.vendor_specific_status_code = buf.get_u16_le();
let tmp = buf.get_u8();
_struct.health = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "UavcanNodeHealth",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.mode = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "UavcanNodeMode",
value: tmp as u32,
})?;
_struct.sub_mode = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_u32_le(self.uptime_sec);
_tmp.put_u16_le(self.vendor_specific_status_code);
_tmp.put_u8(self.health as u8);
_tmp.put_u8(self.mode as u8);
_tmp.put_u8(self.sub_mode);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 192"]
#[doc = "Reports results of completed compass calibration. Sent until MAG_CAL_ACK received.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct MAG_CAL_REPORT_DATA {
#[doc = "RMS milligauss residuals.."]
pub fitness: f32,
#[doc = "X offset.."]
pub ofs_x: f32,
#[doc = "Y offset.."]
pub ofs_y: f32,
#[doc = "Z offset.."]
pub ofs_z: f32,
#[doc = "X diagonal (matrix 11).."]
pub diag_x: f32,
#[doc = "Y diagonal (matrix 22).."]
pub diag_y: f32,
#[doc = "Z diagonal (matrix 33).."]
pub diag_z: f32,
#[doc = "X off-diagonal (matrix 12 and 21).."]
pub offdiag_x: f32,
#[doc = "Y off-diagonal (matrix 13 and 31).."]
pub offdiag_y: f32,
#[doc = "Z off-diagonal (matrix 32 and 23).."]
pub offdiag_z: f32,
#[doc = "Compass being calibrated.."]
pub compass_id: u8,
#[doc = "Bitmask of compasses being calibrated.."]
pub cal_mask: u8,
#[doc = "Calibration Status.."]
pub cal_status: MagCalStatus,
#[doc = "0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters.."]
pub autosaved: u8,
#[doc = "Confidence in orientation (higher is better).."]
#[cfg_attr(feature = "serde", serde(default))]
pub orientation_confidence: f32,
#[doc = "orientation before calibration.."]
#[cfg_attr(feature = "serde", serde(default))]
pub old_orientation: MavSensorOrientation,
#[doc = "orientation after calibration.."]
#[cfg_attr(feature = "serde", serde(default))]
pub new_orientation: MavSensorOrientation,
#[doc = "field radius correction factor."]
#[cfg_attr(feature = "serde", serde(default))]
pub scale_factor: f32,
}
impl MAG_CAL_REPORT_DATA {
pub const ENCODED_LEN: usize = 54usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.fitness = buf.get_f32_le();
_struct.ofs_x = buf.get_f32_le();
_struct.ofs_y = buf.get_f32_le();
_struct.ofs_z = buf.get_f32_le();
_struct.diag_x = buf.get_f32_le();
_struct.diag_y = buf.get_f32_le();
_struct.diag_z = buf.get_f32_le();
_struct.offdiag_x = buf.get_f32_le();
_struct.offdiag_y = buf.get_f32_le();
_struct.offdiag_z = buf.get_f32_le();
_struct.compass_id = buf.get_u8();
_struct.cal_mask = buf.get_u8();
let tmp = buf.get_u8();
_struct.cal_status = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MagCalStatus",
value: tmp as u32,
})?;
_struct.autosaved = buf.get_u8();
_struct.orientation_confidence = buf.get_f32_le();
let tmp = buf.get_u8();
_struct.old_orientation = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavSensorOrientation",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.new_orientation = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavSensorOrientation",
value: tmp as u32,
})?;
_struct.scale_factor = buf.get_f32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.fitness);
_tmp.put_f32_le(self.ofs_x);
_tmp.put_f32_le(self.ofs_y);
_tmp.put_f32_le(self.ofs_z);
_tmp.put_f32_le(self.diag_x);
_tmp.put_f32_le(self.diag_y);
_tmp.put_f32_le(self.diag_z);
_tmp.put_f32_le(self.offdiag_x);
_tmp.put_f32_le(self.offdiag_y);
_tmp.put_f32_le(self.offdiag_z);
_tmp.put_u8(self.compass_id);
_tmp.put_u8(self.cal_mask);
_tmp.put_u8(self.cal_status as u8);
_tmp.put_u8(self.autosaved);
_tmp.put_f32_le(self.orientation_confidence);
_tmp.put_u8(self.old_orientation as u8);
_tmp.put_u8(self.new_orientation as u8);
_tmp.put_f32_le(self.scale_factor);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 137"]
#[doc = "Barometer readings for 2nd barometer."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct SCALED_PRESSURE2_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "Absolute pressure."]
pub press_abs: f32,
#[doc = "Differential pressure."]
pub press_diff: f32,
#[doc = "Absolute pressure temperature."]
pub temperature: i16,
#[doc = "Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC.."]
#[cfg_attr(feature = "serde", serde(default))]
pub temperature_press_diff: i16,
}
impl SCALED_PRESSURE2_DATA {
pub const ENCODED_LEN: usize = 16usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.press_abs = buf.get_f32_le();
_struct.press_diff = buf.get_f32_le();
_struct.temperature = buf.get_i16_le();
_struct.temperature_press_diff = buf.get_i16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_f32_le(self.press_abs);
_tmp.put_f32_le(self.press_diff);
_tmp.put_i16_le(self.temperature);
_tmp.put_i16_le(self.temperature_press_diff);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 386"]
#[doc = "A forwarded CAN frame as requested by MAV_CMD_CAN_FORWARD.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct CAN_FRAME_DATA {
#[doc = "Frame ID."]
pub id: u32,
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Component ID.."]
pub target_component: u8,
#[doc = "Bus number."]
pub bus: u8,
#[doc = "Frame length."]
pub len: u8,
#[doc = "Frame data."]
pub data: [u8; 8],
}
impl CAN_FRAME_DATA {
pub const ENCODED_LEN: usize = 16usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.id = buf.get_u32_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
_struct.bus = buf.get_u8();
_struct.len = buf.get_u8();
for idx in 0..8usize {
let val = buf.get_u8();
_struct.data[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.id);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.bus);
_tmp.put_u8(self.len);
for val in &self.data {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 100"]
#[doc = "Optical flow from a flow sensor (e.g. optical mouse sensor)."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct OPTICAL_FLOW_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "Flow in x-sensor direction, angular-speed compensated."]
pub flow_comp_m_x: f32,
#[doc = "Flow in y-sensor direction, angular-speed compensated."]
pub flow_comp_m_y: f32,
#[doc = "Ground distance. Positive value: distance known. Negative value: Unknown distance."]
pub ground_distance: f32,
#[doc = "Flow in x-sensor direction."]
pub flow_x: i16,
#[doc = "Flow in y-sensor direction."]
pub flow_y: i16,
#[doc = "Sensor ID."]
pub sensor_id: u8,
#[doc = "Optical flow quality / confidence. 0: bad, 255: maximum quality."]
pub quality: u8,
#[doc = "Flow rate about X axis."]
#[cfg_attr(feature = "serde", serde(default))]
pub flow_rate_x: f32,
#[doc = "Flow rate about Y axis."]
#[cfg_attr(feature = "serde", serde(default))]
pub flow_rate_y: f32,
}
impl OPTICAL_FLOW_DATA {
pub const ENCODED_LEN: usize = 34usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.flow_comp_m_x = buf.get_f32_le();
_struct.flow_comp_m_y = buf.get_f32_le();
_struct.ground_distance = buf.get_f32_le();
_struct.flow_x = buf.get_i16_le();
_struct.flow_y = buf.get_i16_le();
_struct.sensor_id = buf.get_u8();
_struct.quality = buf.get_u8();
_struct.flow_rate_x = buf.get_f32_le();
_struct.flow_rate_y = buf.get_f32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_f32_le(self.flow_comp_m_x);
_tmp.put_f32_le(self.flow_comp_m_y);
_tmp.put_f32_le(self.ground_distance);
_tmp.put_i16_le(self.flow_x);
_tmp.put_i16_le(self.flow_y);
_tmp.put_u8(self.sensor_id);
_tmp.put_u8(self.quality);
_tmp.put_f32_le(self.flow_rate_x);
_tmp.put_f32_le(self.flow_rate_y);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 281"]
#[doc = "Current status about a high level gimbal manager. This message should be broadcast at a low regular rate (e.g. 5Hz).."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct GIMBAL_MANAGER_STATUS_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "High level gimbal manager flags currently applied.."]
pub flags: GimbalManagerFlags,
#[doc = "Gimbal device ID that this gimbal manager is responsible for.."]
pub gimbal_device_id: u8,
#[doc = "System ID of MAVLink component with primary control, 0 for none.."]
pub primary_control_sysid: u8,
#[doc = "Component ID of MAVLink component with primary control, 0 for none.."]
pub primary_control_compid: u8,
#[doc = "System ID of MAVLink component with secondary control, 0 for none.."]
pub secondary_control_sysid: u8,
#[doc = "Component ID of MAVLink component with secondary control, 0 for none.."]
pub secondary_control_compid: u8,
}
impl GIMBAL_MANAGER_STATUS_DATA {
pub const ENCODED_LEN: usize = 13usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
let tmp = buf.get_u32_le();
_struct.flags = FromPrimitive::from_u32(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "GimbalManagerFlags",
value: tmp as u32,
})?;
_struct.gimbal_device_id = buf.get_u8();
_struct.primary_control_sysid = buf.get_u8();
_struct.primary_control_compid = buf.get_u8();
_struct.secondary_control_sysid = buf.get_u8();
_struct.secondary_control_compid = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_u32_le(self.flags as u32);
_tmp.put_u8(self.gimbal_device_id);
_tmp.put_u8(self.primary_control_sysid);
_tmp.put_u8(self.primary_control_compid);
_tmp.put_u8(self.secondary_control_sysid);
_tmp.put_u8(self.secondary_control_compid);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 135"]
#[doc = "Request that the vehicle report terrain height at the given location (expected response is a TERRAIN_REPORT). Used by GCS to check if vehicle has all terrain data needed for a mission.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct TERRAIN_CHECK_DATA {
#[doc = "Latitude."]
pub lat: i32,
#[doc = "Longitude."]
pub lon: i32,
}
impl TERRAIN_CHECK_DATA {
pub const ENCODED_LEN: usize = 8usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.lat = buf.get_i32_le();
_struct.lon = buf.get_i32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_i32_le(self.lat);
_tmp.put_i32_le(self.lon);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 269"]
#[doc = "Information about video stream. It may be requested using MAV_CMD_REQUEST_MESSAGE, where param2 indicates the video stream id: 0 for all streams, 1 for first, 2 for second, etc.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct VIDEO_STREAM_INFORMATION_DATA {
#[doc = "Frame rate.."]
pub framerate: f32,
#[doc = "Bit rate.."]
pub bitrate: u32,
#[doc = "Bitmap of stream status flags.."]
pub flags: VideoStreamStatusFlags,
#[doc = "Horizontal resolution.."]
pub resolution_h: u16,
#[doc = "Vertical resolution.."]
pub resolution_v: u16,
#[doc = "Video image rotation clockwise.."]
pub rotation: u16,
#[doc = "Horizontal Field of view.."]
pub hfov: u16,
#[doc = "Video Stream ID (1 for first, 2 for second, etc.)."]
pub stream_id: u8,
#[doc = "Number of streams available.."]
pub count: u8,
#[doc = "Type of stream.."]
pub mavtype: VideoStreamType,
#[doc = "Stream name.."]
pub name: [u8; 32],
#[doc = "Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to).."]
pub uri: Vec<u8, 160>,
}
impl VIDEO_STREAM_INFORMATION_DATA {
pub const ENCODED_LEN: usize = 213usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.framerate = buf.get_f32_le();
_struct.bitrate = buf.get_u32_le();
let tmp = buf.get_u16_le();
_struct.flags = FromPrimitive::from_u16(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "VideoStreamStatusFlags",
value: tmp as u32,
})?;
_struct.resolution_h = buf.get_u16_le();
_struct.resolution_v = buf.get_u16_le();
_struct.rotation = buf.get_u16_le();
_struct.hfov = buf.get_u16_le();
_struct.stream_id = buf.get_u8();
_struct.count = buf.get_u8();
let tmp = buf.get_u8();
_struct.mavtype = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "VideoStreamType",
value: tmp as u32,
})?;
for idx in 0..32usize {
let val = buf.get_u8();
_struct.name[idx] = val;
}
for _ in 0..160usize {
let val = buf.get_u8();
_struct.uri.push(val).unwrap();
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.framerate);
_tmp.put_u32_le(self.bitrate);
_tmp.put_u16_le(self.flags as u16);
_tmp.put_u16_le(self.resolution_h);
_tmp.put_u16_le(self.resolution_v);
_tmp.put_u16_le(self.rotation);
_tmp.put_u16_le(self.hfov);
_tmp.put_u8(self.stream_id);
_tmp.put_u8(self.count);
_tmp.put_u8(self.mavtype as u8);
for val in &self.name {
_tmp.put_u8(*val);
}
for val in &self.uri {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 158"]
#[doc = "Message with some status from autopilot to GCS about camera or antenna mount.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct MOUNT_STATUS_DATA {
#[doc = "Pitch.."]
pub pointing_a: i32,
#[doc = "Roll.."]
pub pointing_b: i32,
#[doc = "Yaw.."]
pub pointing_c: i32,
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Component ID.."]
pub target_component: u8,
#[doc = "Mount operating mode.."]
#[cfg_attr(feature = "serde", serde(default))]
pub mount_mode: MavMountMode,
}
impl MOUNT_STATUS_DATA {
pub const ENCODED_LEN: usize = 15usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.pointing_a = buf.get_i32_le();
_struct.pointing_b = buf.get_i32_le();
_struct.pointing_c = buf.get_i32_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
let tmp = buf.get_u8();
_struct.mount_mode = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavMountMode",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_i32_le(self.pointing_a);
_tmp.put_i32_le(self.pointing_b);
_tmp.put_i32_le(self.pointing_c);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.mount_mode as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 82"]
#[doc = "Sets a desired vehicle attitude. Used by an external controller to command the vehicle (manual controller or other system).."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct SET_ATTITUDE_TARGET_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)."]
pub q: [f32; 4],
#[doc = "Body roll rate."]
pub body_roll_rate: f32,
#[doc = "Body pitch rate."]
pub body_pitch_rate: f32,
#[doc = "Body yaw rate."]
pub body_yaw_rate: f32,
#[doc = "Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)."]
pub thrust: f32,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle.."]
pub type_mask: AttitudeTargetTypemask,
#[doc = "3D thrust setpoint in the body NED frame, normalized to -1 .. 1."]
#[cfg_attr(feature = "serde", serde(default))]
pub thrust_body: [f32; 3],
}
impl SET_ATTITUDE_TARGET_DATA {
pub const ENCODED_LEN: usize = 51usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
for idx in 0..4usize {
let val = buf.get_f32_le();
_struct.q[idx] = val;
}
_struct.body_roll_rate = buf.get_f32_le();
_struct.body_pitch_rate = buf.get_f32_le();
_struct.body_yaw_rate = buf.get_f32_le();
_struct.thrust = buf.get_f32_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
let tmp = buf.get_u8();
_struct.type_mask = AttitudeTargetTypemask::from_bits(
tmp & AttitudeTargetTypemask::all().bits(),
)
.ok_or(ParserError::InvalidFlag {
flag_type: "AttitudeTargetTypemask",
value: tmp as u32,
})?;
for idx in 0..3usize {
let val = buf.get_f32_le();
_struct.thrust_body[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
for val in &self.q {
_tmp.put_f32_le(*val);
}
_tmp.put_f32_le(self.body_roll_rate);
_tmp.put_f32_le(self.body_pitch_rate);
_tmp.put_f32_le(self.body_yaw_rate);
_tmp.put_f32_le(self.thrust);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.type_mask.bits());
for val in &self.thrust_body {
_tmp.put_f32_le(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 282"]
#[doc = "High level message to control a gimbal's attitude. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct GIMBAL_MANAGER_SET_ATTITUDE_DATA {
#[doc = "High level gimbal manager flags to use.."]
pub flags: GimbalManagerFlags,
#[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set)."]
pub q: [f32; 4],
#[doc = "X component of angular velocity, positive is rolling to the right, NaN to be ignored.."]
pub angular_velocity_x: f32,
#[doc = "Y component of angular velocity, positive is pitching up, NaN to be ignored.."]
pub angular_velocity_y: f32,
#[doc = "Z component of angular velocity, positive is yawing to the right, NaN to be ignored.."]
pub angular_velocity_z: f32,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).."]
pub gimbal_device_id: u8,
}
impl GIMBAL_MANAGER_SET_ATTITUDE_DATA {
pub const ENCODED_LEN: usize = 35usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
let tmp = buf.get_u32_le();
_struct.flags = FromPrimitive::from_u32(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "GimbalManagerFlags",
value: tmp as u32,
})?;
for idx in 0..4usize {
let val = buf.get_f32_le();
_struct.q[idx] = val;
}
_struct.angular_velocity_x = buf.get_f32_le();
_struct.angular_velocity_y = buf.get_f32_le();
_struct.angular_velocity_z = buf.get_f32_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
_struct.gimbal_device_id = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.flags as u32);
for val in &self.q {
_tmp.put_f32_le(*val);
}
_tmp.put_f32_le(self.angular_velocity_x);
_tmp.put_f32_le(self.angular_velocity_y);
_tmp.put_f32_le(self.angular_velocity_z);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.gimbal_device_id);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 284"]
#[doc = "Low level message to control a gimbal device's attitude. \t This message is to be sent from the gimbal manager to the gimbal device component. \t The quaternion and angular velocities can be set to NaN according to use case. \t For the angles encoded in the quaternion and the angular velocities holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). \t If neither of these flags are set, then (for backwards compatibility) it holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), \t else they are relative to the vehicle heading (vehicle frame). \t Setting both GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME and GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is not allowed. \t These rules are to ensure backwards compatibility. \t New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct GIMBAL_DEVICE_SET_ATTITUDE_DATA {
#[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description. Set fields to NaN to be ignored.."]
pub q: [f32; 4],
#[doc = "X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN to be ignored.."]
pub angular_velocity_x: f32,
#[doc = "Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN to be ignored.."]
pub angular_velocity_y: f32,
#[doc = "Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN to be ignored.."]
pub angular_velocity_z: f32,
#[doc = "Low level gimbal flags.."]
pub flags: GimbalDeviceFlags,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
}
impl GIMBAL_DEVICE_SET_ATTITUDE_DATA {
pub const ENCODED_LEN: usize = 32usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
for idx in 0..4usize {
let val = buf.get_f32_le();
_struct.q[idx] = val;
}
_struct.angular_velocity_x = buf.get_f32_le();
_struct.angular_velocity_y = buf.get_f32_le();
_struct.angular_velocity_z = buf.get_f32_le();
let tmp = buf.get_u16_le();
_struct.flags = GimbalDeviceFlags::from_bits(tmp & GimbalDeviceFlags::all().bits()).ok_or(
ParserError::InvalidFlag {
flag_type: "GimbalDeviceFlags",
value: tmp as u32,
},
)?;
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
for val in &self.q {
_tmp.put_f32_le(*val);
}
_tmp.put_f32_le(self.angular_velocity_x);
_tmp.put_f32_le(self.angular_velocity_y);
_tmp.put_f32_le(self.angular_velocity_z);
_tmp.put_u16_le(self.flags.bits());
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 105"]
#[doc = "The IMU readings in SI units in NED body frame."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct HIGHRES_IMU_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "X acceleration."]
pub xacc: f32,
#[doc = "Y acceleration."]
pub yacc: f32,
#[doc = "Z acceleration."]
pub zacc: f32,
#[doc = "Angular speed around X axis."]
pub xgyro: f32,
#[doc = "Angular speed around Y axis."]
pub ygyro: f32,
#[doc = "Angular speed around Z axis."]
pub zgyro: f32,
#[doc = "X Magnetic field."]
pub xmag: f32,
#[doc = "Y Magnetic field."]
pub ymag: f32,
#[doc = "Z Magnetic field."]
pub zmag: f32,
#[doc = "Absolute pressure."]
pub abs_pressure: f32,
#[doc = "Differential pressure."]
pub diff_pressure: f32,
#[doc = "Altitude calculated from pressure."]
pub pressure_alt: f32,
#[doc = "Temperature."]
pub temperature: f32,
#[doc = "Bitmap for fields that have updated since last message."]
pub fields_updated: HighresImuUpdatedFlags,
#[doc = "Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)."]
#[cfg_attr(feature = "serde", serde(default))]
pub id: u8,
}
impl HIGHRES_IMU_DATA {
pub const ENCODED_LEN: usize = 63usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.xacc = buf.get_f32_le();
_struct.yacc = buf.get_f32_le();
_struct.zacc = buf.get_f32_le();
_struct.xgyro = buf.get_f32_le();
_struct.ygyro = buf.get_f32_le();
_struct.zgyro = buf.get_f32_le();
_struct.xmag = buf.get_f32_le();
_struct.ymag = buf.get_f32_le();
_struct.zmag = buf.get_f32_le();
_struct.abs_pressure = buf.get_f32_le();
_struct.diff_pressure = buf.get_f32_le();
_struct.pressure_alt = buf.get_f32_le();
_struct.temperature = buf.get_f32_le();
let tmp = buf.get_u16_le();
_struct.fields_updated = HighresImuUpdatedFlags::from_bits(
tmp & HighresImuUpdatedFlags::all().bits(),
)
.ok_or(ParserError::InvalidFlag {
flag_type: "HighresImuUpdatedFlags",
value: tmp as u32,
})?;
_struct.id = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_f32_le(self.xacc);
_tmp.put_f32_le(self.yacc);
_tmp.put_f32_le(self.zacc);
_tmp.put_f32_le(self.xgyro);
_tmp.put_f32_le(self.ygyro);
_tmp.put_f32_le(self.zgyro);
_tmp.put_f32_le(self.xmag);
_tmp.put_f32_le(self.ymag);
_tmp.put_f32_le(self.zmag);
_tmp.put_f32_le(self.abs_pressure);
_tmp.put_f32_le(self.diff_pressure);
_tmp.put_f32_le(self.pressure_alt);
_tmp.put_f32_le(self.temperature);
_tmp.put_u16_le(self.fields_updated.bits());
_tmp.put_u8(self.id);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 288"]
#[doc = "High level message to control a gimbal manually. The angles or angular rates are unitless; the actual rates will depend on internal gimbal manager settings/configuration (e.g. set by parameters). This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA {
#[doc = "High level gimbal manager flags.."]
pub flags: GimbalManagerFlags,
#[doc = "Pitch angle unitless (-1..1, positive: up, negative: down, NaN to be ignored).."]
pub pitch: f32,
#[doc = "Yaw angle unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored).."]
pub yaw: f32,
#[doc = "Pitch angular rate unitless (-1..1, positive: up, negative: down, NaN to be ignored).."]
pub pitch_rate: f32,
#[doc = "Yaw angular rate unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored).."]
pub yaw_rate: f32,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).."]
pub gimbal_device_id: u8,
}
impl GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA {
pub const ENCODED_LEN: usize = 23usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
let tmp = buf.get_u32_le();
_struct.flags = FromPrimitive::from_u32(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "GimbalManagerFlags",
value: tmp as u32,
})?;
_struct.pitch = buf.get_f32_le();
_struct.yaw = buf.get_f32_le();
_struct.pitch_rate = buf.get_f32_le();
_struct.yaw_rate = buf.get_f32_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
_struct.gimbal_device_id = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.flags as u32);
_tmp.put_f32_le(self.pitch);
_tmp.put_f32_le(self.yaw);
_tmp.put_f32_le(self.pitch_rate);
_tmp.put_f32_le(self.yaw_rate);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.gimbal_device_id);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 112"]
#[doc = "Camera-IMU triggering and synchronisation message.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct CAMERA_TRIGGER_DATA {
#[doc = "Timestamp for image frame (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.."]
pub time_usec: u64,
#[doc = "Image frame sequence."]
pub seq: u32,
}
impl CAMERA_TRIGGER_DATA {
pub const ENCODED_LEN: usize = 12usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.seq = buf.get_u32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_u32_le(self.seq);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 181"]
#[doc = "2nd Battery status."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct BATTERY2_DATA {
#[doc = "Voltage.."]
pub voltage: u16,
#[doc = "Battery current, -1: autopilot does not measure the current.."]
pub current_battery: i16,
}
impl BATTERY2_DATA {
pub const ENCODED_LEN: usize = 4usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.voltage = buf.get_u16_le();
_struct.current_battery = buf.get_i16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.voltage);
_tmp.put_i16_le(self.current_battery);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 185"]
#[doc = "Send Status of each log block that autopilot board might have sent.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct REMOTE_LOG_BLOCK_STATUS_DATA {
#[doc = "Log data block sequence number.."]
pub seqno: u32,
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Component ID.."]
pub target_component: u8,
#[doc = "Log data block status.."]
pub status: MavRemoteLogDataBlockStatuses,
}
impl REMOTE_LOG_BLOCK_STATUS_DATA {
pub const ENCODED_LEN: usize = 7usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.seqno = buf.get_u32_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
let tmp = buf.get_u8();
_struct.status = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavRemoteLogDataBlockStatuses",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.seqno);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.status as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 164"]
#[doc = "Status of simulation environment, if used.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct SIMSTATE_DATA {
#[doc = "Roll angle.."]
pub roll: f32,
#[doc = "Pitch angle.."]
pub pitch: f32,
#[doc = "Yaw angle.."]
pub yaw: f32,
#[doc = "X acceleration.."]
pub xacc: f32,
#[doc = "Y acceleration.."]
pub yacc: f32,
#[doc = "Z acceleration.."]
pub zacc: f32,
#[doc = "Angular speed around X axis.."]
pub xgyro: f32,
#[doc = "Angular speed around Y axis.."]
pub ygyro: f32,
#[doc = "Angular speed around Z axis.."]
pub zgyro: f32,
#[doc = "Latitude.."]
pub lat: i32,
#[doc = "Longitude.."]
pub lng: i32,
}
impl SIMSTATE_DATA {
pub const ENCODED_LEN: usize = 44usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.roll = buf.get_f32_le();
_struct.pitch = buf.get_f32_le();
_struct.yaw = buf.get_f32_le();
_struct.xacc = buf.get_f32_le();
_struct.yacc = buf.get_f32_le();
_struct.zacc = buf.get_f32_le();
_struct.xgyro = buf.get_f32_le();
_struct.ygyro = buf.get_f32_le();
_struct.zgyro = buf.get_f32_le();
_struct.lat = buf.get_i32_le();
_struct.lng = buf.get_i32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.roll);
_tmp.put_f32_le(self.pitch);
_tmp.put_f32_le(self.yaw);
_tmp.put_f32_le(self.xacc);
_tmp.put_f32_le(self.yacc);
_tmp.put_f32_le(self.zacc);
_tmp.put_f32_le(self.xgyro);
_tmp.put_f32_le(self.ygyro);
_tmp.put_f32_le(self.zgyro);
_tmp.put_i32_le(self.lat);
_tmp.put_i32_le(self.lng);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 165"]
#[doc = "Status of key hardware.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct HWSTATUS_DATA {
#[doc = "Board voltage.."]
pub Vcc: u16,
#[doc = "I2C error count.."]
pub I2Cerr: u8,
}
impl HWSTATUS_DATA {
pub const ENCODED_LEN: usize = 3usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.Vcc = buf.get_u16_le();
_struct.I2Cerr = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.Vcc);
_tmp.put_u8(self.I2Cerr);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 167"]
#[doc = "Status of AP_Limits. Sent in extended status stream when AP_Limits is enabled.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct LIMITS_STATUS_DATA {
#[doc = "Time (since boot) of last breach.."]
pub last_trigger: u32,
#[doc = "Time (since boot) of last recovery action.."]
pub last_action: u32,
#[doc = "Time (since boot) of last successful recovery.."]
pub last_recovery: u32,
#[doc = "Time (since boot) of last all-clear.."]
pub last_clear: u32,
#[doc = "Number of fence breaches.."]
pub breach_count: u16,
#[doc = "State of AP_Limits.."]
pub limits_state: LimitsState,
#[doc = "AP_Limit_Module bitfield of enabled modules.."]
pub mods_enabled: LimitModule,
#[doc = "AP_Limit_Module bitfield of required modules.."]
pub mods_required: LimitModule,
#[doc = "AP_Limit_Module bitfield of triggered modules.."]
pub mods_triggered: LimitModule,
}
impl LIMITS_STATUS_DATA {
pub const ENCODED_LEN: usize = 22usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.last_trigger = buf.get_u32_le();
_struct.last_action = buf.get_u32_le();
_struct.last_recovery = buf.get_u32_le();
_struct.last_clear = buf.get_u32_le();
_struct.breach_count = buf.get_u16_le();
let tmp = buf.get_u8();
_struct.limits_state = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "LimitsState",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.mods_enabled = LimitModule::from_bits(tmp & LimitModule::all().bits()).ok_or(
ParserError::InvalidFlag {
flag_type: "LimitModule",
value: tmp as u32,
},
)?;
let tmp = buf.get_u8();
_struct.mods_required = LimitModule::from_bits(tmp & LimitModule::all().bits()).ok_or(
ParserError::InvalidFlag {
flag_type: "LimitModule",
value: tmp as u32,
},
)?;
let tmp = buf.get_u8();
_struct.mods_triggered = LimitModule::from_bits(tmp & LimitModule::all().bits()).ok_or(
ParserError::InvalidFlag {
flag_type: "LimitModule",
value: tmp as u32,
},
)?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.last_trigger);
_tmp.put_u32_le(self.last_action);
_tmp.put_u32_le(self.last_recovery);
_tmp.put_u32_le(self.last_clear);
_tmp.put_u16_le(self.breach_count);
_tmp.put_u8(self.limits_state as u8);
_tmp.put_u8(self.mods_enabled.bits());
_tmp.put_u8(self.mods_required.bits());
_tmp.put_u8(self.mods_triggered.bits());
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 235"]
#[doc = "Message appropriate for high latency connections like Iridium (version 2)."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct HIGH_LATENCY2_DATA {
#[doc = "Timestamp (milliseconds since boot or Unix epoch)."]
pub timestamp: u32,
#[doc = "Latitude."]
pub latitude: i32,
#[doc = "Longitude."]
pub longitude: i32,
#[doc = "A bitfield for use for autopilot-specific flags (2 byte version).."]
pub custom_mode: u16,
#[doc = "Altitude above mean sea level."]
pub altitude: i16,
#[doc = "Altitude setpoint."]
pub target_altitude: i16,
#[doc = "Distance to target waypoint or position."]
pub target_distance: u16,
#[doc = "Current waypoint number."]
pub wp_num: u16,
#[doc = "Bitmap of failure flags.."]
pub failure_flags: HlFailureFlag,
#[doc = "Type of the MAV (quadrotor, helicopter, etc.)."]
pub mavtype: MavType,
#[doc = "Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.."]
pub autopilot: MavAutopilot,
#[doc = "Heading."]
pub heading: u8,
#[doc = "Heading setpoint."]
pub target_heading: u8,
#[doc = "Throttle."]
pub throttle: u8,
#[doc = "Airspeed."]
pub airspeed: u8,
#[doc = "Airspeed setpoint."]
pub airspeed_sp: u8,
#[doc = "Groundspeed."]
pub groundspeed: u8,
#[doc = "Windspeed."]
pub windspeed: u8,
#[doc = "Wind heading."]
pub wind_heading: u8,
#[doc = "Maximum error horizontal position since last message."]
pub eph: u8,
#[doc = "Maximum error vertical position since last message."]
pub epv: u8,
#[doc = "Air temperature from airspeed sensor."]
pub temperature_air: i8,
#[doc = "Maximum climb rate magnitude since last message."]
pub climb_rate: i8,
#[doc = "Battery level (-1 if field not provided).."]
pub battery: i8,
#[doc = "Field for custom payload.."]
pub custom0: i8,
#[doc = "Field for custom payload.."]
pub custom1: i8,
#[doc = "Field for custom payload.."]
pub custom2: i8,
}
impl HIGH_LATENCY2_DATA {
pub const ENCODED_LEN: usize = 42usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.timestamp = buf.get_u32_le();
_struct.latitude = buf.get_i32_le();
_struct.longitude = buf.get_i32_le();
_struct.custom_mode = buf.get_u16_le();
_struct.altitude = buf.get_i16_le();
_struct.target_altitude = buf.get_i16_le();
_struct.target_distance = buf.get_u16_le();
_struct.wp_num = buf.get_u16_le();
let tmp = buf.get_u16_le();
_struct.failure_flags = HlFailureFlag::from_bits(tmp & HlFailureFlag::all().bits()).ok_or(
ParserError::InvalidFlag {
flag_type: "HlFailureFlag",
value: tmp as u32,
},
)?;
let tmp = buf.get_u8();
_struct.mavtype = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavType",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.autopilot = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavAutopilot",
value: tmp as u32,
})?;
_struct.heading = buf.get_u8();
_struct.target_heading = buf.get_u8();
_struct.throttle = buf.get_u8();
_struct.airspeed = buf.get_u8();
_struct.airspeed_sp = buf.get_u8();
_struct.groundspeed = buf.get_u8();
_struct.windspeed = buf.get_u8();
_struct.wind_heading = buf.get_u8();
_struct.eph = buf.get_u8();
_struct.epv = buf.get_u8();
_struct.temperature_air = buf.get_i8();
_struct.climb_rate = buf.get_i8();
_struct.battery = buf.get_i8();
_struct.custom0 = buf.get_i8();
_struct.custom1 = buf.get_i8();
_struct.custom2 = buf.get_i8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.timestamp);
_tmp.put_i32_le(self.latitude);
_tmp.put_i32_le(self.longitude);
_tmp.put_u16_le(self.custom_mode);
_tmp.put_i16_le(self.altitude);
_tmp.put_i16_le(self.target_altitude);
_tmp.put_u16_le(self.target_distance);
_tmp.put_u16_le(self.wp_num);
_tmp.put_u16_le(self.failure_flags.bits());
_tmp.put_u8(self.mavtype as u8);
_tmp.put_u8(self.autopilot as u8);
_tmp.put_u8(self.heading);
_tmp.put_u8(self.target_heading);
_tmp.put_u8(self.throttle);
_tmp.put_u8(self.airspeed);
_tmp.put_u8(self.airspeed_sp);
_tmp.put_u8(self.groundspeed);
_tmp.put_u8(self.windspeed);
_tmp.put_u8(self.wind_heading);
_tmp.put_u8(self.eph);
_tmp.put_u8(self.epv);
_tmp.put_i8(self.temperature_air);
_tmp.put_i8(self.climb_rate);
_tmp.put_i8(self.battery);
_tmp.put_i8(self.custom0);
_tmp.put_i8(self.custom1);
_tmp.put_i8(self.custom2);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 261"]
#[doc = "Information about a storage medium. This message is sent in response to a request with MAV_CMD_REQUEST_MESSAGE and whenever the status of the storage changes (STORAGE_STATUS). Use MAV_CMD_REQUEST_MESSAGE.param2 to indicate the index/id of requested storage: 0 for all, 1 for first, 2 for second, etc.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct STORAGE_INFORMATION_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "Total capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.."]
pub total_capacity: f32,
#[doc = "Used capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.."]
pub used_capacity: f32,
#[doc = "Available storage capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.."]
pub available_capacity: f32,
#[doc = "Read speed.."]
pub read_speed: f32,
#[doc = "Write speed.."]
pub write_speed: f32,
#[doc = "Storage ID (1 for first, 2 for second, etc.)."]
pub storage_id: u8,
#[doc = "Number of storage devices."]
pub storage_count: u8,
#[doc = "Status of storage."]
pub status: StorageStatus,
#[doc = "Type of storage."]
#[cfg_attr(feature = "serde", serde(default))]
pub mavtype: StorageType,
#[doc = "Textual storage name to be used in UI (microSD 1, Internal Memory, etc.) This is a NULL terminated string. If it is exactly 32 characters long, add a terminating NULL. If this string is empty, the generic type is shown to the user.."]
#[cfg_attr(feature = "serde", serde(default))]
pub name: [u8; 32],
#[doc = "Flags indicating whether this instance is preferred storage for photos, videos, etc. Note: Implementations should initially set the flags on the system-default storage id used for saving media (if possible/supported). This setting can then be overridden using MAV_CMD_SET_STORAGE_USAGE. If the media usage flags are not set, a GCS may assume storage ID 1 is the default storage for all media types.."]
#[cfg_attr(feature = "serde", serde(default))]
pub storage_usage: StorageUsageFlag,
}
impl STORAGE_INFORMATION_DATA {
pub const ENCODED_LEN: usize = 61usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.total_capacity = buf.get_f32_le();
_struct.used_capacity = buf.get_f32_le();
_struct.available_capacity = buf.get_f32_le();
_struct.read_speed = buf.get_f32_le();
_struct.write_speed = buf.get_f32_le();
_struct.storage_id = buf.get_u8();
_struct.storage_count = buf.get_u8();
let tmp = buf.get_u8();
_struct.status = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "StorageStatus",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.mavtype = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "StorageType",
value: tmp as u32,
})?;
for idx in 0..32usize {
let val = buf.get_u8();
_struct.name[idx] = val;
}
let tmp = buf.get_u8();
_struct.storage_usage = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "StorageUsageFlag",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_f32_le(self.total_capacity);
_tmp.put_f32_le(self.used_capacity);
_tmp.put_f32_le(self.available_capacity);
_tmp.put_f32_le(self.read_speed);
_tmp.put_f32_le(self.write_speed);
_tmp.put_u8(self.storage_id);
_tmp.put_u8(self.storage_count);
_tmp.put_u8(self.status as u8);
_tmp.put_u8(self.mavtype as u8);
for val in &self.name {
_tmp.put_u8(*val);
}
_tmp.put_u8(self.storage_usage as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 148"]
#[doc = "Version and capability of autopilot software. This should be emitted in response to a request with MAV_CMD_REQUEST_MESSAGE.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct AUTOPILOT_VERSION_DATA {
#[doc = "Bitmap of capabilities."]
pub capabilities: MavProtocolCapability,
#[doc = "UID if provided by hardware (see uid2)."]
pub uid: u64,
#[doc = "Firmware version number."]
pub flight_sw_version: u32,
#[doc = "Middleware version number."]
pub middleware_sw_version: u32,
#[doc = "Operating system version number."]
pub os_sw_version: u32,
#[doc = "HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify https://github.com/PX4/PX4-Bootloader/blob/master/board_types.txt."]
pub board_version: u32,
#[doc = "ID of the board vendor."]
pub vendor_id: u16,
#[doc = "ID of the product."]
pub product_id: u16,
#[doc = "Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.."]
pub flight_custom_version: [u8; 8],
#[doc = "Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.."]
pub middleware_custom_version: [u8; 8],
#[doc = "Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.."]
pub os_custom_version: [u8; 8],
#[doc = "UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid)."]
#[cfg_attr(feature = "serde", serde(default))]
pub uid2: [u8; 18],
}
impl AUTOPILOT_VERSION_DATA {
pub const ENCODED_LEN: usize = 78usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
let tmp = buf.get_u64_le();
_struct.capabilities = MavProtocolCapability::from_bits(
tmp & MavProtocolCapability::all().bits(),
)
.ok_or(ParserError::InvalidFlag {
flag_type: "MavProtocolCapability",
value: tmp as u32,
})?;
_struct.uid = buf.get_u64_le();
_struct.flight_sw_version = buf.get_u32_le();
_struct.middleware_sw_version = buf.get_u32_le();
_struct.os_sw_version = buf.get_u32_le();
_struct.board_version = buf.get_u32_le();
_struct.vendor_id = buf.get_u16_le();
_struct.product_id = buf.get_u16_le();
for idx in 0..8usize {
let val = buf.get_u8();
_struct.flight_custom_version[idx] = val;
}
for idx in 0..8usize {
let val = buf.get_u8();
_struct.middleware_custom_version[idx] = val;
}
for idx in 0..8usize {
let val = buf.get_u8();
_struct.os_custom_version[idx] = val;
}
for idx in 0..18usize {
let val = buf.get_u8();
_struct.uid2[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.capabilities.bits());
_tmp.put_u64_le(self.uid);
_tmp.put_u32_le(self.flight_sw_version);
_tmp.put_u32_le(self.middleware_sw_version);
_tmp.put_u32_le(self.os_sw_version);
_tmp.put_u32_le(self.board_version);
_tmp.put_u16_le(self.vendor_id);
_tmp.put_u16_le(self.product_id);
for val in &self.flight_custom_version {
_tmp.put_u8(*val);
}
for val in &self.middleware_custom_version {
_tmp.put_u8(*val);
}
for val in &self.os_custom_version {
_tmp.put_u8(*val);
}
for val in &self.uid2 {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 47"]
#[doc = "Acknowledgment message during waypoint handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero).."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct MISSION_ACK_DATA {
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "Mission result.."]
pub mavtype: MavMissionResult,
#[doc = "Mission type.."]
#[cfg_attr(feature = "serde", serde(default))]
pub mission_type: MavMissionType,
}
impl MISSION_ACK_DATA {
pub const ENCODED_LEN: usize = 4usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
let tmp = buf.get_u8();
_struct.mavtype = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavMissionResult",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.mission_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavMissionType",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.mavtype as u8);
_tmp.put_u8(self.mission_type as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 161"]
#[doc = "Request a current fence point from MAV.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct FENCE_FETCH_POINT_DATA {
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Component ID.."]
pub target_component: u8,
#[doc = "Point index (first point is 1, 0 is for return point).."]
pub idx: u8,
}
impl FENCE_FETCH_POINT_DATA {
pub const ENCODED_LEN: usize = 3usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
_struct.idx = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.idx);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 156"]
#[doc = "Message to configure a camera mount, directional antenna, etc.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct MOUNT_CONFIGURE_DATA {
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Component ID.."]
pub target_component: u8,
#[doc = "Mount operating mode.."]
pub mount_mode: MavMountMode,
#[doc = "(1 = yes, 0 = no).."]
pub stab_roll: u8,
#[doc = "(1 = yes, 0 = no).."]
pub stab_pitch: u8,
#[doc = "(1 = yes, 0 = no).."]
pub stab_yaw: u8,
}
impl MOUNT_CONFIGURE_DATA {
pub const ENCODED_LEN: usize = 6usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
let tmp = buf.get_u8();
_struct.mount_mode = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavMountMode",
value: tmp as u32,
})?;
_struct.stab_roll = buf.get_u8();
_struct.stab_pitch = buf.get_u8();
_struct.stab_yaw = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.mount_mode as u8);
_tmp.put_u8(self.stab_roll);
_tmp.put_u8(self.stab_pitch);
_tmp.put_u8(self.stab_yaw);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 332"]
#[doc = "Describe a trajectory using an array of up-to 5 waypoints in the local frame (MAV_FRAME_LOCAL_NED).."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "X-coordinate of waypoint, set to NaN if not being used."]
pub pos_x: [f32; 5],
#[doc = "Y-coordinate of waypoint, set to NaN if not being used."]
pub pos_y: [f32; 5],
#[doc = "Z-coordinate of waypoint, set to NaN if not being used."]
pub pos_z: [f32; 5],
#[doc = "X-velocity of waypoint, set to NaN if not being used."]
pub vel_x: [f32; 5],
#[doc = "Y-velocity of waypoint, set to NaN if not being used."]
pub vel_y: [f32; 5],
#[doc = "Z-velocity of waypoint, set to NaN if not being used."]
pub vel_z: [f32; 5],
#[doc = "X-acceleration of waypoint, set to NaN if not being used."]
pub acc_x: [f32; 5],
#[doc = "Y-acceleration of waypoint, set to NaN if not being used."]
pub acc_y: [f32; 5],
#[doc = "Z-acceleration of waypoint, set to NaN if not being used."]
pub acc_z: [f32; 5],
#[doc = "Yaw angle, set to NaN if not being used."]
pub pos_yaw: [f32; 5],
#[doc = "Yaw rate, set to NaN if not being used."]
pub vel_yaw: [f32; 5],
#[doc = "MAV_CMD command id of waypoint, set to UINT16_MAX if not being used.."]
pub command: [u16; 5],
#[doc = "Number of valid points (up-to 5 waypoints are possible)."]
pub valid_points: u8,
}
impl TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA {
pub const ENCODED_LEN: usize = 239usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
for idx in 0..5usize {
let val = buf.get_f32_le();
_struct.pos_x[idx] = val;
}
for idx in 0..5usize {
let val = buf.get_f32_le();
_struct.pos_y[idx] = val;
}
for idx in 0..5usize {
let val = buf.get_f32_le();
_struct.pos_z[idx] = val;
}
for idx in 0..5usize {
let val = buf.get_f32_le();
_struct.vel_x[idx] = val;
}
for idx in 0..5usize {
let val = buf.get_f32_le();
_struct.vel_y[idx] = val;
}
for idx in 0..5usize {
let val = buf.get_f32_le();
_struct.vel_z[idx] = val;
}
for idx in 0..5usize {
let val = buf.get_f32_le();
_struct.acc_x[idx] = val;
}
for idx in 0..5usize {
let val = buf.get_f32_le();
_struct.acc_y[idx] = val;
}
for idx in 0..5usize {
let val = buf.get_f32_le();
_struct.acc_z[idx] = val;
}
for idx in 0..5usize {
let val = buf.get_f32_le();
_struct.pos_yaw[idx] = val;
}
for idx in 0..5usize {
let val = buf.get_f32_le();
_struct.vel_yaw[idx] = val;
}
for idx in 0..5usize {
let val = buf.get_u16_le();
_struct.command[idx] = val;
}
_struct.valid_points = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
for val in &self.pos_x {
_tmp.put_f32_le(*val);
}
for val in &self.pos_y {
_tmp.put_f32_le(*val);
}
for val in &self.pos_z {
_tmp.put_f32_le(*val);
}
for val in &self.vel_x {
_tmp.put_f32_le(*val);
}
for val in &self.vel_y {
_tmp.put_f32_le(*val);
}
for val in &self.vel_z {
_tmp.put_f32_le(*val);
}
for val in &self.acc_x {
_tmp.put_f32_le(*val);
}
for val in &self.acc_y {
_tmp.put_f32_le(*val);
}
for val in &self.acc_z {
_tmp.put_f32_le(*val);
}
for val in &self.pos_yaw {
_tmp.put_f32_le(*val);
}
for val in &self.vel_yaw {
_tmp.put_f32_le(*val);
}
for val in &self.command {
_tmp.put_u16_le(*val);
}
_tmp.put_u8(self.valid_points);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 5"]
#[doc = "Request to control this MAV."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct CHANGE_OPERATOR_CONTROL_DATA {
#[doc = "System the GCS requests control for."]
pub target_system: u8,
#[doc = "0: request control of this MAV, 1: Release control of this MAV."]
pub control_request: u8,
#[doc = "0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.."]
pub version: u8,
#[doc = "Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and \"!?,.-\"."]
pub passkey: [u8; 25],
}
impl CHANGE_OPERATOR_CONTROL_DATA {
pub const ENCODED_LEN: usize = 28usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.target_system = buf.get_u8();
_struct.control_request = buf.get_u8();
_struct.version = buf.get_u8();
for idx in 0..25usize {
let val = buf.get_u8();
_struct.passkey[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.control_request);
_tmp.put_u8(self.version);
for val in &self.passkey {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 395"]
#[doc = "Component information message, which may be requested using MAV_CMD_REQUEST_MESSAGE.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct COMPONENT_INFORMATION_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "CRC32 of the general metadata file (general_metadata_uri).."]
pub general_metadata_file_crc: u32,
#[doc = "CRC32 of peripherals metadata file (peripherals_metadata_uri).."]
pub peripherals_metadata_file_crc: u32,
#[doc = "MAVLink FTP URI for the general metadata file (COMP_METADATA_TYPE_GENERAL), which may be compressed with xz. The file contains general component metadata, and may contain URI links for additional metadata (see COMP_METADATA_TYPE). The information is static from boot, and may be generated at compile time. The string needs to be zero terminated.."]
pub general_metadata_uri: Vec<u8, 100>,
#[doc = "(Optional) MAVLink FTP URI for the peripherals metadata file (COMP_METADATA_TYPE_PERIPHERALS), which may be compressed with xz. This contains data about \"attached components\" such as UAVCAN nodes. The peripherals are in a separate file because the information must be generated dynamically at runtime. The string needs to be zero terminated.."]
pub peripherals_metadata_uri: Vec<u8, 100>,
}
impl COMPONENT_INFORMATION_DATA {
pub const ENCODED_LEN: usize = 212usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.general_metadata_file_crc = buf.get_u32_le();
_struct.peripherals_metadata_file_crc = buf.get_u32_le();
for _ in 0..100usize {
let val = buf.get_u8();
_struct.general_metadata_uri.push(val).unwrap();
}
for _ in 0..100usize {
let val = buf.get_u8();
_struct.peripherals_metadata_uri.push(val).unwrap();
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_u32_le(self.general_metadata_file_crc);
_tmp.put_u32_le(self.peripherals_metadata_file_crc);
for val in &self.general_metadata_uri {
_tmp.put_u8(*val);
}
for val in &self.peripherals_metadata_uri {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 1"]
#[doc = "The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows whether the system is currently active or not and if an emergency occurred. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occurred it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct SYS_STATUS_DATA {
#[doc = "Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present.."]
pub onboard_control_sensors_present: MavSysStatusSensor,
#[doc = "Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled.."]
pub onboard_control_sensors_enabled: MavSysStatusSensor,
#[doc = "Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy.."]
pub onboard_control_sensors_health: MavSysStatusSensor,
#[doc = "Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000."]
pub load: u16,
#[doc = "Battery voltage, UINT16_MAX: Voltage not sent by autopilot."]
pub voltage_battery: u16,
#[doc = "Battery current, -1: Current not sent by autopilot."]
pub current_battery: i16,
#[doc = "Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)."]
pub drop_rate_comm: u16,
#[doc = "Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)."]
pub errors_comm: u16,
#[doc = "Autopilot-specific errors."]
pub errors_count1: u16,
#[doc = "Autopilot-specific errors."]
pub errors_count2: u16,
#[doc = "Autopilot-specific errors."]
pub errors_count3: u16,
#[doc = "Autopilot-specific errors."]
pub errors_count4: u16,
#[doc = "Battery energy remaining, -1: Battery remaining energy not sent by autopilot."]
pub battery_remaining: i8,
#[doc = "Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present.."]
#[cfg_attr(feature = "serde", serde(default))]
pub onboard_control_sensors_present_extended: MavSysStatusSensorExtended,
#[doc = "Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled.."]
#[cfg_attr(feature = "serde", serde(default))]
pub onboard_control_sensors_enabled_extended: MavSysStatusSensorExtended,
#[doc = "Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy.."]
#[cfg_attr(feature = "serde", serde(default))]
pub onboard_control_sensors_health_extended: MavSysStatusSensorExtended,
}
impl SYS_STATUS_DATA {
pub const ENCODED_LEN: usize = 43usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
let tmp = buf.get_u32_le();
_struct.onboard_control_sensors_present = MavSysStatusSensor::from_bits(
tmp & MavSysStatusSensor::all().bits(),
)
.ok_or(ParserError::InvalidFlag {
flag_type: "MavSysStatusSensor",
value: tmp as u32,
})?;
let tmp = buf.get_u32_le();
_struct.onboard_control_sensors_enabled = MavSysStatusSensor::from_bits(
tmp & MavSysStatusSensor::all().bits(),
)
.ok_or(ParserError::InvalidFlag {
flag_type: "MavSysStatusSensor",
value: tmp as u32,
})?;
let tmp = buf.get_u32_le();
_struct.onboard_control_sensors_health = MavSysStatusSensor::from_bits(
tmp & MavSysStatusSensor::all().bits(),
)
.ok_or(ParserError::InvalidFlag {
flag_type: "MavSysStatusSensor",
value: tmp as u32,
})?;
_struct.load = buf.get_u16_le();
_struct.voltage_battery = buf.get_u16_le();
_struct.current_battery = buf.get_i16_le();
_struct.drop_rate_comm = buf.get_u16_le();
_struct.errors_comm = buf.get_u16_le();
_struct.errors_count1 = buf.get_u16_le();
_struct.errors_count2 = buf.get_u16_le();
_struct.errors_count3 = buf.get_u16_le();
_struct.errors_count4 = buf.get_u16_le();
_struct.battery_remaining = buf.get_i8();
let tmp = buf.get_u32_le();
_struct.onboard_control_sensors_present_extended =
MavSysStatusSensorExtended::from_bits(tmp & MavSysStatusSensorExtended::all().bits())
.ok_or(ParserError::InvalidFlag {
flag_type: "MavSysStatusSensorExtended",
value: tmp as u32,
})?;
let tmp = buf.get_u32_le();
_struct.onboard_control_sensors_enabled_extended =
MavSysStatusSensorExtended::from_bits(tmp & MavSysStatusSensorExtended::all().bits())
.ok_or(ParserError::InvalidFlag {
flag_type: "MavSysStatusSensorExtended",
value: tmp as u32,
})?;
let tmp = buf.get_u32_le();
_struct.onboard_control_sensors_health_extended =
MavSysStatusSensorExtended::from_bits(tmp & MavSysStatusSensorExtended::all().bits())
.ok_or(ParserError::InvalidFlag {
flag_type: "MavSysStatusSensorExtended",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.onboard_control_sensors_present.bits());
_tmp.put_u32_le(self.onboard_control_sensors_enabled.bits());
_tmp.put_u32_le(self.onboard_control_sensors_health.bits());
_tmp.put_u16_le(self.load);
_tmp.put_u16_le(self.voltage_battery);
_tmp.put_i16_le(self.current_battery);
_tmp.put_u16_le(self.drop_rate_comm);
_tmp.put_u16_le(self.errors_comm);
_tmp.put_u16_le(self.errors_count1);
_tmp.put_u16_le(self.errors_count2);
_tmp.put_u16_le(self.errors_count3);
_tmp.put_u16_le(self.errors_count4);
_tmp.put_i8(self.battery_remaining);
_tmp.put_u32_le(self.onboard_control_sensors_present_extended.bits());
_tmp.put_u32_le(self.onboard_control_sensors_enabled_extended.bits());
_tmp.put_u32_le(self.onboard_control_sensors_health_extended.bits());
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 11010"]
#[doc = "Adaptive Controller tuning information.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct ADAP_TUNING_DATA {
#[doc = "Desired rate.."]
pub desired: f32,
#[doc = "Achieved rate.."]
pub achieved: f32,
#[doc = "Error between model and vehicle.."]
pub error: f32,
#[doc = "Theta estimated state predictor.."]
pub theta: f32,
#[doc = "Omega estimated state predictor.."]
pub omega: f32,
#[doc = "Sigma estimated state predictor.."]
pub sigma: f32,
#[doc = "Theta derivative.."]
pub theta_dot: f32,
#[doc = "Omega derivative.."]
pub omega_dot: f32,
#[doc = "Sigma derivative.."]
pub sigma_dot: f32,
#[doc = "Projection operator value.."]
pub f: f32,
#[doc = "Projection operator derivative.."]
pub f_dot: f32,
#[doc = "u adaptive controlled output command.."]
pub u: f32,
#[doc = "Axis.."]
pub axis: PidTuningAxis,
}
impl ADAP_TUNING_DATA {
pub const ENCODED_LEN: usize = 49usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.desired = buf.get_f32_le();
_struct.achieved = buf.get_f32_le();
_struct.error = buf.get_f32_le();
_struct.theta = buf.get_f32_le();
_struct.omega = buf.get_f32_le();
_struct.sigma = buf.get_f32_le();
_struct.theta_dot = buf.get_f32_le();
_struct.omega_dot = buf.get_f32_le();
_struct.sigma_dot = buf.get_f32_le();
_struct.f = buf.get_f32_le();
_struct.f_dot = buf.get_f32_le();
_struct.u = buf.get_f32_le();
let tmp = buf.get_u8();
_struct.axis = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "PidTuningAxis",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.desired);
_tmp.put_f32_le(self.achieved);
_tmp.put_f32_le(self.error);
_tmp.put_f32_le(self.theta);
_tmp.put_f32_le(self.omega);
_tmp.put_f32_le(self.sigma);
_tmp.put_f32_le(self.theta_dot);
_tmp.put_f32_le(self.omega_dot);
_tmp.put_f32_le(self.sigma_dot);
_tmp.put_f32_le(self.f);
_tmp.put_f32_le(self.f_dot);
_tmp.put_f32_le(self.u);
_tmp.put_u8(self.axis as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 101"]
#[doc = "Global position/attitude estimate from a vision source.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct GLOBAL_VISION_POSITION_ESTIMATE_DATA {
#[doc = "Timestamp (UNIX time or since system boot)."]
pub usec: u64,
#[doc = "Global X position."]
pub x: f32,
#[doc = "Global Y position."]
pub y: f32,
#[doc = "Global Z position."]
pub z: f32,
#[doc = "Roll angle."]
pub roll: f32,
#[doc = "Pitch angle."]
pub pitch: f32,
#[doc = "Yaw angle."]
pub yaw: f32,
#[doc = "Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x_global, y_global, z_global, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.."]
#[cfg_attr(feature = "serde", serde(default))]
pub covariance: [f32; 21],
#[doc = "Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.."]
#[cfg_attr(feature = "serde", serde(default))]
pub reset_counter: u8,
}
impl GLOBAL_VISION_POSITION_ESTIMATE_DATA {
pub const ENCODED_LEN: usize = 117usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.usec = buf.get_u64_le();
_struct.x = buf.get_f32_le();
_struct.y = buf.get_f32_le();
_struct.z = buf.get_f32_le();
_struct.roll = buf.get_f32_le();
_struct.pitch = buf.get_f32_le();
_struct.yaw = buf.get_f32_le();
for idx in 0..21usize {
let val = buf.get_f32_le();
_struct.covariance[idx] = val;
}
_struct.reset_counter = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.usec);
_tmp.put_f32_le(self.x);
_tmp.put_f32_le(self.y);
_tmp.put_f32_le(self.z);
_tmp.put_f32_le(self.roll);
_tmp.put_f32_le(self.pitch);
_tmp.put_f32_le(self.yaw);
for val in &self.covariance {
_tmp.put_f32_le(*val);
}
_tmp.put_u8(self.reset_counter);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 154"]
#[doc = "Configure on-board Camera Control System.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct DIGICAM_CONFIGURE_DATA {
#[doc = "Correspondent value to given extra_param.."]
pub extra_value: f32,
#[doc = "Divisor number //e.g. 1000 means 1/1000 (0 means ignore).."]
pub shutter_speed: u16,
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Component ID.."]
pub target_component: u8,
#[doc = "Mode enumeration from 1 to N //P, TV, AV, M, etc. (0 means ignore).."]
pub mode: u8,
#[doc = "F stop number x 10 //e.g. 28 means 2.8 (0 means ignore).."]
pub aperture: u8,
#[doc = "ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore).."]
pub iso: u8,
#[doc = "Exposure type enumeration from 1 to N (0 means ignore).."]
pub exposure_type: u8,
#[doc = "Command Identity (incremental loop: 0 to 255). //A command sent multiple times will be executed or pooled just once.."]
pub command_id: u8,
#[doc = "Main engine cut-off time before camera trigger (0 means no cut-off).."]
pub engine_cut_off: u8,
#[doc = "Extra parameters enumeration (0 means ignore).."]
pub extra_param: u8,
}
impl DIGICAM_CONFIGURE_DATA {
pub const ENCODED_LEN: usize = 15usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.extra_value = buf.get_f32_le();
_struct.shutter_speed = buf.get_u16_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
_struct.mode = buf.get_u8();
_struct.aperture = buf.get_u8();
_struct.iso = buf.get_u8();
_struct.exposure_type = buf.get_u8();
_struct.command_id = buf.get_u8();
_struct.engine_cut_off = buf.get_u8();
_struct.extra_param = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.extra_value);
_tmp.put_u16_le(self.shutter_speed);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.mode);
_tmp.put_u8(self.aperture);
_tmp.put_u8(self.iso);
_tmp.put_u8(self.exposure_type);
_tmp.put_u8(self.command_id);
_tmp.put_u8(self.engine_cut_off);
_tmp.put_u8(self.extra_param);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 133"]
#[doc = "Request for terrain data and terrain status. See terrain protocol docs: https://mavlink.io/en/services/terrain.html."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct TERRAIN_REQUEST_DATA {
#[doc = "Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)."]
pub mask: u64,
#[doc = "Latitude of SW corner of first grid."]
pub lat: i32,
#[doc = "Longitude of SW corner of first grid."]
pub lon: i32,
#[doc = "Grid spacing."]
pub grid_spacing: u16,
}
impl TERRAIN_REQUEST_DATA {
pub const ENCODED_LEN: usize = 18usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.mask = buf.get_u64_le();
_struct.lat = buf.get_i32_le();
_struct.lon = buf.get_i32_le();
_struct.grid_spacing = buf.get_u16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.mask);
_tmp.put_i32_le(self.lat);
_tmp.put_i32_le(self.lon);
_tmp.put_u16_le(self.grid_spacing);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 172"]
#[doc = "Data packet, size 96.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct DATA96_DATA {
#[doc = "Data type.."]
pub mavtype: u8,
#[doc = "Data length.."]
pub len: u8,
#[doc = "Raw data.."]
pub data: Vec<u8, 96>,
}
impl DATA96_DATA {
pub const ENCODED_LEN: usize = 98usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.mavtype = buf.get_u8();
_struct.len = buf.get_u8();
for _ in 0..96usize {
let val = buf.get_u8();
_struct.data.push(val).unwrap();
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.mavtype);
_tmp.put_u8(self.len);
for val in &self.data {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 11035"]
#[doc = "Read a configured an OSD parameter slot.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct OSD_PARAM_SHOW_CONFIG_DATA {
#[doc = "Request ID - copied to reply.."]
pub request_id: u32,
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Component ID.."]
pub target_component: u8,
#[doc = "OSD parameter screen index.."]
pub osd_screen: u8,
#[doc = "OSD parameter display index.."]
pub osd_index: u8,
}
impl OSD_PARAM_SHOW_CONFIG_DATA {
pub const ENCODED_LEN: usize = 8usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.request_id = buf.get_u32_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
_struct.osd_screen = buf.get_u8();
_struct.osd_index = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.request_id);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.osd_screen);
_tmp.put_u8(self.osd_index);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 109"]
#[doc = "Status generated by radio and injected into MAVLink stream.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct RADIO_STATUS_DATA {
#[doc = "Count of radio packet receive errors (since boot).."]
pub rxerrors: u16,
#[doc = "Count of error corrected radio packets (since boot).."]
pub fixed: u16,
#[doc = "Local (message sender) received signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown.."]
pub rssi: u8,
#[doc = "Remote (message receiver) signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown.."]
pub remrssi: u8,
#[doc = "Remaining free transmitter buffer space.."]
pub txbuf: u8,
#[doc = "Local background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown.."]
pub noise: u8,
#[doc = "Remote background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown.."]
pub remnoise: u8,
}
impl RADIO_STATUS_DATA {
pub const ENCODED_LEN: usize = 9usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.rxerrors = buf.get_u16_le();
_struct.fixed = buf.get_u16_le();
_struct.rssi = buf.get_u8();
_struct.remrssi = buf.get_u8();
_struct.txbuf = buf.get_u8();
_struct.noise = buf.get_u8();
_struct.remnoise = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.rxerrors);
_tmp.put_u16_le(self.fixed);
_tmp.put_u8(self.rssi);
_tmp.put_u8(self.remrssi);
_tmp.put_u8(self.txbuf);
_tmp.put_u8(self.noise);
_tmp.put_u8(self.remnoise);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 27"]
#[doc = "The RAW IMU readings for a 9DOF sensor, which is identified by the id (default IMU1). This message should always contain the true raw values without any scaling to allow data capture and system debugging.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct RAW_IMU_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "X acceleration (raw)."]
pub xacc: i16,
#[doc = "Y acceleration (raw)."]
pub yacc: i16,
#[doc = "Z acceleration (raw)."]
pub zacc: i16,
#[doc = "Angular speed around X axis (raw)."]
pub xgyro: i16,
#[doc = "Angular speed around Y axis (raw)."]
pub ygyro: i16,
#[doc = "Angular speed around Z axis (raw)."]
pub zgyro: i16,
#[doc = "X Magnetic field (raw)."]
pub xmag: i16,
#[doc = "Y Magnetic field (raw)."]
pub ymag: i16,
#[doc = "Z Magnetic field (raw)."]
pub zmag: i16,
#[doc = "Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)."]
#[cfg_attr(feature = "serde", serde(default))]
pub id: u8,
#[doc = "Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C).."]
#[cfg_attr(feature = "serde", serde(default))]
pub temperature: i16,
}
impl RAW_IMU_DATA {
pub const ENCODED_LEN: usize = 29usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.xacc = buf.get_i16_le();
_struct.yacc = buf.get_i16_le();
_struct.zacc = buf.get_i16_le();
_struct.xgyro = buf.get_i16_le();
_struct.ygyro = buf.get_i16_le();
_struct.zgyro = buf.get_i16_le();
_struct.xmag = buf.get_i16_le();
_struct.ymag = buf.get_i16_le();
_struct.zmag = buf.get_i16_le();
_struct.id = buf.get_u8();
_struct.temperature = buf.get_i16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_i16_le(self.xacc);
_tmp.put_i16_le(self.yacc);
_tmp.put_i16_le(self.zacc);
_tmp.put_i16_le(self.xgyro);
_tmp.put_i16_le(self.ygyro);
_tmp.put_i16_le(self.zgyro);
_tmp.put_i16_le(self.xmag);
_tmp.put_i16_le(self.ymag);
_tmp.put_i16_le(self.zmag);
_tmp.put_u8(self.id);
_tmp.put_i16_le(self.temperature);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 39"]
#[doc = "Message encoding a mission item. This message is emitted to announce the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN may be used to indicate an optional/default value (e.g. to use the system's current latitude or yaw rather than a specific value). See also https://mavlink.io/en/services/mission.html.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct MISSION_ITEM_DATA {
#[doc = "PARAM1, see MAV_CMD enum."]
pub param1: f32,
#[doc = "PARAM2, see MAV_CMD enum."]
pub param2: f32,
#[doc = "PARAM3, see MAV_CMD enum."]
pub param3: f32,
#[doc = "PARAM4, see MAV_CMD enum."]
pub param4: f32,
#[doc = "PARAM5 / local: X coordinate, global: latitude."]
pub x: f32,
#[doc = "PARAM6 / local: Y coordinate, global: longitude."]
pub y: f32,
#[doc = "PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame).."]
pub z: f32,
#[doc = "Sequence."]
pub seq: u16,
#[doc = "The scheduled action for the waypoint.."]
pub command: MavCmd,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "The coordinate system of the waypoint.."]
pub frame: MavFrame,
#[doc = "false:0, true:1."]
pub current: u8,
#[doc = "Autocontinue to next waypoint. 0: false, 1: true. Set false to pause mission after the item completes.."]
pub autocontinue: u8,
#[doc = "Mission type.."]
#[cfg_attr(feature = "serde", serde(default))]
pub mission_type: MavMissionType,
}
impl MISSION_ITEM_DATA {
pub const ENCODED_LEN: usize = 38usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.param1 = buf.get_f32_le();
_struct.param2 = buf.get_f32_le();
_struct.param3 = buf.get_f32_le();
_struct.param4 = buf.get_f32_le();
_struct.x = buf.get_f32_le();
_struct.y = buf.get_f32_le();
_struct.z = buf.get_f32_le();
_struct.seq = buf.get_u16_le();
let tmp = buf.get_u16_le();
_struct.command = FromPrimitive::from_u16(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavCmd",
value: tmp as u32,
})?;
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
let tmp = buf.get_u8();
_struct.frame = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavFrame",
value: tmp as u32,
})?;
_struct.current = buf.get_u8();
_struct.autocontinue = buf.get_u8();
let tmp = buf.get_u8();
_struct.mission_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavMissionType",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.param1);
_tmp.put_f32_le(self.param2);
_tmp.put_f32_le(self.param3);
_tmp.put_f32_le(self.param4);
_tmp.put_f32_le(self.x);
_tmp.put_f32_le(self.y);
_tmp.put_f32_le(self.z);
_tmp.put_u16_le(self.seq);
_tmp.put_u16_le(self.command as u16);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.frame as u8);
_tmp.put_u8(self.current);
_tmp.put_u8(self.autocontinue);
_tmp.put_u8(self.mission_type as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 66"]
#[doc = "Request a data stream.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct REQUEST_DATA_STREAM_DATA {
#[doc = "The requested message rate."]
pub req_message_rate: u16,
#[doc = "The target requested to send the message stream.."]
pub target_system: u8,
#[doc = "The target requested to send the message stream.."]
pub target_component: u8,
#[doc = "The ID of the requested data stream."]
pub req_stream_id: u8,
#[doc = "1 to start sending, 0 to stop sending.."]
pub start_stop: u8,
}
impl REQUEST_DATA_STREAM_DATA {
pub const ENCODED_LEN: usize = 6usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.req_message_rate = buf.get_u16_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
_struct.req_stream_id = buf.get_u8();
_struct.start_stop = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.req_message_rate);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.req_stream_id);
_tmp.put_u8(self.start_stop);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 270"]
#[doc = "Information about the status of a video stream. It may be requested using MAV_CMD_REQUEST_MESSAGE.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct VIDEO_STREAM_STATUS_DATA {
#[doc = "Frame rate."]
pub framerate: f32,
#[doc = "Bit rate."]
pub bitrate: u32,
#[doc = "Bitmap of stream status flags."]
pub flags: VideoStreamStatusFlags,
#[doc = "Horizontal resolution."]
pub resolution_h: u16,
#[doc = "Vertical resolution."]
pub resolution_v: u16,
#[doc = "Video image rotation clockwise."]
pub rotation: u16,
#[doc = "Horizontal Field of view."]
pub hfov: u16,
#[doc = "Video Stream ID (1 for first, 2 for second, etc.)."]
pub stream_id: u8,
}
impl VIDEO_STREAM_STATUS_DATA {
pub const ENCODED_LEN: usize = 19usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.framerate = buf.get_f32_le();
_struct.bitrate = buf.get_u32_le();
let tmp = buf.get_u16_le();
_struct.flags = FromPrimitive::from_u16(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "VideoStreamStatusFlags",
value: tmp as u32,
})?;
_struct.resolution_h = buf.get_u16_le();
_struct.resolution_v = buf.get_u16_le();
_struct.rotation = buf.get_u16_le();
_struct.hfov = buf.get_u16_le();
_struct.stream_id = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.framerate);
_tmp.put_u32_le(self.bitrate);
_tmp.put_u16_le(self.flags as u16);
_tmp.put_u16_le(self.resolution_h);
_tmp.put_u16_le(self.resolution_v);
_tmp.put_u16_le(self.rotation);
_tmp.put_u16_le(self.hfov);
_tmp.put_u8(self.stream_id);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 121"]
#[doc = "Erase all logs."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct LOG_ERASE_DATA {
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
}
impl LOG_ERASE_DATA {
pub const ENCODED_LEN: usize = 2usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 69"]
#[doc = "This message provides an API for manually controlling the vehicle using standard joystick axes nomenclature, along with a joystick-like input device. Unused axes can be disabled and buttons states are transmitted as individual on/off bits of a bitmask."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct MANUAL_CONTROL_DATA {
#[doc = "X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.."]
pub x: i16,
#[doc = "Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.."]
pub y: i16,
#[doc = "Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust.."]
pub z: i16,
#[doc = "R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.."]
pub r: i16,
#[doc = "A bitfield corresponding to the joystick buttons' 0-15 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.."]
pub buttons: u16,
#[doc = "The system to be controlled.."]
pub target: u8,
#[doc = "A bitfield corresponding to the joystick buttons' 16-31 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 16.."]
#[cfg_attr(feature = "serde", serde(default))]
pub buttons2: u16,
#[doc = "Set bits to 1 to indicate which of the following extension fields contain valid data: bit 0: pitch, bit 1: roll.."]
#[cfg_attr(feature = "serde", serde(default))]
pub enabled_extensions: u8,
#[doc = "Pitch-only-axis, normalized to the range [-1000,1000]. Generally corresponds to pitch on vehicles with additional degrees of freedom. Valid if bit 0 of enabled_extensions field is set. Set to 0 if invalid.."]
#[cfg_attr(feature = "serde", serde(default))]
pub s: i16,
#[doc = "Roll-only-axis, normalized to the range [-1000,1000]. Generally corresponds to roll on vehicles with additional degrees of freedom. Valid if bit 1 of enabled_extensions field is set. Set to 0 if invalid.."]
#[cfg_attr(feature = "serde", serde(default))]
pub t: i16,
}
impl MANUAL_CONTROL_DATA {
pub const ENCODED_LEN: usize = 18usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.x = buf.get_i16_le();
_struct.y = buf.get_i16_le();
_struct.z = buf.get_i16_le();
_struct.r = buf.get_i16_le();
_struct.buttons = buf.get_u16_le();
_struct.target = buf.get_u8();
_struct.buttons2 = buf.get_u16_le();
_struct.enabled_extensions = buf.get_u8();
_struct.s = buf.get_i16_le();
_struct.t = buf.get_i16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_i16_le(self.x);
_tmp.put_i16_le(self.y);
_tmp.put_i16_le(self.z);
_tmp.put_i16_le(self.r);
_tmp.put_u16_le(self.buttons);
_tmp.put_u8(self.target);
_tmp.put_u16_le(self.buttons2);
_tmp.put_u8(self.enabled_extensions);
_tmp.put_i16_le(self.s);
_tmp.put_i16_le(self.t);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 76"]
#[doc = "Send a command with up to seven parameters to the MAV. COMMAND_INT is generally preferred when sending MAV_CMD commands where param 5 and param 6 contain latitude/longitude data, as sending these in floats can result in a significant loss of precision. COMMAND_LONG is required for commands that mandate float values in params 5 and 6. The command microservice is documented at https://mavlink.io/en/services/command.html."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct COMMAND_LONG_DATA {
#[doc = "Parameter 1 (for the specific command).."]
pub param1: f32,
#[doc = "Parameter 2 (for the specific command).."]
pub param2: f32,
#[doc = "Parameter 3 (for the specific command).."]
pub param3: f32,
#[doc = "Parameter 4 (for the specific command).."]
pub param4: f32,
#[doc = "Parameter 5 (for the specific command).."]
pub param5: f32,
#[doc = "Parameter 6 (for the specific command).."]
pub param6: f32,
#[doc = "Parameter 7 (for the specific command).."]
pub param7: f32,
#[doc = "Command ID (of command to send).."]
pub command: MavCmd,
#[doc = "System which should execute the command."]
pub target_system: u8,
#[doc = "Component which should execute the command, 0 for all components."]
pub target_component: u8,
#[doc = "0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)."]
pub confirmation: u8,
}
impl COMMAND_LONG_DATA {
pub const ENCODED_LEN: usize = 33usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.param1 = buf.get_f32_le();
_struct.param2 = buf.get_f32_le();
_struct.param3 = buf.get_f32_le();
_struct.param4 = buf.get_f32_le();
_struct.param5 = buf.get_f32_le();
_struct.param6 = buf.get_f32_le();
_struct.param7 = buf.get_f32_le();
let tmp = buf.get_u16_le();
_struct.command = FromPrimitive::from_u16(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavCmd",
value: tmp as u32,
})?;
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
_struct.confirmation = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.param1);
_tmp.put_f32_le(self.param2);
_tmp.put_f32_le(self.param3);
_tmp.put_f32_le(self.param4);
_tmp.put_f32_le(self.param5);
_tmp.put_f32_le(self.param6);
_tmp.put_f32_le(self.param7);
_tmp.put_u16_le(self.command as u16);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.confirmation);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 81"]
#[doc = "Setpoint in roll, pitch, yaw and thrust from the operator."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct MANUAL_SETPOINT_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "Desired roll rate."]
pub roll: f32,
#[doc = "Desired pitch rate."]
pub pitch: f32,
#[doc = "Desired yaw rate."]
pub yaw: f32,
#[doc = "Collective thrust, normalized to 0 .. 1."]
pub thrust: f32,
#[doc = "Flight mode switch position, 0.. 255."]
pub mode_switch: u8,
#[doc = "Override mode switch position, 0.. 255."]
pub manual_override_switch: u8,
}
impl MANUAL_SETPOINT_DATA {
pub const ENCODED_LEN: usize = 22usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.roll = buf.get_f32_le();
_struct.pitch = buf.get_f32_le();
_struct.yaw = buf.get_f32_le();
_struct.thrust = buf.get_f32_le();
_struct.mode_switch = buf.get_u8();
_struct.manual_override_switch = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_f32_le(self.roll);
_tmp.put_f32_le(self.pitch);
_tmp.put_f32_le(self.yaw);
_tmp.put_f32_le(self.thrust);
_tmp.put_u8(self.mode_switch);
_tmp.put_u8(self.manual_override_switch);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 12919"]
#[doc = "Update the data in the OPEN_DRONE_ID_SYSTEM message with new location information. This can be sent to update the location information for the operator when no other information in the SYSTEM message has changed. This message allows for efficient operation on radio links which have limited uplink bandwidth while meeting requirements for update frequency of the operator location.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct OPEN_DRONE_ID_SYSTEM_UPDATE_DATA {
#[doc = "Latitude of the operator. If unknown: 0 (both Lat/Lon).."]
pub operator_latitude: i32,
#[doc = "Longitude of the operator. If unknown: 0 (both Lat/Lon).."]
pub operator_longitude: i32,
#[doc = "Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m.."]
pub operator_altitude_geo: f32,
#[doc = "32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019.."]
pub timestamp: u32,
#[doc = "System ID (0 for broadcast).."]
pub target_system: u8,
#[doc = "Component ID (0 for broadcast).."]
pub target_component: u8,
}
impl OPEN_DRONE_ID_SYSTEM_UPDATE_DATA {
pub const ENCODED_LEN: usize = 18usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.operator_latitude = buf.get_i32_le();
_struct.operator_longitude = buf.get_i32_le();
_struct.operator_altitude_geo = buf.get_f32_le();
_struct.timestamp = buf.get_u32_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_i32_le(self.operator_latitude);
_tmp.put_i32_le(self.operator_longitude);
_tmp.put_f32_le(self.operator_altitude_geo);
_tmp.put_u32_le(self.timestamp);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 12904"]
#[doc = "Data for filling the OpenDroneID System message. The System Message contains general system information including the operator location/altitude and possible aircraft group and/or category/class information.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct OPEN_DRONE_ID_SYSTEM_DATA {
#[doc = "Latitude of the operator. If unknown: 0 (both Lat/Lon).."]
pub operator_latitude: i32,
#[doc = "Longitude of the operator. If unknown: 0 (both Lat/Lon).."]
pub operator_longitude: i32,
#[doc = "Area Operations Ceiling relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA.."]
pub area_ceiling: f32,
#[doc = "Area Operations Floor relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA.."]
pub area_floor: f32,
#[doc = "Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m.."]
pub operator_altitude_geo: f32,
#[doc = "32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019.."]
pub timestamp: u32,
#[doc = "Number of aircraft in the area, group or formation (default 1). Used only for swarms/multiple UA.."]
pub area_count: u16,
#[doc = "Radius of the cylindrical area of the group or formation (default 0). Used only for swarms/multiple UA.."]
pub area_radius: u16,
#[doc = "System ID (0 for broadcast).."]
pub target_system: u8,
#[doc = "Component ID (0 for broadcast).."]
pub target_component: u8,
#[doc = "Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.."]
pub id_or_mac: [u8; 20],
#[doc = "Specifies the operator location type.."]
pub operator_location_type: MavOdidOperatorLocationType,
#[doc = "Specifies the classification type of the UA.."]
pub classification_type: MavOdidClassificationType,
#[doc = "When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA.."]
pub category_eu: MavOdidCategoryEu,
#[doc = "When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA.."]
pub class_eu: MavOdidClassEu,
}
impl OPEN_DRONE_ID_SYSTEM_DATA {
pub const ENCODED_LEN: usize = 54usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.operator_latitude = buf.get_i32_le();
_struct.operator_longitude = buf.get_i32_le();
_struct.area_ceiling = buf.get_f32_le();
_struct.area_floor = buf.get_f32_le();
_struct.operator_altitude_geo = buf.get_f32_le();
_struct.timestamp = buf.get_u32_le();
_struct.area_count = buf.get_u16_le();
_struct.area_radius = buf.get_u16_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
for idx in 0..20usize {
let val = buf.get_u8();
_struct.id_or_mac[idx] = val;
}
let tmp = buf.get_u8();
_struct.operator_location_type =
FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavOdidOperatorLocationType",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.classification_type =
FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavOdidClassificationType",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.category_eu = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavOdidCategoryEu",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.class_eu = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavOdidClassEu",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_i32_le(self.operator_latitude);
_tmp.put_i32_le(self.operator_longitude);
_tmp.put_f32_le(self.area_ceiling);
_tmp.put_f32_le(self.area_floor);
_tmp.put_f32_le(self.operator_altitude_geo);
_tmp.put_u32_le(self.timestamp);
_tmp.put_u16_le(self.area_count);
_tmp.put_u16_le(self.area_radius);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
for val in &self.id_or_mac {
_tmp.put_u8(*val);
}
_tmp.put_u8(self.operator_location_type as u8);
_tmp.put_u8(self.classification_type as u8);
_tmp.put_u8(self.category_eu as u8);
_tmp.put_u8(self.class_eu as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 8"]
#[doc = "Status generated in each node in the communication chain and injected into MAVLink stream.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct LINK_NODE_STATUS_DATA {
#[doc = "Timestamp (time since system boot).."]
pub timestamp: u64,
#[doc = "Transmit rate."]
pub tx_rate: u32,
#[doc = "Receive rate."]
pub rx_rate: u32,
#[doc = "Messages sent."]
pub messages_sent: u32,
#[doc = "Messages received (estimated from counting seq)."]
pub messages_received: u32,
#[doc = "Messages lost (estimated from counting seq)."]
pub messages_lost: u32,
#[doc = "Number of bytes that could not be parsed correctly.."]
pub rx_parse_err: u16,
#[doc = "Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX."]
pub tx_overflows: u16,
#[doc = "Receive buffer overflows. This number wraps around as it reaches UINT16_MAX."]
pub rx_overflows: u16,
#[doc = "Remaining free transmit buffer space."]
pub tx_buf: u8,
#[doc = "Remaining free receive buffer space."]
pub rx_buf: u8,
}
impl LINK_NODE_STATUS_DATA {
pub const ENCODED_LEN: usize = 36usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.timestamp = buf.get_u64_le();
_struct.tx_rate = buf.get_u32_le();
_struct.rx_rate = buf.get_u32_le();
_struct.messages_sent = buf.get_u32_le();
_struct.messages_received = buf.get_u32_le();
_struct.messages_lost = buf.get_u32_le();
_struct.rx_parse_err = buf.get_u16_le();
_struct.tx_overflows = buf.get_u16_le();
_struct.rx_overflows = buf.get_u16_le();
_struct.tx_buf = buf.get_u8();
_struct.rx_buf = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.timestamp);
_tmp.put_u32_le(self.tx_rate);
_tmp.put_u32_le(self.rx_rate);
_tmp.put_u32_le(self.messages_sent);
_tmp.put_u32_le(self.messages_received);
_tmp.put_u32_le(self.messages_lost);
_tmp.put_u16_le(self.rx_parse_err);
_tmp.put_u16_le(self.tx_overflows);
_tmp.put_u16_le(self.rx_overflows);
_tmp.put_u8(self.tx_buf);
_tmp.put_u8(self.rx_buf);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 12903"]
#[doc = "Data for filling the OpenDroneID Self ID message. The Self ID Message is an opportunity for the operator to (optionally) declare their identity and purpose of the flight. This message can provide additional information that could reduce the threat profile of a UA (Unmanned Aircraft) flying in a particular area or manner. This message can also be used to provide optional additional clarification in an emergency/remote ID system failure situation.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct OPEN_DRONE_ID_SELF_ID_DATA {
#[doc = "System ID (0 for broadcast).."]
pub target_system: u8,
#[doc = "Component ID (0 for broadcast).."]
pub target_component: u8,
#[doc = "Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.."]
pub id_or_mac: [u8; 20],
#[doc = "Indicates the type of the description field.."]
pub description_type: MavOdidDescType,
#[doc = "Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field.."]
pub description: [u8; 23],
}
impl OPEN_DRONE_ID_SELF_ID_DATA {
pub const ENCODED_LEN: usize = 46usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
for idx in 0..20usize {
let val = buf.get_u8();
_struct.id_or_mac[idx] = val;
}
let tmp = buf.get_u8();
_struct.description_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavOdidDescType",
value: tmp as u32,
})?;
for idx in 0..23usize {
let val = buf.get_u8();
_struct.description[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
for val in &self.id_or_mac {
_tmp.put_u8(*val);
}
_tmp.put_u8(self.description_type as u8);
for val in &self.description {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 102"]
#[doc = "Local position/attitude estimate from a vision source.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct VISION_POSITION_ESTIMATE_DATA {
#[doc = "Timestamp (UNIX time or time since system boot)."]
pub usec: u64,
#[doc = "Local X position."]
pub x: f32,
#[doc = "Local Y position."]
pub y: f32,
#[doc = "Local Z position."]
pub z: f32,
#[doc = "Roll angle."]
pub roll: f32,
#[doc = "Pitch angle."]
pub pitch: f32,
#[doc = "Yaw angle."]
pub yaw: f32,
#[doc = "Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.."]
#[cfg_attr(feature = "serde", serde(default))]
pub covariance: [f32; 21],
#[doc = "Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.."]
#[cfg_attr(feature = "serde", serde(default))]
pub reset_counter: u8,
}
impl VISION_POSITION_ESTIMATE_DATA {
pub const ENCODED_LEN: usize = 117usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.usec = buf.get_u64_le();
_struct.x = buf.get_f32_le();
_struct.y = buf.get_f32_le();
_struct.z = buf.get_f32_le();
_struct.roll = buf.get_f32_le();
_struct.pitch = buf.get_f32_le();
_struct.yaw = buf.get_f32_le();
for idx in 0..21usize {
let val = buf.get_f32_le();
_struct.covariance[idx] = val;
}
_struct.reset_counter = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.usec);
_tmp.put_f32_le(self.x);
_tmp.put_f32_le(self.y);
_tmp.put_f32_le(self.z);
_tmp.put_f32_le(self.roll);
_tmp.put_f32_le(self.pitch);
_tmp.put_f32_le(self.yaw);
for val in &self.covariance {
_tmp.put_f32_le(*val);
}
_tmp.put_u8(self.reset_counter);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 11001"]
#[doc = "Read registers reply.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct DEVICE_OP_READ_REPLY_DATA {
#[doc = "Request ID - copied from request.."]
pub request_id: u32,
#[doc = "0 for success, anything else is failure code.."]
pub result: u8,
#[doc = "Starting register.."]
pub regstart: u8,
#[doc = "Count of bytes read.."]
pub count: u8,
#[doc = "Reply data.."]
pub data: Vec<u8, 128>,
#[doc = "Bank number.."]
#[cfg_attr(feature = "serde", serde(default))]
pub bank: u8,
}
impl DEVICE_OP_READ_REPLY_DATA {
pub const ENCODED_LEN: usize = 136usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.request_id = buf.get_u32_le();
_struct.result = buf.get_u8();
_struct.regstart = buf.get_u8();
_struct.count = buf.get_u8();
for _ in 0..128usize {
let val = buf.get_u8();
_struct.data.push(val).unwrap();
}
_struct.bank = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.request_id);
_tmp.put_u8(self.result);
_tmp.put_u8(self.regstart);
_tmp.put_u8(self.count);
for val in &self.data {
_tmp.put_u8(*val);
}
_tmp.put_u8(self.bank);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 12920"]
#[doc = "Temperature and humidity from hygrometer.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct HYGROMETER_SENSOR_DATA {
#[doc = "Temperature."]
pub temperature: i16,
#[doc = "Humidity."]
pub humidity: u16,
#[doc = "Hygrometer ID."]
pub id: u8,
}
impl HYGROMETER_SENSOR_DATA {
pub const ENCODED_LEN: usize = 5usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.temperature = buf.get_i16_le();
_struct.humidity = buf.get_u16_le();
_struct.id = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_i16_le(self.temperature);
_tmp.put_u16_le(self.humidity);
_tmp.put_u8(self.id);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 138"]
#[doc = "Motion capture attitude and position."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct ATT_POS_MOCAP_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)."]
pub q: [f32; 4],
#[doc = "X position (NED)."]
pub x: f32,
#[doc = "Y position (NED)."]
pub y: f32,
#[doc = "Z position (NED)."]
pub z: f32,
#[doc = "Row-major representation of a pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.."]
#[cfg_attr(feature = "serde", serde(default))]
pub covariance: [f32; 21],
}
impl ATT_POS_MOCAP_DATA {
pub const ENCODED_LEN: usize = 120usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
for idx in 0..4usize {
let val = buf.get_f32_le();
_struct.q[idx] = val;
}
_struct.x = buf.get_f32_le();
_struct.y = buf.get_f32_le();
_struct.z = buf.get_f32_le();
for idx in 0..21usize {
let val = buf.get_f32_le();
_struct.covariance[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
for val in &self.q {
_tmp.put_f32_le(*val);
}
_tmp.put_f32_le(self.x);
_tmp.put_f32_le(self.y);
_tmp.put_f32_le(self.z);
for val in &self.covariance {
_tmp.put_f32_le(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 65"]
#[doc = "The PPM values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. A value of UINT16_MAX implies the channel is unused. Individual receivers/transmitters might violate this specification.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct RC_CHANNELS_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "RC channel 1 value.."]
pub chan1_raw: u16,
#[doc = "RC channel 2 value.."]
pub chan2_raw: u16,
#[doc = "RC channel 3 value.."]
pub chan3_raw: u16,
#[doc = "RC channel 4 value.."]
pub chan4_raw: u16,
#[doc = "RC channel 5 value.."]
pub chan5_raw: u16,
#[doc = "RC channel 6 value.."]
pub chan6_raw: u16,
#[doc = "RC channel 7 value.."]
pub chan7_raw: u16,
#[doc = "RC channel 8 value.."]
pub chan8_raw: u16,
#[doc = "RC channel 9 value.."]
pub chan9_raw: u16,
#[doc = "RC channel 10 value.."]
pub chan10_raw: u16,
#[doc = "RC channel 11 value.."]
pub chan11_raw: u16,
#[doc = "RC channel 12 value.."]
pub chan12_raw: u16,
#[doc = "RC channel 13 value.."]
pub chan13_raw: u16,
#[doc = "RC channel 14 value.."]
pub chan14_raw: u16,
#[doc = "RC channel 15 value.."]
pub chan15_raw: u16,
#[doc = "RC channel 16 value.."]
pub chan16_raw: u16,
#[doc = "RC channel 17 value.."]
pub chan17_raw: u16,
#[doc = "RC channel 18 value.."]
pub chan18_raw: u16,
#[doc = "Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.."]
pub chancount: u8,
#[doc = "Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown.."]
pub rssi: u8,
}
impl RC_CHANNELS_DATA {
pub const ENCODED_LEN: usize = 42usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.chan1_raw = buf.get_u16_le();
_struct.chan2_raw = buf.get_u16_le();
_struct.chan3_raw = buf.get_u16_le();
_struct.chan4_raw = buf.get_u16_le();
_struct.chan5_raw = buf.get_u16_le();
_struct.chan6_raw = buf.get_u16_le();
_struct.chan7_raw = buf.get_u16_le();
_struct.chan8_raw = buf.get_u16_le();
_struct.chan9_raw = buf.get_u16_le();
_struct.chan10_raw = buf.get_u16_le();
_struct.chan11_raw = buf.get_u16_le();
_struct.chan12_raw = buf.get_u16_le();
_struct.chan13_raw = buf.get_u16_le();
_struct.chan14_raw = buf.get_u16_le();
_struct.chan15_raw = buf.get_u16_le();
_struct.chan16_raw = buf.get_u16_le();
_struct.chan17_raw = buf.get_u16_le();
_struct.chan18_raw = buf.get_u16_le();
_struct.chancount = buf.get_u8();
_struct.rssi = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_u16_le(self.chan1_raw);
_tmp.put_u16_le(self.chan2_raw);
_tmp.put_u16_le(self.chan3_raw);
_tmp.put_u16_le(self.chan4_raw);
_tmp.put_u16_le(self.chan5_raw);
_tmp.put_u16_le(self.chan6_raw);
_tmp.put_u16_le(self.chan7_raw);
_tmp.put_u16_le(self.chan8_raw);
_tmp.put_u16_le(self.chan9_raw);
_tmp.put_u16_le(self.chan10_raw);
_tmp.put_u16_le(self.chan11_raw);
_tmp.put_u16_le(self.chan12_raw);
_tmp.put_u16_le(self.chan13_raw);
_tmp.put_u16_le(self.chan14_raw);
_tmp.put_u16_le(self.chan15_raw);
_tmp.put_u16_le(self.chan16_raw);
_tmp.put_u16_le(self.chan17_raw);
_tmp.put_u16_le(self.chan18_raw);
_tmp.put_u8(self.chancount);
_tmp.put_u8(self.rssi);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 144"]
#[doc = "Current motion information from a designated system."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct FOLLOW_TARGET_DATA {
#[doc = "Timestamp (time since system boot).."]
pub timestamp: u64,
#[doc = "button states or switches of a tracker device."]
pub custom_state: u64,
#[doc = "Latitude (WGS84)."]
pub lat: i32,
#[doc = "Longitude (WGS84)."]
pub lon: i32,
#[doc = "Altitude (MSL)."]
pub alt: f32,
#[doc = "target velocity (0,0,0) for unknown."]
pub vel: [f32; 3],
#[doc = "linear target acceleration (0,0,0) for unknown."]
pub acc: [f32; 3],
#[doc = "(0 0 0 0 for unknown)."]
pub attitude_q: [f32; 4],
#[doc = "(0 0 0 for unknown)."]
pub rates: [f32; 3],
#[doc = "eph epv."]
pub position_cov: [f32; 3],
#[doc = "bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3)."]
pub est_capabilities: u8,
}
impl FOLLOW_TARGET_DATA {
pub const ENCODED_LEN: usize = 93usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.timestamp = buf.get_u64_le();
_struct.custom_state = buf.get_u64_le();
_struct.lat = buf.get_i32_le();
_struct.lon = buf.get_i32_le();
_struct.alt = buf.get_f32_le();
for idx in 0..3usize {
let val = buf.get_f32_le();
_struct.vel[idx] = val;
}
for idx in 0..3usize {
let val = buf.get_f32_le();
_struct.acc[idx] = val;
}
for idx in 0..4usize {
let val = buf.get_f32_le();
_struct.attitude_q[idx] = val;
}
for idx in 0..3usize {
let val = buf.get_f32_le();
_struct.rates[idx] = val;
}
for idx in 0..3usize {
let val = buf.get_f32_le();
_struct.position_cov[idx] = val;
}
_struct.est_capabilities = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.timestamp);
_tmp.put_u64_le(self.custom_state);
_tmp.put_i32_le(self.lat);
_tmp.put_i32_le(self.lon);
_tmp.put_f32_le(self.alt);
for val in &self.vel {
_tmp.put_f32_le(*val);
}
for val in &self.acc {
_tmp.put_f32_le(*val);
}
for val in &self.attitude_q {
_tmp.put_f32_le(*val);
}
for val in &self.rates {
_tmp.put_f32_le(*val);
}
for val in &self.position_cov {
_tmp.put_f32_le(*val);
}
_tmp.put_u8(self.est_capabilities);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 90"]
#[doc = "Sent from simulation to autopilot. This packet is useful for high throughput applications such as hardware in the loop simulations.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct HIL_STATE_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "Roll angle."]
pub roll: f32,
#[doc = "Pitch angle."]
pub pitch: f32,
#[doc = "Yaw angle."]
pub yaw: f32,
#[doc = "Body frame roll / phi angular speed."]
pub rollspeed: f32,
#[doc = "Body frame pitch / theta angular speed."]
pub pitchspeed: f32,
#[doc = "Body frame yaw / psi angular speed."]
pub yawspeed: f32,
#[doc = "Latitude."]
pub lat: i32,
#[doc = "Longitude."]
pub lon: i32,
#[doc = "Altitude."]
pub alt: i32,
#[doc = "Ground X Speed (Latitude)."]
pub vx: i16,
#[doc = "Ground Y Speed (Longitude)."]
pub vy: i16,
#[doc = "Ground Z Speed (Altitude)."]
pub vz: i16,
#[doc = "X acceleration."]
pub xacc: i16,
#[doc = "Y acceleration."]
pub yacc: i16,
#[doc = "Z acceleration."]
pub zacc: i16,
}
impl HIL_STATE_DATA {
pub const ENCODED_LEN: usize = 56usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.roll = buf.get_f32_le();
_struct.pitch = buf.get_f32_le();
_struct.yaw = buf.get_f32_le();
_struct.rollspeed = buf.get_f32_le();
_struct.pitchspeed = buf.get_f32_le();
_struct.yawspeed = buf.get_f32_le();
_struct.lat = buf.get_i32_le();
_struct.lon = buf.get_i32_le();
_struct.alt = buf.get_i32_le();
_struct.vx = buf.get_i16_le();
_struct.vy = buf.get_i16_le();
_struct.vz = buf.get_i16_le();
_struct.xacc = buf.get_i16_le();
_struct.yacc = buf.get_i16_le();
_struct.zacc = buf.get_i16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_f32_le(self.roll);
_tmp.put_f32_le(self.pitch);
_tmp.put_f32_le(self.yaw);
_tmp.put_f32_le(self.rollspeed);
_tmp.put_f32_le(self.pitchspeed);
_tmp.put_f32_le(self.yawspeed);
_tmp.put_i32_le(self.lat);
_tmp.put_i32_le(self.lon);
_tmp.put_i32_le(self.alt);
_tmp.put_i16_le(self.vx);
_tmp.put_i16_le(self.vy);
_tmp.put_i16_le(self.vz);
_tmp.put_i16_le(self.xacc);
_tmp.put_i16_le(self.yacc);
_tmp.put_i16_le(self.zacc);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 242"]
#[doc = "Contains the home position. \tThe home position is the default position that the system will return to and land on. \tThe position must be set automatically by the system during the takeoff, and may also be explicitly set using MAV_CMD_DO_SET_HOME. \tThe global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. \tUnder normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. \tThe approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. Note: this message can be requested by sending the MAV_CMD_REQUEST_MESSAGE with param1=242 (or the deprecated MAV_CMD_GET_HOME_POSITION command).."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct HOME_POSITION_DATA {
#[doc = "Latitude (WGS84)."]
pub latitude: i32,
#[doc = "Longitude (WGS84)."]
pub longitude: i32,
#[doc = "Altitude (MSL). Positive for up.."]
pub altitude: i32,
#[doc = "Local X position of this position in the local coordinate frame (NED)."]
pub x: f32,
#[doc = "Local Y position of this position in the local coordinate frame (NED)."]
pub y: f32,
#[doc = "Local Z position of this position in the local coordinate frame (NED: positive \"down\")."]
pub z: f32,
#[doc = "World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground."]
pub q: [f32; 4],
#[doc = "Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.."]
pub approach_x: f32,
#[doc = "Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.."]
pub approach_y: f32,
#[doc = "Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.."]
pub approach_z: f32,
#[doc = "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.."]
#[cfg_attr(feature = "serde", serde(default))]
pub time_usec: u64,
}
impl HOME_POSITION_DATA {
pub const ENCODED_LEN: usize = 60usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.latitude = buf.get_i32_le();
_struct.longitude = buf.get_i32_le();
_struct.altitude = buf.get_i32_le();
_struct.x = buf.get_f32_le();
_struct.y = buf.get_f32_le();
_struct.z = buf.get_f32_le();
for idx in 0..4usize {
let val = buf.get_f32_le();
_struct.q[idx] = val;
}
_struct.approach_x = buf.get_f32_le();
_struct.approach_y = buf.get_f32_le();
_struct.approach_z = buf.get_f32_le();
_struct.time_usec = buf.get_u64_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_i32_le(self.latitude);
_tmp.put_i32_le(self.longitude);
_tmp.put_i32_le(self.altitude);
_tmp.put_f32_le(self.x);
_tmp.put_f32_le(self.y);
_tmp.put_f32_le(self.z);
for val in &self.q {
_tmp.put_f32_le(*val);
}
_tmp.put_f32_le(self.approach_x);
_tmp.put_f32_le(self.approach_y);
_tmp.put_f32_le(self.approach_z);
_tmp.put_u64_le(self.time_usec);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 12901"]
#[doc = "Data for filling the OpenDroneID Location message. The float data types are 32-bit IEEE 754. The Location message provides the location, altitude, direction and speed of the aircraft.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct OPEN_DRONE_ID_LOCATION_DATA {
#[doc = "Current latitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon).."]
pub latitude: i32,
#[doc = "Current longitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon).."]
pub longitude: i32,
#[doc = "The altitude calculated from the barometric pressue. Reference is against 29.92inHg or 1013.2mb. If unknown: -1000 m.."]
pub altitude_barometric: f32,
#[doc = "The geodetic altitude as defined by WGS84. If unknown: -1000 m.."]
pub altitude_geodetic: f32,
#[doc = "The current height of the unmanned aircraft above the take-off location or the ground as indicated by height_reference. If unknown: -1000 m.."]
pub height: f32,
#[doc = "Seconds after the full hour with reference to UTC time. Typically the GPS outputs a time-of-week value in milliseconds. First convert that to UTC and then convert for this field using ((float) (time_week_ms % (60*60*1000))) / 1000. If unknown: 0xFFFF.."]
pub timestamp: f32,
#[doc = "Direction over ground (not heading, but direction of movement) measured clockwise from true North: 0 - 35999 centi-degrees. If unknown: 36100 centi-degrees.."]
pub direction: u16,
#[doc = "Ground speed. Positive only. If unknown: 25500 cm/s. If speed is larger than 25425 cm/s, use 25425 cm/s.."]
pub speed_horizontal: u16,
#[doc = "The vertical speed. Up is positive. If unknown: 6300 cm/s. If speed is larger than 6200 cm/s, use 6200 cm/s. If lower than -6200 cm/s, use -6200 cm/s.."]
pub speed_vertical: i16,
#[doc = "System ID (0 for broadcast).."]
pub target_system: u8,
#[doc = "Component ID (0 for broadcast).."]
pub target_component: u8,
#[doc = "Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.."]
pub id_or_mac: [u8; 20],
#[doc = "Indicates whether the unmanned aircraft is on the ground or in the air.."]
pub status: MavOdidStatus,
#[doc = "Indicates the reference point for the height field.."]
pub height_reference: MavOdidHeightRef,
#[doc = "The accuracy of the horizontal position.."]
pub horizontal_accuracy: MavOdidHorAcc,
#[doc = "The accuracy of the vertical position.."]
pub vertical_accuracy: MavOdidVerAcc,
#[doc = "The accuracy of the barometric altitude.."]
pub barometer_accuracy: MavOdidVerAcc,
#[doc = "The accuracy of the horizontal and vertical speed.."]
pub speed_accuracy: MavOdidSpeedAcc,
#[doc = "The accuracy of the timestamps.."]
pub timestamp_accuracy: MavOdidTimeAcc,
}
impl OPEN_DRONE_ID_LOCATION_DATA {
pub const ENCODED_LEN: usize = 59usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.latitude = buf.get_i32_le();
_struct.longitude = buf.get_i32_le();
_struct.altitude_barometric = buf.get_f32_le();
_struct.altitude_geodetic = buf.get_f32_le();
_struct.height = buf.get_f32_le();
_struct.timestamp = buf.get_f32_le();
_struct.direction = buf.get_u16_le();
_struct.speed_horizontal = buf.get_u16_le();
_struct.speed_vertical = buf.get_i16_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
for idx in 0..20usize {
let val = buf.get_u8();
_struct.id_or_mac[idx] = val;
}
let tmp = buf.get_u8();
_struct.status = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavOdidStatus",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.height_reference = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavOdidHeightRef",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.horizontal_accuracy =
FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavOdidHorAcc",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.vertical_accuracy =
FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavOdidVerAcc",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.barometer_accuracy =
FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavOdidVerAcc",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.speed_accuracy = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavOdidSpeedAcc",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.timestamp_accuracy =
FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavOdidTimeAcc",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_i32_le(self.latitude);
_tmp.put_i32_le(self.longitude);
_tmp.put_f32_le(self.altitude_barometric);
_tmp.put_f32_le(self.altitude_geodetic);
_tmp.put_f32_le(self.height);
_tmp.put_f32_le(self.timestamp);
_tmp.put_u16_le(self.direction);
_tmp.put_u16_le(self.speed_horizontal);
_tmp.put_i16_le(self.speed_vertical);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
for val in &self.id_or_mac {
_tmp.put_u8(*val);
}
_tmp.put_u8(self.status as u8);
_tmp.put_u8(self.height_reference as u8);
_tmp.put_u8(self.horizontal_accuracy as u8);
_tmp.put_u8(self.vertical_accuracy as u8);
_tmp.put_u8(self.barometer_accuracy as u8);
_tmp.put_u8(self.speed_accuracy as u8);
_tmp.put_u8(self.timestamp_accuracy as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 67"]
#[doc = "Data stream status information.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct DATA_STREAM_DATA {
#[doc = "The message rate."]
pub message_rate: u16,
#[doc = "The ID of the requested data stream."]
pub stream_id: u8,
#[doc = "1 stream is enabled, 0 stream is stopped.."]
pub on_off: u8,
}
impl DATA_STREAM_DATA {
pub const ENCODED_LEN: usize = 4usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.message_rate = buf.get_u16_le();
_struct.stream_id = buf.get_u8();
_struct.on_off = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.message_rate);
_tmp.put_u8(self.stream_id);
_tmp.put_u8(self.on_off);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 45"]
#[doc = "Delete all mission items at once.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct MISSION_CLEAR_ALL_DATA {
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "Mission type.."]
#[cfg_attr(feature = "serde", serde(default))]
pub mission_type: MavMissionType,
}
impl MISSION_CLEAR_ALL_DATA {
pub const ENCODED_LEN: usize = 3usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
let tmp = buf.get_u8();
_struct.mission_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavMissionType",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.mission_type as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 280"]
#[doc = "Information about a high level gimbal manager. This message should be requested by a ground station using MAV_CMD_REQUEST_MESSAGE.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct GIMBAL_MANAGER_INFORMATION_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "Bitmap of gimbal capability flags.."]
pub cap_flags: GimbalManagerCapFlags,
#[doc = "Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left)."]
pub roll_min: f32,
#[doc = "Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left)."]
pub roll_max: f32,
#[doc = "Minimum pitch angle (positive: up, negative: down)."]
pub pitch_min: f32,
#[doc = "Maximum pitch angle (positive: up, negative: down)."]
pub pitch_max: f32,
#[doc = "Minimum yaw angle (positive: to the right, negative: to the left)."]
pub yaw_min: f32,
#[doc = "Maximum yaw angle (positive: to the right, negative: to the left)."]
pub yaw_max: f32,
#[doc = "Gimbal device ID that this gimbal manager is responsible for.."]
pub gimbal_device_id: u8,
}
impl GIMBAL_MANAGER_INFORMATION_DATA {
pub const ENCODED_LEN: usize = 33usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
let tmp = buf.get_u32_le();
_struct.cap_flags = GimbalManagerCapFlags::from_bits(
tmp & GimbalManagerCapFlags::all().bits(),
)
.ok_or(ParserError::InvalidFlag {
flag_type: "GimbalManagerCapFlags",
value: tmp as u32,
})?;
_struct.roll_min = buf.get_f32_le();
_struct.roll_max = buf.get_f32_le();
_struct.pitch_min = buf.get_f32_le();
_struct.pitch_max = buf.get_f32_le();
_struct.yaw_min = buf.get_f32_le();
_struct.yaw_max = buf.get_f32_le();
_struct.gimbal_device_id = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_u32_le(self.cap_flags.bits());
_tmp.put_f32_le(self.roll_min);
_tmp.put_f32_le(self.roll_max);
_tmp.put_f32_le(self.pitch_min);
_tmp.put_f32_le(self.pitch_max);
_tmp.put_f32_le(self.yaw_min);
_tmp.put_f32_le(self.yaw_max);
_tmp.put_u8(self.gimbal_device_id);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 103"]
#[doc = "Speed estimate from a vision source.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct VISION_SPEED_ESTIMATE_DATA {
#[doc = "Timestamp (UNIX time or time since system boot)."]
pub usec: u64,
#[doc = "Global X speed."]
pub x: f32,
#[doc = "Global Y speed."]
pub y: f32,
#[doc = "Global Z speed."]
pub z: f32,
#[doc = "Row-major representation of 3x3 linear velocity covariance matrix (states: vx, vy, vz; 1st three entries - 1st row, etc.). If unknown, assign NaN value to first element in the array.."]
#[cfg_attr(feature = "serde", serde(default))]
pub covariance: [f32; 9],
#[doc = "Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.."]
#[cfg_attr(feature = "serde", serde(default))]
pub reset_counter: u8,
}
impl VISION_SPEED_ESTIMATE_DATA {
pub const ENCODED_LEN: usize = 57usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.usec = buf.get_u64_le();
_struct.x = buf.get_f32_le();
_struct.y = buf.get_f32_le();
_struct.z = buf.get_f32_le();
for idx in 0..9usize {
let val = buf.get_f32_le();
_struct.covariance[idx] = val;
}
_struct.reset_counter = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.usec);
_tmp.put_f32_le(self.x);
_tmp.put_f32_le(self.y);
_tmp.put_f32_le(self.z);
for val in &self.covariance {
_tmp.put_f32_le(*val);
}
_tmp.put_u8(self.reset_counter);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 290"]
#[doc = "ESC information for lower rate streaming. Recommended streaming rate 1Hz. See ESC_STATUS for higher-rate ESC data.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct ESC_INFO_DATA {
#[doc = "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 the number.."]
pub time_usec: u64,
#[doc = "Number of reported errors by each ESC since boot.."]
pub error_count: [u32; 4],
#[doc = "Counter of data packets received.."]
pub counter: u16,
#[doc = "Bitmap of ESC failure flags.."]
pub failure_flags: [u16; 4],
#[doc = "Temperature of each ESC. INT16_MAX: if data not supplied by ESC.."]
pub temperature: [i16; 4],
#[doc = "Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.."]
pub index: u8,
#[doc = "Total number of ESCs in all messages of this type. Message fields with an index higher than this should be ignored because they contain invalid data.."]
pub count: u8,
#[doc = "Connection type protocol for all ESC.."]
pub connection_type: EscConnectionType,
#[doc = "Information regarding online/offline status of each ESC.."]
pub info: u8,
}
impl ESC_INFO_DATA {
pub const ENCODED_LEN: usize = 46usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
for idx in 0..4usize {
let val = buf.get_u32_le();
_struct.error_count[idx] = val;
}
_struct.counter = buf.get_u16_le();
for idx in 0..4usize {
let val = buf.get_u16_le();
_struct.failure_flags[idx] = val;
}
for idx in 0..4usize {
let val = buf.get_i16_le();
_struct.temperature[idx] = val;
}
_struct.index = buf.get_u8();
_struct.count = buf.get_u8();
let tmp = buf.get_u8();
_struct.connection_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "EscConnectionType",
value: tmp as u32,
})?;
_struct.info = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
for val in &self.error_count {
_tmp.put_u32_le(*val);
}
_tmp.put_u16_le(self.counter);
for val in &self.failure_flags {
_tmp.put_u16_le(*val);
}
for val in &self.temperature {
_tmp.put_i16_le(*val);
}
_tmp.put_u8(self.index);
_tmp.put_u8(self.count);
_tmp.put_u8(self.connection_type as u8);
_tmp.put_u8(self.info);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 169"]
#[doc = "Data packet, size 16.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct DATA16_DATA {
#[doc = "Data type.."]
pub mavtype: u8,
#[doc = "Data length.."]
pub len: u8,
#[doc = "Raw data.."]
pub data: [u8; 16],
}
impl DATA16_DATA {
pub const ENCODED_LEN: usize = 18usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.mavtype = buf.get_u8();
_struct.len = buf.get_u8();
for idx in 0..16usize {
let val = buf.get_u8();
_struct.data[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.mavtype);
_tmp.put_u8(self.len);
for val in &self.data {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 249"]
#[doc = "Send raw controller memory. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct MEMORY_VECT_DATA {
#[doc = "Starting address of the debug variables."]
pub address: u16,
#[doc = "Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below."]
pub ver: u8,
#[doc = "Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14."]
pub mavtype: u8,
#[doc = "Memory contents at specified address."]
pub value: [i8; 32],
}
impl MEMORY_VECT_DATA {
pub const ENCODED_LEN: usize = 36usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.address = buf.get_u16_le();
_struct.ver = buf.get_u8();
_struct.mavtype = buf.get_u8();
for idx in 0..32usize {
let val = buf.get_i8();
_struct.value[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.address);
_tmp.put_u8(self.ver);
_tmp.put_u8(self.mavtype);
for val in &self.value {
_tmp.put_i8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 191"]
#[doc = "Reports progress of compass calibration.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct MAG_CAL_PROGRESS_DATA {
#[doc = "Body frame direction vector for display.."]
pub direction_x: f32,
#[doc = "Body frame direction vector for display.."]
pub direction_y: f32,
#[doc = "Body frame direction vector for display.."]
pub direction_z: f32,
#[doc = "Compass being calibrated.."]
pub compass_id: u8,
#[doc = "Bitmask of compasses being calibrated.."]
pub cal_mask: u8,
#[doc = "Calibration Status.."]
pub cal_status: MagCalStatus,
#[doc = "Attempt number.."]
pub attempt: u8,
#[doc = "Completion percentage.."]
pub completion_pct: u8,
#[doc = "Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid).."]
pub completion_mask: [u8; 10],
}
impl MAG_CAL_PROGRESS_DATA {
pub const ENCODED_LEN: usize = 27usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.direction_x = buf.get_f32_le();
_struct.direction_y = buf.get_f32_le();
_struct.direction_z = buf.get_f32_le();
_struct.compass_id = buf.get_u8();
_struct.cal_mask = buf.get_u8();
let tmp = buf.get_u8();
_struct.cal_status = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MagCalStatus",
value: tmp as u32,
})?;
_struct.attempt = buf.get_u8();
_struct.completion_pct = buf.get_u8();
for idx in 0..10usize {
let val = buf.get_u8();
_struct.completion_mask[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.direction_x);
_tmp.put_f32_le(self.direction_y);
_tmp.put_f32_le(self.direction_z);
_tmp.put_u8(self.compass_id);
_tmp.put_u8(self.cal_mask);
_tmp.put_u8(self.cal_status as u8);
_tmp.put_u8(self.attempt);
_tmp.put_u8(self.completion_pct);
for val in &self.completion_mask {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 46"]
#[doc = "A certain mission item has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next waypoint.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct MISSION_ITEM_REACHED_DATA {
#[doc = "Sequence."]
pub seq: u16,
}
impl MISSION_ITEM_REACHED_DATA {
pub const ENCODED_LEN: usize = 2usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.seq = buf.get_u16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.seq);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 265"]
#[doc = "Orientation of a mount."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct MOUNT_ORIENTATION_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "Roll in global frame (set to NaN for invalid).."]
pub roll: f32,
#[doc = "Pitch in global frame (set to NaN for invalid).."]
pub pitch: f32,
#[doc = "Yaw relative to vehicle (set to NaN for invalid).."]
pub yaw: f32,
#[doc = "Yaw in absolute frame relative to Earth's North, north is 0 (set to NaN for invalid).."]
#[cfg_attr(feature = "serde", serde(default))]
pub yaw_absolute: f32,
}
impl MOUNT_ORIENTATION_DATA {
pub const ENCODED_LEN: usize = 20usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.roll = buf.get_f32_le();
_struct.pitch = buf.get_f32_le();
_struct.yaw = buf.get_f32_le();
_struct.yaw_absolute = buf.get_f32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_f32_le(self.roll);
_tmp.put_f32_le(self.pitch);
_tmp.put_f32_le(self.yaw);
_tmp.put_f32_le(self.yaw_absolute);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 11000"]
#[doc = "Read registers for a device.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct DEVICE_OP_READ_DATA {
#[doc = "Request ID - copied to reply.."]
pub request_id: u32,
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Component ID.."]
pub target_component: u8,
#[doc = "The bus type.."]
pub bustype: DeviceOpBustype,
#[doc = "Bus number.."]
pub bus: u8,
#[doc = "Bus address.."]
pub address: u8,
#[doc = "Name of device on bus (for SPI).."]
pub busname: Vec<u8, 40>,
#[doc = "First register to read.."]
pub regstart: u8,
#[doc = "Count of registers to read.."]
pub count: u8,
#[doc = "Bank number.."]
#[cfg_attr(feature = "serde", serde(default))]
pub bank: u8,
}
impl DEVICE_OP_READ_DATA {
pub const ENCODED_LEN: usize = 52usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.request_id = buf.get_u32_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
let tmp = buf.get_u8();
_struct.bustype = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "DeviceOpBustype",
value: tmp as u32,
})?;
_struct.bus = buf.get_u8();
_struct.address = buf.get_u8();
for _ in 0..40usize {
let val = buf.get_u8();
_struct.busname.push(val).unwrap();
}
_struct.regstart = buf.get_u8();
_struct.count = buf.get_u8();
_struct.bank = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.request_id);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.bustype as u8);
_tmp.put_u8(self.bus);
_tmp.put_u8(self.address);
for val in &self.busname {
_tmp.put_u8(*val);
}
_tmp.put_u8(self.regstart);
_tmp.put_u8(self.count);
_tmp.put_u8(self.bank);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 74"]
#[doc = "Metrics typically displayed on a HUD for fixed wing aircraft.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct VFR_HUD_DATA {
#[doc = "Vehicle speed in form appropriate for vehicle type. For standard aircraft this is typically calibrated airspeed (CAS) or indicated airspeed (IAS) - either of which can be used by a pilot to estimate stall speed.."]
pub airspeed: f32,
#[doc = "Current ground speed.."]
pub groundspeed: f32,
#[doc = "Current altitude (MSL).."]
pub alt: f32,
#[doc = "Current climb rate.."]
pub climb: f32,
#[doc = "Current heading in compass units (0-360, 0=north).."]
pub heading: i16,
#[doc = "Current throttle setting (0 to 100).."]
pub throttle: u16,
}
impl VFR_HUD_DATA {
pub const ENCODED_LEN: usize = 20usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.airspeed = buf.get_f32_le();
_struct.groundspeed = buf.get_f32_le();
_struct.alt = buf.get_f32_le();
_struct.climb = buf.get_f32_le();
_struct.heading = buf.get_i16_le();
_struct.throttle = buf.get_u16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.airspeed);
_tmp.put_f32_le(self.groundspeed);
_tmp.put_f32_le(self.alt);
_tmp.put_f32_le(self.climb);
_tmp.put_i16_le(self.heading);
_tmp.put_u16_le(self.throttle);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 411"]
#[doc = "Regular broadcast for the current latest event sequence number for a component. This is used to check for dropped events.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct CURRENT_EVENT_SEQUENCE_DATA {
#[doc = "Sequence number.."]
pub sequence: u16,
#[doc = "Flag bitset.."]
pub flags: MavEventCurrentSequenceFlags,
}
impl CURRENT_EVENT_SEQUENCE_DATA {
pub const ENCODED_LEN: usize = 3usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.sequence = buf.get_u16_le();
let tmp = buf.get_u8();
_struct.flags = MavEventCurrentSequenceFlags::from_bits(
tmp & MavEventCurrentSequenceFlags::all().bits(),
)
.ok_or(ParserError::InvalidFlag {
flag_type: "MavEventCurrentSequenceFlags",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.sequence);
_tmp.put_u8(self.flags.bits());
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 30"]
#[doc = "The attitude in the aeronautical frame (right-handed, Z-down, Y-right, X-front, ZYX, intrinsic).."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct ATTITUDE_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "Roll angle (-pi..+pi)."]
pub roll: f32,
#[doc = "Pitch angle (-pi..+pi)."]
pub pitch: f32,
#[doc = "Yaw angle (-pi..+pi)."]
pub yaw: f32,
#[doc = "Roll angular speed."]
pub rollspeed: f32,
#[doc = "Pitch angular speed."]
pub pitchspeed: f32,
#[doc = "Yaw angular speed."]
pub yawspeed: f32,
}
impl ATTITUDE_DATA {
pub const ENCODED_LEN: usize = 28usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.roll = buf.get_f32_le();
_struct.pitch = buf.get_f32_le();
_struct.yaw = buf.get_f32_le();
_struct.rollspeed = buf.get_f32_le();
_struct.pitchspeed = buf.get_f32_le();
_struct.yawspeed = buf.get_f32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_f32_le(self.roll);
_tmp.put_f32_le(self.pitch);
_tmp.put_f32_le(self.yaw);
_tmp.put_f32_le(self.rollspeed);
_tmp.put_f32_le(self.pitchspeed);
_tmp.put_f32_le(self.yawspeed);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 29"]
#[doc = "The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct SCALED_PRESSURE_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "Absolute pressure."]
pub press_abs: f32,
#[doc = "Differential pressure 1."]
pub press_diff: f32,
#[doc = "Absolute pressure temperature."]
pub temperature: i16,
#[doc = "Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC.."]
#[cfg_attr(feature = "serde", serde(default))]
pub temperature_press_diff: i16,
}
impl SCALED_PRESSURE_DATA {
pub const ENCODED_LEN: usize = 16usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.press_abs = buf.get_f32_le();
_struct.press_diff = buf.get_f32_le();
_struct.temperature = buf.get_i16_le();
_struct.temperature_press_diff = buf.get_i16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_f32_le(self.press_abs);
_tmp.put_f32_le(self.press_diff);
_tmp.put_i16_le(self.temperature);
_tmp.put_i16_le(self.temperature_press_diff);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 150"]
#[doc = "Offsets and calibrations values for hardware sensors. This makes it easier to debug the calibration process.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct SENSOR_OFFSETS_DATA {
#[doc = "Magnetic declination.."]
pub mag_declination: f32,
#[doc = "Raw pressure from barometer.."]
pub raw_press: i32,
#[doc = "Raw temperature from barometer.."]
pub raw_temp: i32,
#[doc = "Gyro X calibration.."]
pub gyro_cal_x: f32,
#[doc = "Gyro Y calibration.."]
pub gyro_cal_y: f32,
#[doc = "Gyro Z calibration.."]
pub gyro_cal_z: f32,
#[doc = "Accel X calibration.."]
pub accel_cal_x: f32,
#[doc = "Accel Y calibration.."]
pub accel_cal_y: f32,
#[doc = "Accel Z calibration.."]
pub accel_cal_z: f32,
#[doc = "Magnetometer X offset.."]
pub mag_ofs_x: i16,
#[doc = "Magnetometer Y offset.."]
pub mag_ofs_y: i16,
#[doc = "Magnetometer Z offset.."]
pub mag_ofs_z: i16,
}
impl SENSOR_OFFSETS_DATA {
pub const ENCODED_LEN: usize = 42usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.mag_declination = buf.get_f32_le();
_struct.raw_press = buf.get_i32_le();
_struct.raw_temp = buf.get_i32_le();
_struct.gyro_cal_x = buf.get_f32_le();
_struct.gyro_cal_y = buf.get_f32_le();
_struct.gyro_cal_z = buf.get_f32_le();
_struct.accel_cal_x = buf.get_f32_le();
_struct.accel_cal_y = buf.get_f32_le();
_struct.accel_cal_z = buf.get_f32_le();
_struct.mag_ofs_x = buf.get_i16_le();
_struct.mag_ofs_y = buf.get_i16_le();
_struct.mag_ofs_z = buf.get_i16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.mag_declination);
_tmp.put_i32_le(self.raw_press);
_tmp.put_i32_le(self.raw_temp);
_tmp.put_f32_le(self.gyro_cal_x);
_tmp.put_f32_le(self.gyro_cal_y);
_tmp.put_f32_le(self.gyro_cal_z);
_tmp.put_f32_le(self.accel_cal_x);
_tmp.put_f32_le(self.accel_cal_y);
_tmp.put_f32_le(self.accel_cal_z);
_tmp.put_i16_le(self.mag_ofs_x);
_tmp.put_i16_le(self.mag_ofs_y);
_tmp.put_i16_le(self.mag_ofs_z);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 11011"]
#[doc = "Camera vision based attitude and position deltas.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct VISION_POSITION_DELTA_DATA {
#[doc = "Timestamp (synced to UNIX time or since system boot).."]
pub time_usec: u64,
#[doc = "Time since the last reported camera frame.."]
pub time_delta_usec: u64,
#[doc = "Defines a rotation vector [roll, pitch, yaw] to the current MAV_FRAME_BODY_FRD from the previous MAV_FRAME_BODY_FRD.."]
pub angle_delta: [f32; 3],
#[doc = "Change in position to the current MAV_FRAME_BODY_FRD from the previous FRAME_BODY_FRD rotated to the current MAV_FRAME_BODY_FRD.."]
pub position_delta: [f32; 3],
#[doc = "Normalised confidence value from 0 to 100.."]
pub confidence: f32,
}
impl VISION_POSITION_DELTA_DATA {
pub const ENCODED_LEN: usize = 44usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.time_delta_usec = buf.get_u64_le();
for idx in 0..3usize {
let val = buf.get_f32_le();
_struct.angle_delta[idx] = val;
}
for idx in 0..3usize {
let val = buf.get_f32_le();
_struct.position_delta[idx] = val;
}
_struct.confidence = buf.get_f32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_u64_le(self.time_delta_usec);
for val in &self.angle_delta {
_tmp.put_f32_le(*val);
}
for val in &self.position_delta {
_tmp.put_f32_le(*val);
}
_tmp.put_f32_le(self.confidence);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 266"]
#[doc = "A message containing logged data (see also MAV_CMD_LOGGING_START)."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct LOGGING_DATA_DATA {
#[doc = "sequence number (can wrap)."]
pub sequence: u16,
#[doc = "system ID of the target."]
pub target_system: u8,
#[doc = "component ID of the target."]
pub target_component: u8,
#[doc = "data length."]
pub length: u8,
#[doc = "offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to UINT8_MAX if no start exists).."]
pub first_message_offset: u8,
#[doc = "logged data."]
pub data: Vec<u8, 249>,
}
impl LOGGING_DATA_DATA {
pub const ENCODED_LEN: usize = 255usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.sequence = buf.get_u16_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
_struct.length = buf.get_u8();
_struct.first_message_offset = buf.get_u8();
for _ in 0..249usize {
let val = buf.get_u8();
_struct.data.push(val).unwrap();
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.sequence);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.length);
_tmp.put_u8(self.first_message_offset);
for val in &self.data {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 233"]
#[doc = "RTCM message for injecting into the onboard GPS (used for DGPS)."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct GPS_RTCM_DATA_DATA {
#[doc = "LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order.."]
pub flags: u8,
#[doc = "data length."]
pub len: u8,
#[doc = "RTCM message (may be fragmented)."]
pub data: Vec<u8, 180>,
}
impl GPS_RTCM_DATA_DATA {
pub const ENCODED_LEN: usize = 182usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.flags = buf.get_u8();
_struct.len = buf.get_u8();
for _ in 0..180usize {
let val = buf.get_u8();
_struct.data.push(val).unwrap();
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.flags);
_tmp.put_u8(self.len);
for val in &self.data {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 85"]
#[doc = "Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_LOCAL_NED if the vehicle is being controlled this way.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct POSITION_TARGET_LOCAL_NED_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "X Position in NED frame."]
pub x: f32,
#[doc = "Y Position in NED frame."]
pub y: f32,
#[doc = "Z Position in NED frame (note, altitude is negative in NED)."]
pub z: f32,
#[doc = "X velocity in NED frame."]
pub vx: f32,
#[doc = "Y velocity in NED frame."]
pub vy: f32,
#[doc = "Z velocity in NED frame."]
pub vz: f32,
#[doc = "X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N."]
pub afx: f32,
#[doc = "Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N."]
pub afy: f32,
#[doc = "Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N."]
pub afz: f32,
#[doc = "yaw setpoint."]
pub yaw: f32,
#[doc = "yaw rate setpoint."]
pub yaw_rate: f32,
#[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle.."]
pub type_mask: PositionTargetTypemask,
#[doc = "Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9."]
pub coordinate_frame: MavFrame,
}
impl POSITION_TARGET_LOCAL_NED_DATA {
pub const ENCODED_LEN: usize = 51usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.x = buf.get_f32_le();
_struct.y = buf.get_f32_le();
_struct.z = buf.get_f32_le();
_struct.vx = buf.get_f32_le();
_struct.vy = buf.get_f32_le();
_struct.vz = buf.get_f32_le();
_struct.afx = buf.get_f32_le();
_struct.afy = buf.get_f32_le();
_struct.afz = buf.get_f32_le();
_struct.yaw = buf.get_f32_le();
_struct.yaw_rate = buf.get_f32_le();
let tmp = buf.get_u16_le();
_struct.type_mask = PositionTargetTypemask::from_bits(
tmp & PositionTargetTypemask::all().bits(),
)
.ok_or(ParserError::InvalidFlag {
flag_type: "PositionTargetTypemask",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.coordinate_frame = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavFrame",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_f32_le(self.x);
_tmp.put_f32_le(self.y);
_tmp.put_f32_le(self.z);
_tmp.put_f32_le(self.vx);
_tmp.put_f32_le(self.vy);
_tmp.put_f32_le(self.vz);
_tmp.put_f32_le(self.afx);
_tmp.put_f32_le(self.afy);
_tmp.put_f32_le(self.afz);
_tmp.put_f32_le(self.yaw);
_tmp.put_f32_le(self.yaw_rate);
_tmp.put_u16_le(self.type_mask.bits());
_tmp.put_u8(self.coordinate_frame as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 40"]
#[doc = "Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM message. https://mavlink.io/en/services/mission.html."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct MISSION_REQUEST_DATA {
#[doc = "Sequence."]
pub seq: u16,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "Mission type.."]
#[cfg_attr(feature = "serde", serde(default))]
pub mission_type: MavMissionType,
}
impl MISSION_REQUEST_DATA {
pub const ENCODED_LEN: usize = 5usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.seq = buf.get_u16_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
let tmp = buf.get_u8();
_struct.mission_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavMissionType",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.seq);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.mission_type as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 271"]
#[doc = "Information about the field of view of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct CAMERA_FOV_STATUS_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "Latitude of camera (INT32_MAX if unknown).."]
pub lat_camera: i32,
#[doc = "Longitude of camera (INT32_MAX if unknown).."]
pub lon_camera: i32,
#[doc = "Altitude (MSL) of camera (INT32_MAX if unknown).."]
pub alt_camera: i32,
#[doc = "Latitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).."]
pub lat_image: i32,
#[doc = "Longitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).."]
pub lon_image: i32,
#[doc = "Altitude (MSL) of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).."]
pub alt_image: i32,
#[doc = "Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)."]
pub q: [f32; 4],
#[doc = "Horizontal field of view (NaN if unknown).."]
pub hfov: f32,
#[doc = "Vertical field of view (NaN if unknown).."]
pub vfov: f32,
}
impl CAMERA_FOV_STATUS_DATA {
pub const ENCODED_LEN: usize = 52usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.lat_camera = buf.get_i32_le();
_struct.lon_camera = buf.get_i32_le();
_struct.alt_camera = buf.get_i32_le();
_struct.lat_image = buf.get_i32_le();
_struct.lon_image = buf.get_i32_le();
_struct.alt_image = buf.get_i32_le();
for idx in 0..4usize {
let val = buf.get_f32_le();
_struct.q[idx] = val;
}
_struct.hfov = buf.get_f32_le();
_struct.vfov = buf.get_f32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_i32_le(self.lat_camera);
_tmp.put_i32_le(self.lon_camera);
_tmp.put_i32_le(self.alt_camera);
_tmp.put_i32_le(self.lat_image);
_tmp.put_i32_le(self.lon_image);
_tmp.put_i32_le(self.alt_image);
for val in &self.q {
_tmp.put_f32_le(*val);
}
_tmp.put_f32_le(self.hfov);
_tmp.put_f32_le(self.vfov);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 0"]
#[doc = "The heartbeat message shows that a system or component is present and responding. The type and autopilot fields (along with the message component id), allow the receiving system to treat further messages from this system appropriately (e.g. by laying out the user interface based on the autopilot). This microservice is documented at https://mavlink.io/en/services/heartbeat.html."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct HEARTBEAT_DATA {
#[doc = "A bitfield for use for autopilot-specific flags."]
pub custom_mode: u32,
#[doc = "Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type.."]
pub mavtype: MavType,
#[doc = "Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.."]
pub autopilot: MavAutopilot,
#[doc = "System mode bitmap.."]
pub base_mode: MavModeFlag,
#[doc = "System status flag.."]
pub system_status: MavState,
#[doc = "MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version."]
pub mavlink_version: u8,
}
impl HEARTBEAT_DATA {
pub const ENCODED_LEN: usize = 9usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.custom_mode = buf.get_u32_le();
let tmp = buf.get_u8();
_struct.mavtype = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavType",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.autopilot = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavAutopilot",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.base_mode = MavModeFlag::from_bits(tmp & MavModeFlag::all().bits()).ok_or(
ParserError::InvalidFlag {
flag_type: "MavModeFlag",
value: tmp as u32,
},
)?;
let tmp = buf.get_u8();
_struct.system_status = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavState",
value: tmp as u32,
})?;
_struct.mavlink_version = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.custom_mode);
_tmp.put_u8(self.mavtype as u8);
_tmp.put_u8(self.autopilot as u8);
_tmp.put_u8(self.base_mode.bits());
_tmp.put_u8(self.system_status as u8);
_tmp.put_u8(self.mavlink_version);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 155"]
#[doc = "Control on-board Camera Control System to take shots.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct DIGICAM_CONTROL_DATA {
#[doc = "Correspondent value to given extra_param.."]
pub extra_value: f32,
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Component ID.."]
pub target_component: u8,
#[doc = "0: stop, 1: start or keep it up //Session control e.g. show/hide lens.."]
pub session: u8,
#[doc = "1 to N //Zoom's absolute position (0 means ignore).."]
pub zoom_pos: u8,
#[doc = "-100 to 100 //Zooming step value to offset zoom from the current position.."]
pub zoom_step: i8,
#[doc = "0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus.."]
pub focus_lock: u8,
#[doc = "0: ignore, 1: shot or start filming.."]
pub shot: u8,
#[doc = "Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once.."]
pub command_id: u8,
#[doc = "Extra parameters enumeration (0 means ignore).."]
pub extra_param: u8,
}
impl DIGICAM_CONTROL_DATA {
pub const ENCODED_LEN: usize = 13usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.extra_value = buf.get_f32_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
_struct.session = buf.get_u8();
_struct.zoom_pos = buf.get_u8();
_struct.zoom_step = buf.get_i8();
_struct.focus_lock = buf.get_u8();
_struct.shot = buf.get_u8();
_struct.command_id = buf.get_u8();
_struct.extra_param = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_f32_le(self.extra_value);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.session);
_tmp.put_u8(self.zoom_pos);
_tmp.put_i8(self.zoom_step);
_tmp.put_u8(self.focus_lock);
_tmp.put_u8(self.shot);
_tmp.put_u8(self.command_id);
_tmp.put_u8(self.extra_param);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 340"]
#[doc = "The global position resulting from GPS and sensor fusion.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct UTM_GLOBAL_POSITION_DATA {
#[doc = "Time of applicability of position (microseconds since UNIX epoch).."]
pub time: u64,
#[doc = "Latitude (WGS84)."]
pub lat: i32,
#[doc = "Longitude (WGS84)."]
pub lon: i32,
#[doc = "Altitude (WGS84)."]
pub alt: i32,
#[doc = "Altitude above ground."]
pub relative_alt: i32,
#[doc = "Next waypoint, latitude (WGS84)."]
pub next_lat: i32,
#[doc = "Next waypoint, longitude (WGS84)."]
pub next_lon: i32,
#[doc = "Next waypoint, altitude (WGS84)."]
pub next_alt: i32,
#[doc = "Ground X speed (latitude, positive north)."]
pub vx: i16,
#[doc = "Ground Y speed (longitude, positive east)."]
pub vy: i16,
#[doc = "Ground Z speed (altitude, positive down)."]
pub vz: i16,
#[doc = "Horizontal position uncertainty (standard deviation)."]
pub h_acc: u16,
#[doc = "Altitude uncertainty (standard deviation)."]
pub v_acc: u16,
#[doc = "Speed uncertainty (standard deviation)."]
pub vel_acc: u16,
#[doc = "Time until next update. Set to 0 if unknown or in data driven mode.."]
pub update_rate: u16,
#[doc = "Unique UAS ID.."]
pub uas_id: [u8; 18],
#[doc = "Flight state."]
pub flight_state: UtmFlightState,
#[doc = "Bitwise OR combination of the data available flags.."]
pub flags: UtmDataAvailFlags,
}
impl UTM_GLOBAL_POSITION_DATA {
pub const ENCODED_LEN: usize = 70usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time = buf.get_u64_le();
_struct.lat = buf.get_i32_le();
_struct.lon = buf.get_i32_le();
_struct.alt = buf.get_i32_le();
_struct.relative_alt = buf.get_i32_le();
_struct.next_lat = buf.get_i32_le();
_struct.next_lon = buf.get_i32_le();
_struct.next_alt = buf.get_i32_le();
_struct.vx = buf.get_i16_le();
_struct.vy = buf.get_i16_le();
_struct.vz = buf.get_i16_le();
_struct.h_acc = buf.get_u16_le();
_struct.v_acc = buf.get_u16_le();
_struct.vel_acc = buf.get_u16_le();
_struct.update_rate = buf.get_u16_le();
for idx in 0..18usize {
let val = buf.get_u8();
_struct.uas_id[idx] = val;
}
let tmp = buf.get_u8();
_struct.flight_state = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "UtmFlightState",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.flags = UtmDataAvailFlags::from_bits(tmp & UtmDataAvailFlags::all().bits()).ok_or(
ParserError::InvalidFlag {
flag_type: "UtmDataAvailFlags",
value: tmp as u32,
},
)?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time);
_tmp.put_i32_le(self.lat);
_tmp.put_i32_le(self.lon);
_tmp.put_i32_le(self.alt);
_tmp.put_i32_le(self.relative_alt);
_tmp.put_i32_le(self.next_lat);
_tmp.put_i32_le(self.next_lon);
_tmp.put_i32_le(self.next_alt);
_tmp.put_i16_le(self.vx);
_tmp.put_i16_le(self.vy);
_tmp.put_i16_le(self.vz);
_tmp.put_u16_le(self.h_acc);
_tmp.put_u16_le(self.v_acc);
_tmp.put_u16_le(self.vel_acc);
_tmp.put_u16_le(self.update_rate);
for val in &self.uas_id {
_tmp.put_u8(*val);
}
_tmp.put_u8(self.flight_state as u8);
_tmp.put_u8(self.flags.bits());
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 176"]
#[doc = "Request a current rally point from MAV. MAV should respond with a RALLY_POINT message. MAV should not respond if the request is invalid.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct RALLY_FETCH_POINT_DATA {
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Component ID.."]
pub target_component: u8,
#[doc = "Point index (first point is 0).."]
pub idx: u8,
}
impl RALLY_FETCH_POINT_DATA {
pub const ENCODED_LEN: usize = 3usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
_struct.idx = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.idx);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 11037"]
#[doc = "Obstacle located as a 3D vector.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct OBSTACLE_DISTANCE_3D_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "X position of the obstacle.."]
pub x: f32,
#[doc = "Y position of the obstacle.."]
pub y: f32,
#[doc = "Z position of the obstacle.."]
pub z: f32,
#[doc = "Minimum distance the sensor can measure.."]
pub min_distance: f32,
#[doc = "Maximum distance the sensor can measure.."]
pub max_distance: f32,
#[doc = "Unique ID given to each obstacle so that its movement can be tracked. Use UINT16_MAX if object ID is unknown or cannot be determined.."]
pub obstacle_id: u16,
#[doc = "Class id of the distance sensor type.."]
pub sensor_type: MavDistanceSensor,
#[doc = "Coordinate frame of reference.."]
pub frame: MavFrame,
}
impl OBSTACLE_DISTANCE_3D_DATA {
pub const ENCODED_LEN: usize = 28usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.x = buf.get_f32_le();
_struct.y = buf.get_f32_le();
_struct.z = buf.get_f32_le();
_struct.min_distance = buf.get_f32_le();
_struct.max_distance = buf.get_f32_le();
_struct.obstacle_id = buf.get_u16_le();
let tmp = buf.get_u8();
_struct.sensor_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavDistanceSensor",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.frame = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavFrame",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_f32_le(self.x);
_tmp.put_f32_le(self.y);
_tmp.put_f32_le(self.z);
_tmp.put_f32_le(self.min_distance);
_tmp.put_f32_le(self.max_distance);
_tmp.put_u16_le(self.obstacle_id);
_tmp.put_u8(self.sensor_type as u8);
_tmp.put_u8(self.frame as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 175"]
#[doc = "A rally point. Used to set a point when from GCS -> MAV. Also used to return a point from MAV -> GCS.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct RALLY_POINT_DATA {
#[doc = "Latitude of point.."]
pub lat: i32,
#[doc = "Longitude of point.."]
pub lng: i32,
#[doc = "Transit / loiter altitude relative to home.."]
pub alt: i16,
#[doc = "Break altitude relative to home.."]
pub break_alt: i16,
#[doc = "Heading to aim for when landing.."]
pub land_dir: u16,
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Component ID.."]
pub target_component: u8,
#[doc = "Point index (first point is 0).."]
pub idx: u8,
#[doc = "Total number of points (for sanity checking).."]
pub count: u8,
#[doc = "Configuration flags.."]
pub flags: RallyFlags,
}
impl RALLY_POINT_DATA {
pub const ENCODED_LEN: usize = 19usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.lat = buf.get_i32_le();
_struct.lng = buf.get_i32_le();
_struct.alt = buf.get_i16_le();
_struct.break_alt = buf.get_i16_le();
_struct.land_dir = buf.get_u16_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
_struct.idx = buf.get_u8();
_struct.count = buf.get_u8();
let tmp = buf.get_u8();
_struct.flags = RallyFlags::from_bits(tmp & RallyFlags::all().bits()).ok_or(
ParserError::InvalidFlag {
flag_type: "RallyFlags",
value: tmp as u32,
},
)?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_i32_le(self.lat);
_tmp.put_i32_le(self.lng);
_tmp.put_i16_le(self.alt);
_tmp.put_i16_le(self.break_alt);
_tmp.put_u16_le(self.land_dir);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.idx);
_tmp.put_u8(self.count);
_tmp.put_u8(self.flags.bits());
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 35"]
#[doc = "The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. A value of UINT16_MAX implies the channel is unused. Individual receivers/transmitters might violate this specification.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct RC_CHANNELS_RAW_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "RC channel 1 value.."]
pub chan1_raw: u16,
#[doc = "RC channel 2 value.."]
pub chan2_raw: u16,
#[doc = "RC channel 3 value.."]
pub chan3_raw: u16,
#[doc = "RC channel 4 value.."]
pub chan4_raw: u16,
#[doc = "RC channel 5 value.."]
pub chan5_raw: u16,
#[doc = "RC channel 6 value.."]
pub chan6_raw: u16,
#[doc = "RC channel 7 value.."]
pub chan7_raw: u16,
#[doc = "RC channel 8 value.."]
pub chan8_raw: u16,
#[doc = "Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX.."]
pub port: u8,
#[doc = "Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown.."]
pub rssi: u8,
}
impl RC_CHANNELS_RAW_DATA {
pub const ENCODED_LEN: usize = 22usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.chan1_raw = buf.get_u16_le();
_struct.chan2_raw = buf.get_u16_le();
_struct.chan3_raw = buf.get_u16_le();
_struct.chan4_raw = buf.get_u16_le();
_struct.chan5_raw = buf.get_u16_le();
_struct.chan6_raw = buf.get_u16_le();
_struct.chan7_raw = buf.get_u16_le();
_struct.chan8_raw = buf.get_u16_le();
_struct.port = buf.get_u8();
_struct.rssi = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_u16_le(self.chan1_raw);
_tmp.put_u16_le(self.chan2_raw);
_tmp.put_u16_le(self.chan3_raw);
_tmp.put_u16_le(self.chan4_raw);
_tmp.put_u16_le(self.chan5_raw);
_tmp.put_u16_le(self.chan6_raw);
_tmp.put_u16_le(self.chan7_raw);
_tmp.put_u16_le(self.chan8_raw);
_tmp.put_u8(self.port);
_tmp.put_u8(self.rssi);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 183"]
#[doc = "Request the autopilot version from the system/component.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct AUTOPILOT_VERSION_REQUEST_DATA {
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Component ID.."]
pub target_component: u8,
}
impl AUTOPILOT_VERSION_REQUEST_DATA {
pub const ENCODED_LEN: usize = 2usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 231"]
#[doc = "Wind estimate from vehicle. Note that despite the name, this message does not actually contain any covariances but instead variability and accuracy fields in terms of standard deviation (1-STD).."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct WIND_COV_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "Wind in North (NED) direction (NAN if unknown)."]
pub wind_x: f32,
#[doc = "Wind in East (NED) direction (NAN if unknown)."]
pub wind_y: f32,
#[doc = "Wind in down (NED) direction (NAN if unknown)."]
pub wind_z: f32,
#[doc = "Variability of wind in XY, 1-STD estimated from a 1 Hz lowpassed wind estimate (NAN if unknown)."]
pub var_horiz: f32,
#[doc = "Variability of wind in Z, 1-STD estimated from a 1 Hz lowpassed wind estimate (NAN if unknown)."]
pub var_vert: f32,
#[doc = "Altitude (MSL) that this measurement was taken at (NAN if unknown)."]
pub wind_alt: f32,
#[doc = "Horizontal speed 1-STD accuracy (0 if unknown)."]
pub horiz_accuracy: f32,
#[doc = "Vertical speed 1-STD accuracy (0 if unknown)."]
pub vert_accuracy: f32,
}
impl WIND_COV_DATA {
pub const ENCODED_LEN: usize = 40usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.wind_x = buf.get_f32_le();
_struct.wind_y = buf.get_f32_le();
_struct.wind_z = buf.get_f32_le();
_struct.var_horiz = buf.get_f32_le();
_struct.var_vert = buf.get_f32_le();
_struct.wind_alt = buf.get_f32_le();
_struct.horiz_accuracy = buf.get_f32_le();
_struct.vert_accuracy = buf.get_f32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_f32_le(self.wind_x);
_tmp.put_f32_le(self.wind_y);
_tmp.put_f32_le(self.wind_z);
_tmp.put_f32_le(self.var_horiz);
_tmp.put_f32_le(self.var_vert);
_tmp.put_f32_le(self.wind_alt);
_tmp.put_f32_le(self.horiz_accuracy);
_tmp.put_f32_le(self.vert_accuracy);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 93"]
#[doc = "Sent from autopilot to simulation. Hardware in the loop control outputs (replacement for HIL_CONTROLS)."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct HIL_ACTUATOR_CONTROLS_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "Flags as bitfield, 1: indicate simulation using lockstep.."]
pub flags: u64,
#[doc = "Control outputs -1 .. 1. Channel assignment depends on the simulated hardware.."]
pub controls: [f32; 16],
#[doc = "System mode. Includes arming state.."]
pub mode: MavModeFlag,
}
impl HIL_ACTUATOR_CONTROLS_DATA {
pub const ENCODED_LEN: usize = 81usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.flags = buf.get_u64_le();
for idx in 0..16usize {
let val = buf.get_f32_le();
_struct.controls[idx] = val;
}
let tmp = buf.get_u8();
_struct.mode = MavModeFlag::from_bits(tmp & MavModeFlag::all().bits()).ok_or(
ParserError::InvalidFlag {
flag_type: "MavModeFlag",
value: tmp as u32,
},
)?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_u64_le(self.flags);
for val in &self.controls {
_tmp.put_f32_le(*val);
}
_tmp.put_u8(self.mode.bits());
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 260"]
#[doc = "Settings of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct CAMERA_SETTINGS_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "Camera mode."]
pub mode_id: CameraMode,
#[doc = "Current zoom level as a percentage of the full range (0.0 to 100.0, NaN if not known)."]
#[cfg_attr(feature = "serde", serde(default))]
pub zoomLevel: f32,
#[doc = "Current focus level as a percentage of the full range (0.0 to 100.0, NaN if not known)."]
#[cfg_attr(feature = "serde", serde(default))]
pub focusLevel: f32,
}
impl CAMERA_SETTINGS_DATA {
pub const ENCODED_LEN: usize = 13usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
let tmp = buf.get_u8();
_struct.mode_id = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "CameraMode",
value: tmp as u32,
})?;
_struct.zoomLevel = buf.get_f32_le();
_struct.focusLevel = buf.get_f32_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_u8(self.mode_id as u8);
_tmp.put_f32_le(self.zoomLevel);
_tmp.put_f32_le(self.focusLevel);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 390"]
#[doc = "Hardware status sent by an onboard computer.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct ONBOARD_COMPUTER_STATUS_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "Time since system boot.."]
pub uptime: u32,
#[doc = "Amount of used RAM on the component system. A value of UINT32_MAX implies the field is unused.."]
pub ram_usage: u32,
#[doc = "Total amount of RAM on the component system. A value of UINT32_MAX implies the field is unused.."]
pub ram_total: u32,
#[doc = "Storage type: 0: HDD, 1: SSD, 2: EMMC, 3: SD card (non-removable), 4: SD card (removable). A value of UINT32_MAX implies the field is unused.."]
pub storage_type: [u32; 4],
#[doc = "Amount of used storage space on the component system. A value of UINT32_MAX implies the field is unused.."]
pub storage_usage: [u32; 4],
#[doc = "Total amount of storage space on the component system. A value of UINT32_MAX implies the field is unused.."]
pub storage_total: [u32; 4],
#[doc = "Link type: 0-9: UART, 10-19: Wired network, 20-29: Wifi, 30-39: Point-to-point proprietary, 40-49: Mesh proprietary."]
pub link_type: [u32; 6],
#[doc = "Network traffic from the component system. A value of UINT32_MAX implies the field is unused.."]
pub link_tx_rate: [u32; 6],
#[doc = "Network traffic to the component system. A value of UINT32_MAX implies the field is unused.."]
pub link_rx_rate: [u32; 6],
#[doc = "Network capacity from the component system. A value of UINT32_MAX implies the field is unused.."]
pub link_tx_max: [u32; 6],
#[doc = "Network capacity to the component system. A value of UINT32_MAX implies the field is unused.."]
pub link_rx_max: [u32; 6],
#[doc = "Fan speeds. A value of INT16_MAX implies the field is unused.."]
pub fan_speed: [i16; 4],
#[doc = "Type of the onboard computer: 0: Mission computer primary, 1: Mission computer backup 1, 2: Mission computer backup 2, 3: Compute node, 4-5: Compute spares, 6-9: Payload computers.."]
pub mavtype: u8,
#[doc = "CPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused.."]
pub cpu_cores: [u8; 8],
#[doc = "Combined CPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused.."]
pub cpu_combined: [u8; 10],
#[doc = "GPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused.."]
pub gpu_cores: [u8; 4],
#[doc = "Combined GPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused.."]
pub gpu_combined: [u8; 10],
#[doc = "Temperature of the board. A value of INT8_MAX implies the field is unused.."]
pub temperature_board: i8,
#[doc = "Temperature of the CPU core. A value of INT8_MAX implies the field is unused.."]
pub temperature_core: [i8; 8],
}
impl ONBOARD_COMPUTER_STATUS_DATA {
pub const ENCODED_LEN: usize = 238usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.uptime = buf.get_u32_le();
_struct.ram_usage = buf.get_u32_le();
_struct.ram_total = buf.get_u32_le();
for idx in 0..4usize {
let val = buf.get_u32_le();
_struct.storage_type[idx] = val;
}
for idx in 0..4usize {
let val = buf.get_u32_le();
_struct.storage_usage[idx] = val;
}
for idx in 0..4usize {
let val = buf.get_u32_le();
_struct.storage_total[idx] = val;
}
for idx in 0..6usize {
let val = buf.get_u32_le();
_struct.link_type[idx] = val;
}
for idx in 0..6usize {
let val = buf.get_u32_le();
_struct.link_tx_rate[idx] = val;
}
for idx in 0..6usize {
let val = buf.get_u32_le();
_struct.link_rx_rate[idx] = val;
}
for idx in 0..6usize {
let val = buf.get_u32_le();
_struct.link_tx_max[idx] = val;
}
for idx in 0..6usize {
let val = buf.get_u32_le();
_struct.link_rx_max[idx] = val;
}
for idx in 0..4usize {
let val = buf.get_i16_le();
_struct.fan_speed[idx] = val;
}
_struct.mavtype = buf.get_u8();
for idx in 0..8usize {
let val = buf.get_u8();
_struct.cpu_cores[idx] = val;
}
for idx in 0..10usize {
let val = buf.get_u8();
_struct.cpu_combined[idx] = val;
}
for idx in 0..4usize {
let val = buf.get_u8();
_struct.gpu_cores[idx] = val;
}
for idx in 0..10usize {
let val = buf.get_u8();
_struct.gpu_combined[idx] = val;
}
_struct.temperature_board = buf.get_i8();
for idx in 0..8usize {
let val = buf.get_i8();
_struct.temperature_core[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_u32_le(self.uptime);
_tmp.put_u32_le(self.ram_usage);
_tmp.put_u32_le(self.ram_total);
for val in &self.storage_type {
_tmp.put_u32_le(*val);
}
for val in &self.storage_usage {
_tmp.put_u32_le(*val);
}
for val in &self.storage_total {
_tmp.put_u32_le(*val);
}
for val in &self.link_type {
_tmp.put_u32_le(*val);
}
for val in &self.link_tx_rate {
_tmp.put_u32_le(*val);
}
for val in &self.link_rx_rate {
_tmp.put_u32_le(*val);
}
for val in &self.link_tx_max {
_tmp.put_u32_le(*val);
}
for val in &self.link_rx_max {
_tmp.put_u32_le(*val);
}
for val in &self.fan_speed {
_tmp.put_i16_le(*val);
}
_tmp.put_u8(self.mavtype);
for val in &self.cpu_cores {
_tmp.put_u8(*val);
}
for val in &self.cpu_combined {
_tmp.put_u8(*val);
}
for val in &self.gpu_cores {
_tmp.put_u8(*val);
}
for val in &self.gpu_combined {
_tmp.put_u8(*val);
}
_tmp.put_i8(self.temperature_board);
for val in &self.temperature_core {
_tmp.put_i8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 110"]
#[doc = "File transfer protocol message: https://mavlink.io/en/services/ftp.html.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct FILE_TRANSFER_PROTOCOL_DATA {
#[doc = "Network ID (0 for broadcast)."]
pub target_network: u8,
#[doc = "System ID (0 for broadcast)."]
pub target_system: u8,
#[doc = "Component ID (0 for broadcast)."]
pub target_component: u8,
#[doc = "Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The content/format of this block is defined in https://mavlink.io/en/services/ftp.html.."]
pub payload: Vec<u8, 251>,
}
impl FILE_TRANSFER_PROTOCOL_DATA {
pub const ENCODED_LEN: usize = 254usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.target_network = buf.get_u8();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
for _ in 0..251usize {
let val = buf.get_u8();
_struct.payload.push(val).unwrap();
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.target_network);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
for val in &self.payload {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 127"]
#[doc = "RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct GPS_RTK_DATA {
#[doc = "Time since boot of last baseline message received.."]
pub time_last_baseline_ms: u32,
#[doc = "GPS Time of Week of last baseline."]
pub tow: u32,
#[doc = "Current baseline in ECEF x or NED north component.."]
pub baseline_a_mm: i32,
#[doc = "Current baseline in ECEF y or NED east component.."]
pub baseline_b_mm: i32,
#[doc = "Current baseline in ECEF z or NED down component.."]
pub baseline_c_mm: i32,
#[doc = "Current estimate of baseline accuracy.."]
pub accuracy: u32,
#[doc = "Current number of integer ambiguity hypotheses.."]
pub iar_num_hypotheses: i32,
#[doc = "GPS Week Number of last baseline."]
pub wn: u16,
#[doc = "Identification of connected RTK receiver.."]
pub rtk_receiver_id: u8,
#[doc = "GPS-specific health report for RTK data.."]
pub rtk_health: u8,
#[doc = "Rate of baseline messages being received by GPS."]
pub rtk_rate: u8,
#[doc = "Current number of sats used for RTK calculation.."]
pub nsats: u8,
#[doc = "Coordinate system of baseline."]
pub baseline_coords_type: RtkBaselineCoordinateSystem,
}
impl GPS_RTK_DATA {
pub const ENCODED_LEN: usize = 35usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_last_baseline_ms = buf.get_u32_le();
_struct.tow = buf.get_u32_le();
_struct.baseline_a_mm = buf.get_i32_le();
_struct.baseline_b_mm = buf.get_i32_le();
_struct.baseline_c_mm = buf.get_i32_le();
_struct.accuracy = buf.get_u32_le();
_struct.iar_num_hypotheses = buf.get_i32_le();
_struct.wn = buf.get_u16_le();
_struct.rtk_receiver_id = buf.get_u8();
_struct.rtk_health = buf.get_u8();
_struct.rtk_rate = buf.get_u8();
_struct.nsats = buf.get_u8();
let tmp = buf.get_u8();
_struct.baseline_coords_type =
FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "RtkBaselineCoordinateSystem",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_last_baseline_ms);
_tmp.put_u32_le(self.tow);
_tmp.put_i32_le(self.baseline_a_mm);
_tmp.put_i32_le(self.baseline_b_mm);
_tmp.put_i32_le(self.baseline_c_mm);
_tmp.put_u32_le(self.accuracy);
_tmp.put_i32_le(self.iar_num_hypotheses);
_tmp.put_u16_le(self.wn);
_tmp.put_u8(self.rtk_receiver_id);
_tmp.put_u8(self.rtk_health);
_tmp.put_u8(self.rtk_rate);
_tmp.put_u8(self.nsats);
_tmp.put_u8(self.baseline_coords_type as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 283"]
#[doc = "Information about a low level gimbal. This message should be requested by the gimbal manager or a ground station using MAV_CMD_REQUEST_MESSAGE. The maximum angles and rates are the limits by hardware. However, the limits by software used are likely different/smaller and dependent on mode/settings/etc..."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct GIMBAL_DEVICE_INFORMATION_DATA {
#[doc = "UID of gimbal hardware (0 if unknown).."]
pub uid: u64,
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "Version of the gimbal firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).."]
pub firmware_version: u32,
#[doc = "Version of the gimbal hardware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).."]
pub hardware_version: u32,
#[doc = "Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown.."]
pub roll_min: f32,
#[doc = "Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown.."]
pub roll_max: f32,
#[doc = "Minimum hardware pitch angle (positive: up, negative: down). NAN if unknown.."]
pub pitch_min: f32,
#[doc = "Maximum hardware pitch angle (positive: up, negative: down). NAN if unknown.."]
pub pitch_max: f32,
#[doc = "Minimum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown.."]
pub yaw_min: f32,
#[doc = "Maximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown.."]
pub yaw_max: f32,
#[doc = "Bitmap of gimbal capability flags.."]
pub cap_flags: GimbalDeviceCapFlags,
#[doc = "Bitmap for use for gimbal-specific capability flags.."]
pub custom_cap_flags: u16,
#[doc = "Name of the gimbal vendor.."]
pub vendor_name: [u8; 32],
#[doc = "Name of the gimbal model.."]
pub model_name: [u8; 32],
#[doc = "Custom name of the gimbal given to it by the user.."]
pub custom_name: [u8; 32],
}
impl GIMBAL_DEVICE_INFORMATION_DATA {
pub const ENCODED_LEN: usize = 144usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.uid = buf.get_u64_le();
_struct.time_boot_ms = buf.get_u32_le();
_struct.firmware_version = buf.get_u32_le();
_struct.hardware_version = buf.get_u32_le();
_struct.roll_min = buf.get_f32_le();
_struct.roll_max = buf.get_f32_le();
_struct.pitch_min = buf.get_f32_le();
_struct.pitch_max = buf.get_f32_le();
_struct.yaw_min = buf.get_f32_le();
_struct.yaw_max = buf.get_f32_le();
let tmp = buf.get_u16_le();
_struct.cap_flags = GimbalDeviceCapFlags::from_bits(
tmp & GimbalDeviceCapFlags::all().bits(),
)
.ok_or(ParserError::InvalidFlag {
flag_type: "GimbalDeviceCapFlags",
value: tmp as u32,
})?;
_struct.custom_cap_flags = buf.get_u16_le();
for idx in 0..32usize {
let val = buf.get_u8();
_struct.vendor_name[idx] = val;
}
for idx in 0..32usize {
let val = buf.get_u8();
_struct.model_name[idx] = val;
}
for idx in 0..32usize {
let val = buf.get_u8();
_struct.custom_name[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.uid);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_u32_le(self.firmware_version);
_tmp.put_u32_le(self.hardware_version);
_tmp.put_f32_le(self.roll_min);
_tmp.put_f32_le(self.roll_max);
_tmp.put_f32_le(self.pitch_min);
_tmp.put_f32_le(self.pitch_max);
_tmp.put_f32_le(self.yaw_min);
_tmp.put_f32_le(self.yaw_max);
_tmp.put_u16_le(self.cap_flags.bits());
_tmp.put_u16_le(self.custom_cap_flags);
for val in &self.vendor_name {
_tmp.put_u8(*val);
}
for val in &self.model_name {
_tmp.put_u8(*val);
}
for val in &self.custom_name {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 118"]
#[doc = "Reply to LOG_REQUEST_LIST."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct LOG_ENTRY_DATA {
#[doc = "UTC timestamp of log since 1970, or 0 if not available."]
pub time_utc: u32,
#[doc = "Size of the log (may be approximate)."]
pub size: u32,
#[doc = "Log id."]
pub id: u16,
#[doc = "Total number of logs."]
pub num_logs: u16,
#[doc = "High log number."]
pub last_log_num: u16,
}
impl LOG_ENTRY_DATA {
pub const ENCODED_LEN: usize = 14usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_utc = buf.get_u32_le();
_struct.size = buf.get_u32_le();
_struct.id = buf.get_u16_le();
_struct.num_logs = buf.get_u16_le();
_struct.last_log_num = buf.get_u16_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_utc);
_tmp.put_u32_le(self.size);
_tmp.put_u16_le(self.id);
_tmp.put_u16_le(self.num_logs);
_tmp.put_u16_le(self.last_log_num);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 291"]
#[doc = "ESC information for higher rate streaming. Recommended streaming rate is ~10 Hz. Information that changes more slowly is sent in ESC_INFO. It should typically only be streamed on high-bandwidth links (i.e. to a companion computer).."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct ESC_STATUS_DATA {
#[doc = "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 the number.."]
pub time_usec: u64,
#[doc = "Reported motor RPM from each ESC (negative for reverse rotation).."]
pub rpm: [i32; 4],
#[doc = "Voltage measured from each ESC.."]
pub voltage: [f32; 4],
#[doc = "Current measured from each ESC.."]
pub current: [f32; 4],
#[doc = "Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.."]
pub index: u8,
}
impl ESC_STATUS_DATA {
pub const ENCODED_LEN: usize = 57usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
for idx in 0..4usize {
let val = buf.get_i32_le();
_struct.rpm[idx] = val;
}
for idx in 0..4usize {
let val = buf.get_f32_le();
_struct.voltage[idx] = val;
}
for idx in 0..4usize {
let val = buf.get_f32_le();
_struct.current[idx] = val;
}
_struct.index = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
for val in &self.rpm {
_tmp.put_i32_le(*val);
}
for val in &self.voltage {
_tmp.put_f32_le(*val);
}
for val in &self.current {
_tmp.put_f32_le(*val);
}
_tmp.put_u8(self.index);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 50003"]
#[doc = "Herelink Telemetry."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct HERELINK_TELEM_DATA {}
impl HERELINK_TELEM_DATA {
pub const ENCODED_LEN: usize = 0usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
Ok(Self::default())
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 214"]
#[doc = "100 Hz gimbal torque command telemetry.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct GIMBAL_TORQUE_CMD_REPORT_DATA {
#[doc = "Roll Torque Command.."]
pub rl_torque_cmd: i16,
#[doc = "Elevation Torque Command.."]
pub el_torque_cmd: i16,
#[doc = "Azimuth Torque Command.."]
pub az_torque_cmd: i16,
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Component ID.."]
pub target_component: u8,
}
impl GIMBAL_TORQUE_CMD_REPORT_DATA {
pub const ENCODED_LEN: usize = 8usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.rl_torque_cmd = buf.get_i16_le();
_struct.el_torque_cmd = buf.get_i16_le();
_struct.az_torque_cmd = buf.get_i16_le();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_i16_le(self.rl_torque_cmd);
_tmp.put_i16_le(self.el_torque_cmd);
_tmp.put_i16_le(self.az_torque_cmd);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 234"]
#[doc = "Message appropriate for high latency connections like Iridium."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct HIGH_LATENCY_DATA {
#[doc = "A bitfield for use for autopilot-specific flags.."]
pub custom_mode: u32,
#[doc = "Latitude."]
pub latitude: i32,
#[doc = "Longitude."]
pub longitude: i32,
#[doc = "roll."]
pub roll: i16,
#[doc = "pitch."]
pub pitch: i16,
#[doc = "heading."]
pub heading: u16,
#[doc = "heading setpoint."]
pub heading_sp: i16,
#[doc = "Altitude above mean sea level."]
pub altitude_amsl: i16,
#[doc = "Altitude setpoint relative to the home position."]
pub altitude_sp: i16,
#[doc = "distance to target."]
pub wp_distance: u16,
#[doc = "Bitmap of enabled system modes.."]
pub base_mode: MavModeFlag,
#[doc = "The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.."]
pub landed_state: MavLandedState,
#[doc = "throttle (percentage)."]
pub throttle: i8,
#[doc = "airspeed."]
pub airspeed: u8,
#[doc = "airspeed setpoint."]
pub airspeed_sp: u8,
#[doc = "groundspeed."]
pub groundspeed: u8,
#[doc = "climb rate."]
pub climb_rate: i8,
#[doc = "Number of satellites visible. If unknown, set to UINT8_MAX."]
pub gps_nsat: u8,
#[doc = "GPS Fix type.."]
pub gps_fix_type: GpsFixType,
#[doc = "Remaining battery (percentage)."]
pub battery_remaining: u8,
#[doc = "Autopilot temperature (degrees C)."]
pub temperature: i8,
#[doc = "Air temperature (degrees C) from airspeed sensor."]
pub temperature_air: i8,
#[doc = "failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence)."]
pub failsafe: u8,
#[doc = "current waypoint number."]
pub wp_num: u8,
}
impl HIGH_LATENCY_DATA {
pub const ENCODED_LEN: usize = 40usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.custom_mode = buf.get_u32_le();
_struct.latitude = buf.get_i32_le();
_struct.longitude = buf.get_i32_le();
_struct.roll = buf.get_i16_le();
_struct.pitch = buf.get_i16_le();
_struct.heading = buf.get_u16_le();
_struct.heading_sp = buf.get_i16_le();
_struct.altitude_amsl = buf.get_i16_le();
_struct.altitude_sp = buf.get_i16_le();
_struct.wp_distance = buf.get_u16_le();
let tmp = buf.get_u8();
_struct.base_mode = MavModeFlag::from_bits(tmp & MavModeFlag::all().bits()).ok_or(
ParserError::InvalidFlag {
flag_type: "MavModeFlag",
value: tmp as u32,
},
)?;
let tmp = buf.get_u8();
_struct.landed_state = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavLandedState",
value: tmp as u32,
})?;
_struct.throttle = buf.get_i8();
_struct.airspeed = buf.get_u8();
_struct.airspeed_sp = buf.get_u8();
_struct.groundspeed = buf.get_u8();
_struct.climb_rate = buf.get_i8();
_struct.gps_nsat = buf.get_u8();
let tmp = buf.get_u8();
_struct.gps_fix_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "GpsFixType",
value: tmp as u32,
})?;
_struct.battery_remaining = buf.get_u8();
_struct.temperature = buf.get_i8();
_struct.temperature_air = buf.get_i8();
_struct.failsafe = buf.get_u8();
_struct.wp_num = buf.get_u8();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.custom_mode);
_tmp.put_i32_le(self.latitude);
_tmp.put_i32_le(self.longitude);
_tmp.put_i16_le(self.roll);
_tmp.put_i16_le(self.pitch);
_tmp.put_u16_le(self.heading);
_tmp.put_i16_le(self.heading_sp);
_tmp.put_i16_le(self.altitude_amsl);
_tmp.put_i16_le(self.altitude_sp);
_tmp.put_u16_le(self.wp_distance);
_tmp.put_u8(self.base_mode.bits());
_tmp.put_u8(self.landed_state as u8);
_tmp.put_i8(self.throttle);
_tmp.put_u8(self.airspeed);
_tmp.put_u8(self.airspeed_sp);
_tmp.put_u8(self.groundspeed);
_tmp.put_i8(self.climb_rate);
_tmp.put_u8(self.gps_nsat);
_tmp.put_u8(self.gps_fix_type as u8);
_tmp.put_u8(self.battery_remaining);
_tmp.put_i8(self.temperature);
_tmp.put_i8(self.temperature_air);
_tmp.put_u8(self.failsafe);
_tmp.put_u8(self.wp_num);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 11031"]
#[doc = "ESC Telemetry Data for ESCs 5 to 8, matching data sent by BLHeli ESCs.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct ESC_TELEMETRY_5_TO_8_DATA {
#[doc = "Voltage.."]
pub voltage: [u16; 4],
#[doc = "Current.."]
pub current: [u16; 4],
#[doc = "Total current.."]
pub totalcurrent: [u16; 4],
#[doc = "RPM (eRPM).."]
pub rpm: [u16; 4],
#[doc = "count of telemetry packets received (wraps at 65535).."]
pub count: [u16; 4],
#[doc = "Temperature.."]
pub temperature: [u8; 4],
}
impl ESC_TELEMETRY_5_TO_8_DATA {
pub const ENCODED_LEN: usize = 44usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
for idx in 0..4usize {
let val = buf.get_u16_le();
_struct.voltage[idx] = val;
}
for idx in 0..4usize {
let val = buf.get_u16_le();
_struct.current[idx] = val;
}
for idx in 0..4usize {
let val = buf.get_u16_le();
_struct.totalcurrent[idx] = val;
}
for idx in 0..4usize {
let val = buf.get_u16_le();
_struct.rpm[idx] = val;
}
for idx in 0..4usize {
let val = buf.get_u16_le();
_struct.count[idx] = val;
}
for idx in 0..4usize {
let val = buf.get_u8();
_struct.temperature[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
for val in &self.voltage {
_tmp.put_u16_le(*val);
}
for val in &self.current {
_tmp.put_u16_le(*val);
}
for val in &self.totalcurrent {
_tmp.put_u16_le(*val);
}
for val in &self.rpm {
_tmp.put_u16_le(*val);
}
for val in &self.count {
_tmp.put_u16_le(*val);
}
for val in &self.temperature {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 400"]
#[doc = "Play vehicle tone/tune (buzzer). Supersedes message PLAY_TUNE.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PLAY_TUNE_V2_DATA {
#[doc = "Tune format."]
pub format: TuneFormat,
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "Tune definition as a NULL-terminated string.."]
pub tune: Vec<u8, 248>,
}
impl PLAY_TUNE_V2_DATA {
pub const ENCODED_LEN: usize = 254usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
let tmp = buf.get_u32_le();
_struct.format = TuneFormat::from_bits(tmp & TuneFormat::all().bits()).ok_or(
ParserError::InvalidFlag {
flag_type: "TuneFormat",
value: tmp as u32,
},
)?;
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
for _ in 0..248usize {
let val = buf.get_u8();
_struct.tune.push(val).unwrap();
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.format.bits());
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
for val in &self.tune {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 243"]
#[doc = "Sets the home position. \tThe home position is the default position that the system will return to and land on. The position is set automatically by the system during the takeoff (and may also be set using this message). The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. Note: the current home position may be emitted in a HOME_POSITION message on request (using MAV_CMD_REQUEST_MESSAGE with param1=242).."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct SET_HOME_POSITION_DATA {
#[doc = "Latitude (WGS84)."]
pub latitude: i32,
#[doc = "Longitude (WGS84)."]
pub longitude: i32,
#[doc = "Altitude (MSL). Positive for up.."]
pub altitude: i32,
#[doc = "Local X position of this position in the local coordinate frame (NED)."]
pub x: f32,
#[doc = "Local Y position of this position in the local coordinate frame (NED)."]
pub y: f32,
#[doc = "Local Z position of this position in the local coordinate frame (NED: positive \"down\")."]
pub z: f32,
#[doc = "World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground."]
pub q: [f32; 4],
#[doc = "Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.."]
pub approach_x: f32,
#[doc = "Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.."]
pub approach_y: f32,
#[doc = "Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.."]
pub approach_z: f32,
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "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.."]
#[cfg_attr(feature = "serde", serde(default))]
pub time_usec: u64,
}
impl SET_HOME_POSITION_DATA {
pub const ENCODED_LEN: usize = 61usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.latitude = buf.get_i32_le();
_struct.longitude = buf.get_i32_le();
_struct.altitude = buf.get_i32_le();
_struct.x = buf.get_f32_le();
_struct.y = buf.get_f32_le();
_struct.z = buf.get_f32_le();
for idx in 0..4usize {
let val = buf.get_f32_le();
_struct.q[idx] = val;
}
_struct.approach_x = buf.get_f32_le();
_struct.approach_y = buf.get_f32_le();
_struct.approach_z = buf.get_f32_le();
_struct.target_system = buf.get_u8();
_struct.time_usec = buf.get_u64_le();
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_i32_le(self.latitude);
_tmp.put_i32_le(self.longitude);
_tmp.put_i32_le(self.altitude);
_tmp.put_f32_le(self.x);
_tmp.put_f32_le(self.y);
_tmp.put_f32_le(self.z);
for val in &self.q {
_tmp.put_f32_le(*val);
}
_tmp.put_f32_le(self.approach_x);
_tmp.put_f32_le(self.approach_y);
_tmp.put_f32_le(self.approach_z);
_tmp.put_u8(self.target_system);
_tmp.put_u64_le(self.time_usec);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 147"]
#[doc = "Battery information. Updates GCS with flight controller battery status. Smart batteries also use this message, but may additionally send SMART_BATTERY_INFO.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct BATTERY_STATUS_DATA {
#[doc = "Consumed charge, -1: autopilot does not provide consumption estimate."]
pub current_consumed: i32,
#[doc = "Consumed energy, -1: autopilot does not provide energy consumption estimate."]
pub energy_consumed: i32,
#[doc = "Temperature of the battery. INT16_MAX for unknown temperature.."]
pub temperature: i16,
#[doc = "Battery voltage of cells 1 to 10 (see voltages_ext for cells 11-14). Cells in this field above the valid cell count for this battery should have the UINT16_MAX value. If individual cell voltages are unknown or not measured for this battery, then the overall battery voltage should be filled in cell 0, with all others set to UINT16_MAX. If the voltage of the battery is greater than (UINT16_MAX - 1), then cell 0 should be set to (UINT16_MAX - 1), and cell 1 to the remaining voltage. This can be extended to multiple cells if the total voltage is greater than 2 * (UINT16_MAX - 1).."]
pub voltages: [u16; 10],
#[doc = "Battery current, -1: autopilot does not measure the current."]
pub current_battery: i16,
#[doc = "Battery ID."]
pub id: u8,
#[doc = "Function of the battery."]
pub battery_function: MavBatteryFunction,
#[doc = "Type (chemistry) of the battery."]
pub mavtype: MavBatteryType,
#[doc = "Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery.."]
pub battery_remaining: i8,
#[doc = "Remaining battery time, 0: autopilot does not provide remaining battery time estimate."]
#[cfg_attr(feature = "serde", serde(default))]
pub time_remaining: i32,
#[doc = "State for extent of discharge, provided by autopilot for warning or external reactions."]
#[cfg_attr(feature = "serde", serde(default))]
pub charge_state: MavBatteryChargeState,
#[doc = "Battery voltages for cells 11 to 14. Cells above the valid cell count for this battery should have a value of 0, where zero indicates not supported (note, this is different than for the voltages field and allows empty byte truncation). If the measured value is 0 then 1 should be sent instead.."]
#[cfg_attr(feature = "serde", serde(default))]
pub voltages_ext: [u16; 4],
#[doc = "Battery mode. Default (0) is that battery mode reporting is not supported or battery is in normal-use mode.."]
#[cfg_attr(feature = "serde", serde(default))]
pub mode: MavBatteryMode,
#[doc = "Fault/health indications. These should be set when charge_state is MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY (if not, fault reporting is not supported).."]
#[cfg_attr(feature = "serde", serde(default))]
pub fault_bitmask: MavBatteryFault,
}
impl BATTERY_STATUS_DATA {
pub const ENCODED_LEN: usize = 54usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.current_consumed = buf.get_i32_le();
_struct.energy_consumed = buf.get_i32_le();
_struct.temperature = buf.get_i16_le();
for idx in 0..10usize {
let val = buf.get_u16_le();
_struct.voltages[idx] = val;
}
_struct.current_battery = buf.get_i16_le();
_struct.id = buf.get_u8();
let tmp = buf.get_u8();
_struct.battery_function = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavBatteryFunction",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.mavtype = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavBatteryType",
value: tmp as u32,
})?;
_struct.battery_remaining = buf.get_i8();
_struct.time_remaining = buf.get_i32_le();
let tmp = buf.get_u8();
_struct.charge_state = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavBatteryChargeState",
value: tmp as u32,
})?;
for idx in 0..4usize {
let val = buf.get_u16_le();
_struct.voltages_ext[idx] = val;
}
let tmp = buf.get_u8();
_struct.mode = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavBatteryMode",
value: tmp as u32,
})?;
let tmp = buf.get_u32_le();
_struct.fault_bitmask = MavBatteryFault::from_bits(tmp & MavBatteryFault::all().bits())
.ok_or(ParserError::InvalidFlag {
flag_type: "MavBatteryFault",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_i32_le(self.current_consumed);
_tmp.put_i32_le(self.energy_consumed);
_tmp.put_i16_le(self.temperature);
for val in &self.voltages {
_tmp.put_u16_le(*val);
}
_tmp.put_i16_le(self.current_battery);
_tmp.put_u8(self.id);
_tmp.put_u8(self.battery_function as u8);
_tmp.put_u8(self.mavtype as u8);
_tmp.put_i8(self.battery_remaining);
_tmp.put_i32_le(self.time_remaining);
_tmp.put_u8(self.charge_state as u8);
for val in &self.voltages_ext {
_tmp.put_u16_le(*val);
}
_tmp.put_u8(self.mode as u8);
_tmp.put_u32_le(self.fault_bitmask.bits());
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 12900"]
#[doc = "Data for filling the OpenDroneID Basic ID message. This and the below messages are primarily meant for feeding data to/from an OpenDroneID implementation. E.g. https://github.com/opendroneid/opendroneid-core-c. These messages are compatible with the ASTM F3411 Remote ID standard and the ASD-STAN prEN 4709-002 Direct Remote ID standard. Additional information and usage of these messages is documented at https://mavlink.io/en/services/opendroneid.html.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct OPEN_DRONE_ID_BASIC_ID_DATA {
#[doc = "System ID (0 for broadcast).."]
pub target_system: u8,
#[doc = "Component ID (0 for broadcast).."]
pub target_component: u8,
#[doc = "Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.."]
pub id_or_mac: [u8; 20],
#[doc = "Indicates the format for the uas_id field of this message.."]
pub id_type: MavOdidIdType,
#[doc = "Indicates the type of UA (Unmanned Aircraft).."]
pub ua_type: MavOdidUaType,
#[doc = "UAS (Unmanned Aircraft System) ID following the format specified by id_type. Shall be filled with nulls in the unused portion of the field.."]
pub uas_id: [u8; 20],
}
impl OPEN_DRONE_ID_BASIC_ID_DATA {
pub const ENCODED_LEN: usize = 44usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
for idx in 0..20usize {
let val = buf.get_u8();
_struct.id_or_mac[idx] = val;
}
let tmp = buf.get_u8();
_struct.id_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavOdidIdType",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.ua_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavOdidUaType",
value: tmp as u32,
})?;
for idx in 0..20usize {
let val = buf.get_u8();
_struct.uas_id[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
for val in &self.id_or_mac {
_tmp.put_u8(*val);
}
_tmp.put_u8(self.id_type as u8);
_tmp.put_u8(self.ua_type as u8);
for val in &self.uas_id {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 323"]
#[doc = "Set a parameter value. In order to deal with message loss (and retransmission of PARAM_EXT_SET), when setting a parameter value and the new value is the same as the current value, you will immediately get a PARAM_ACK_ACCEPTED response. If the current state is PARAM_ACK_IN_PROGRESS, you will accordingly receive a PARAM_ACK_IN_PROGRESS in response.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PARAM_EXT_SET_DATA {
#[doc = "System ID."]
pub target_system: u8,
#[doc = "Component ID."]
pub target_component: u8,
#[doc = "Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string."]
pub param_id: [u8; 16],
#[doc = "Parameter value."]
pub param_value: Vec<u8, 128>,
#[doc = "Parameter type.."]
pub param_type: MavParamExtType,
}
impl PARAM_EXT_SET_DATA {
pub const ENCODED_LEN: usize = 147usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
for idx in 0..16usize {
let val = buf.get_u8();
_struct.param_id[idx] = val;
}
for _ in 0..128usize {
let val = buf.get_u8();
_struct.param_value.push(val).unwrap();
}
let tmp = buf.get_u8();
_struct.param_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavParamExtType",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
for val in &self.param_id {
_tmp.put_u8(*val);
}
for val in &self.param_value {
_tmp.put_u8(*val);
}
_tmp.put_u8(self.param_type as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 322"]
#[doc = "Emit the value of a parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows them to re-request missing parameters after a loss or timeout.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PARAM_EXT_VALUE_DATA {
#[doc = "Total number of parameters."]
pub param_count: u16,
#[doc = "Index of this parameter."]
pub param_index: u16,
#[doc = "Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string."]
pub param_id: [u8; 16],
#[doc = "Parameter value."]
pub param_value: Vec<u8, 128>,
#[doc = "Parameter type.."]
pub param_type: MavParamExtType,
}
impl PARAM_EXT_VALUE_DATA {
pub const ENCODED_LEN: usize = 149usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.param_count = buf.get_u16_le();
_struct.param_index = buf.get_u16_le();
for idx in 0..16usize {
let val = buf.get_u8();
_struct.param_id[idx] = val;
}
for _ in 0..128usize {
let val = buf.get_u8();
_struct.param_value.push(val).unwrap();
}
let tmp = buf.get_u8();
_struct.param_type = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavParamExtType",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u16_le(self.param_count);
_tmp.put_u16_le(self.param_index);
for val in &self.param_id {
_tmp.put_u8(*val);
}
for val in &self.param_value {
_tmp.put_u8(*val);
}
_tmp.put_u8(self.param_type as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 360"]
#[doc = "Vehicle status report that is sent out while orbit execution is in progress (see MAV_CMD_DO_ORBIT).."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct ORBIT_EXECUTION_STATUS_DATA {
#[doc = "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.."]
pub time_usec: u64,
#[doc = "Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise.."]
pub radius: f32,
#[doc = "X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.."]
pub x: i32,
#[doc = "Y coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.."]
pub y: i32,
#[doc = "Altitude of center point. Coordinate system depends on frame field.."]
pub z: f32,
#[doc = "The coordinate system of the fields: x, y, z.."]
pub frame: MavFrame,
}
impl ORBIT_EXECUTION_STATUS_DATA {
pub const ENCODED_LEN: usize = 25usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_usec = buf.get_u64_le();
_struct.radius = buf.get_f32_le();
_struct.x = buf.get_i32_le();
_struct.y = buf.get_i32_le();
_struct.z = buf.get_f32_le();
let tmp = buf.get_u8();
_struct.frame = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavFrame",
value: tmp as u32,
})?;
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u64_le(self.time_usec);
_tmp.put_f32_le(self.radius);
_tmp.put_i32_le(self.x);
_tmp.put_i32_le(self.y);
_tmp.put_f32_le(self.z);
_tmp.put_u8(self.frame as u8);
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 252"]
#[doc = "Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct NAMED_VALUE_INT_DATA {
#[doc = "Timestamp (time since system boot).."]
pub time_boot_ms: u32,
#[doc = "Signed integer value."]
pub value: i32,
#[doc = "Name of the debug variable."]
pub name: [u8; 10],
}
impl NAMED_VALUE_INT_DATA {
pub const ENCODED_LEN: usize = 18usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.time_boot_ms = buf.get_u32_le();
_struct.value = buf.get_i32_le();
for idx in 0..10usize {
let val = buf.get_u8();
_struct.name[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u32_le(self.time_boot_ms);
_tmp.put_i32_le(self.value);
for val in &self.name {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 186"]
#[doc = "Control vehicle LEDs.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct LED_CONTROL_DATA {
#[doc = "System ID.."]
pub target_system: u8,
#[doc = "Component ID.."]
pub target_component: u8,
#[doc = "Instance (LED instance to control or 255 for all LEDs).."]
pub instance: u8,
#[doc = "Pattern (see LED_PATTERN_ENUM).."]
pub pattern: u8,
#[doc = "Custom Byte Length.."]
pub custom_len: u8,
#[doc = "Custom Bytes.."]
pub custom_bytes: [u8; 24],
}
impl LED_CONTROL_DATA {
pub const ENCODED_LEN: usize = 29usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.target_system = buf.get_u8();
_struct.target_component = buf.get_u8();
_struct.instance = buf.get_u8();
_struct.pattern = buf.get_u8();
_struct.custom_len = buf.get_u8();
for idx in 0..24usize {
let val = buf.get_u8();
_struct.custom_bytes[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_u8(self.target_system);
_tmp.put_u8(self.target_component);
_tmp.put_u8(self.instance);
_tmp.put_u8(self.pattern);
_tmp.put_u8(self.custom_len);
for val in &self.custom_bytes {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[doc = "id: 370"]
#[doc = "Smart Battery information (static/infrequent update). Use for updates from: smart battery to flight stack, flight stack to GCS. Use BATTERY_STATUS for smart battery frequent updates.."]
#[derive(Debug, Clone, PartialEq, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct SMART_BATTERY_INFO_DATA {
#[doc = "Capacity when full according to manufacturer, -1: field not provided.."]
pub capacity_full_specification: i32,
#[doc = "Capacity when full (accounting for battery degradation), -1: field not provided.."]
pub capacity_full: i32,
#[doc = "Charge/discharge cycle count. UINT16_MAX: field not provided.."]
pub cycle_count: u16,
#[doc = "Battery weight. 0: field not provided.."]
pub weight: u16,
#[doc = "Minimum per-cell voltage when discharging. If not supplied set to UINT16_MAX value.."]
pub discharge_minimum_voltage: u16,
#[doc = "Minimum per-cell voltage when charging. If not supplied set to UINT16_MAX value.."]
pub charging_minimum_voltage: u16,
#[doc = "Minimum per-cell voltage when resting. If not supplied set to UINT16_MAX value.."]
pub resting_minimum_voltage: u16,
#[doc = "Battery ID."]
pub id: u8,
#[doc = "Function of the battery."]
pub battery_function: MavBatteryFunction,
#[doc = "Type (chemistry) of the battery."]
pub mavtype: MavBatteryType,
#[doc = "Serial number in ASCII characters, 0 terminated. All 0: field not provided.."]
pub serial_number: [u8; 16],
#[doc = "Static device name in ASCII characters, 0 terminated. All 0: field not provided. Encode as manufacturer name then product name separated using an underscore.."]
pub device_name: Vec<u8, 50>,
#[doc = "Maximum per-cell voltage when charged. 0: field not provided.."]
#[cfg_attr(feature = "serde", serde(default))]
pub charging_maximum_voltage: u16,
#[doc = "Number of battery cells in series. 0: field not provided.."]
#[cfg_attr(feature = "serde", serde(default))]
pub cells_in_series: u8,
#[doc = "Maximum pack discharge current. 0: field not provided.."]
#[cfg_attr(feature = "serde", serde(default))]
pub discharge_maximum_current: u32,
#[doc = "Maximum pack discharge burst current. 0: field not provided.."]
#[cfg_attr(feature = "serde", serde(default))]
pub discharge_maximum_burst_current: u32,
#[doc = "Manufacture date (DD/MM/YYYY) in ASCII characters, 0 terminated. All 0: field not provided.."]
#[cfg_attr(feature = "serde", serde(default))]
pub manufacture_date: [u8; 11],
}
impl SMART_BATTERY_INFO_DATA {
pub const ENCODED_LEN: usize = 109usize;
pub fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result<Self, ParserError> {
let avail_len = _input.len();
let mut payload_buf = [0; Self::ENCODED_LEN];
let mut buf = if avail_len < Self::ENCODED_LEN {
payload_buf[0..avail_len].copy_from_slice(_input);
Bytes::new(&payload_buf)
} else {
Bytes::new(_input)
};
let mut _struct = Self::default();
_struct.capacity_full_specification = buf.get_i32_le();
_struct.capacity_full = buf.get_i32_le();
_struct.cycle_count = buf.get_u16_le();
_struct.weight = buf.get_u16_le();
_struct.discharge_minimum_voltage = buf.get_u16_le();
_struct.charging_minimum_voltage = buf.get_u16_le();
_struct.resting_minimum_voltage = buf.get_u16_le();
_struct.id = buf.get_u8();
let tmp = buf.get_u8();
_struct.battery_function = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavBatteryFunction",
value: tmp as u32,
})?;
let tmp = buf.get_u8();
_struct.mavtype = FromPrimitive::from_u8(tmp).ok_or(ParserError::InvalidEnum {
enum_type: "MavBatteryType",
value: tmp as u32,
})?;
for idx in 0..16usize {
let val = buf.get_u8();
_struct.serial_number[idx] = val;
}
for _ in 0..50usize {
let val = buf.get_u8();
_struct.device_name.push(val).unwrap();
}
_struct.charging_maximum_voltage = buf.get_u16_le();
_struct.cells_in_series = buf.get_u8();
_struct.discharge_maximum_current = buf.get_u32_le();
_struct.discharge_maximum_burst_current = buf.get_u32_le();
for idx in 0..11usize {
let val = buf.get_u8();
_struct.manufacture_date[idx] = val;
}
Ok(_struct)
}
pub fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
let mut _tmp = BytesMut::new(bytes);
_tmp.put_i32_le(self.capacity_full_specification);
_tmp.put_i32_le(self.capacity_full);
_tmp.put_u16_le(self.cycle_count);
_tmp.put_u16_le(self.weight);
_tmp.put_u16_le(self.discharge_minimum_voltage);
_tmp.put_u16_le(self.charging_minimum_voltage);
_tmp.put_u16_le(self.resting_minimum_voltage);
_tmp.put_u8(self.id);
_tmp.put_u8(self.battery_function as u8);
_tmp.put_u8(self.mavtype as u8);
for val in &self.serial_number {
_tmp.put_u8(*val);
}
for val in &self.device_name {
_tmp.put_u8(*val);
}
_tmp.put_u16_le(self.charging_maximum_voltage);
_tmp.put_u8(self.cells_in_series);
_tmp.put_u32_le(self.discharge_maximum_current);
_tmp.put_u32_le(self.discharge_maximum_burst_current);
for val in &self.manufacture_date {
_tmp.put_u8(*val);
}
if matches!(version, MavlinkVersion::V2) {
let len = _tmp.len();
crate::remove_trailing_zeroes(&mut bytes[..len])
} else {
_tmp.len()
}
}
}
#[derive(Clone, PartialEq, Debug)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
#[cfg_attr(feature = "serde", serde(tag = "type"))]
pub enum MavMessage {
MISSION_WRITE_PARTIAL_LIST(MISSION_WRITE_PARTIAL_LIST_DATA),
CUBEPILOT_FIRMWARE_UPDATE_START(CUBEPILOT_FIRMWARE_UPDATE_START_DATA),
DEBUG_VECT(DEBUG_VECT_DATA),
GIMBAL_CONTROL(GIMBAL_CONTROL_DATA),
COMPASSMOT_STATUS(COMPASSMOT_STATUS_DATA),
BUTTON_CHANGE(BUTTON_CHANGE_DATA),
GPS_INJECT_DATA(GPS_INJECT_DATA_DATA),
CAMERA_STATUS(CAMERA_STATUS_DATA),
GOPRO_GET_RESPONSE(GOPRO_GET_RESPONSE_DATA),
CUBEPILOT_RAW_RC(CUBEPILOT_RAW_RC_DATA),
CELLULAR_CONFIG(CELLULAR_CONFIG_DATA),
GPS2_RAW(GPS2_RAW_DATA),
ESTIMATOR_STATUS(ESTIMATOR_STATUS_DATA),
UAVCAN_NODE_INFO(UAVCAN_NODE_INFO_DATA),
AIS_VESSEL(AIS_VESSEL_DATA),
ICAROUS_KINEMATIC_BANDS(ICAROUS_KINEMATIC_BANDS_DATA),
EFI_STATUS(EFI_STATUS_DATA),
CAN_FILTER_MODIFY(CAN_FILTER_MODIFY_DATA),
CUBEPILOT_FIRMWARE_UPDATE_RESP(CUBEPILOT_FIRMWARE_UPDATE_RESP_DATA),
DEBUG_FLOAT_ARRAY(DEBUG_FLOAT_ARRAY_DATA),
WIFI_CONFIG_AP(WIFI_CONFIG_AP_DATA),
AP_ADC(AP_ADC_DATA),
WIND(WIND_DATA),
AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA),
SCALED_IMU(SCALED_IMU_DATA),
LOCAL_POSITION_NED(LOCAL_POSITION_NED_DATA),
GOPRO_SET_RESPONSE(GOPRO_SET_RESPONSE_DATA),
GIMBAL_REPORT(GIMBAL_REPORT_DATA),
SET_MODE(SET_MODE_DATA),
CAMERA_TRACKING_GEO_STATUS(CAMERA_TRACKING_GEO_STATUS_DATA),
PARAM_EXT_ACK(PARAM_EXT_ACK_DATA),
DEVICE_OP_WRITE_REPLY(DEVICE_OP_WRITE_REPLY_DATA),
AIRSPEED_AUTOCAL(AIRSPEED_AUTOCAL_DATA),
ACTUATOR_OUTPUT_STATUS(ACTUATOR_OUTPUT_STATUS_DATA),
LOG_DATA(LOG_DATA_DATA),
LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA),
GOPRO_HEARTBEAT(GOPRO_HEARTBEAT_DATA),
CAMERA_INFORMATION(CAMERA_INFORMATION_DATA),
OSD_PARAM_CONFIG_REPLY(OSD_PARAM_CONFIG_REPLY_DATA),
GPS_RAW_INT(GPS_RAW_INT_DATA),
SIM_STATE(SIM_STATE_DATA),
COMMAND_ACK(COMMAND_ACK_DATA),
SCALED_PRESSURE3(SCALED_PRESSURE3_DATA),
OPEN_DRONE_ID_MESSAGE_PACK(OPEN_DRONE_ID_MESSAGE_PACK_DATA),
RAW_RPM(RAW_RPM_DATA),
GPS2_RTK(GPS2_RTK_DATA),
TERRAIN_DATA(TERRAIN_DATA_DATA),
MISSION_SET_CURRENT(MISSION_SET_CURRENT_DATA),
ACTUATOR_CONTROL_TARGET(ACTUATOR_CONTROL_TARGET_DATA),
MOUNT_CONTROL(MOUNT_CONTROL_DATA),
DISTANCE_SENSOR(DISTANCE_SENSOR_DATA),
TIME_ESTIMATE_TO_TARGET(TIME_ESTIMATE_TO_TARGET_DATA),
CELLULAR_STATUS(CELLULAR_STATUS_DATA),
GIMBAL_DEVICE_ATTITUDE_STATUS(GIMBAL_DEVICE_ATTITUDE_STATUS_DATA),
GLOBAL_POSITION_INT_COV(GLOBAL_POSITION_INT_COV_DATA),
RC_CHANNELS_SCALED(RC_CHANNELS_SCALED_DATA),
SETUP_SIGNING(SETUP_SIGNING_DATA),
CAMERA_CAPTURE_STATUS(CAMERA_CAPTURE_STATUS_DATA),
REMOTE_LOG_DATA_BLOCK(REMOTE_LOG_DATA_BLOCK_DATA),
PLAY_TUNE(PLAY_TUNE_DATA),
AHRS2(AHRS2_DATA),
HIL_STATE_QUATERNION(HIL_STATE_QUATERNION_DATA),
RAW_PRESSURE(RAW_PRESSURE_DATA),
WINCH_STATUS(WINCH_STATUS_DATA),
CAMERA_TRACKING_IMAGE_STATUS(CAMERA_TRACKING_IMAGE_STATUS_DATA),
PARAM_REQUEST_READ(PARAM_REQUEST_READ_DATA),
MISSION_COUNT(MISSION_COUNT_DATA),
RPM(RPM_DATA),
ESC_TELEMETRY_9_TO_12(ESC_TELEMETRY_9_TO_12_DATA),
WHEEL_DISTANCE(WHEEL_DISTANCE_DATA),
DEBUG(DEBUG_DATA),
HIL_SENSOR(HIL_SENSOR_DATA),
COMMAND_CANCEL(COMMAND_CANCEL_DATA),
FENCE_STATUS(FENCE_STATUS_DATA),
OBSTACLE_DISTANCE(OBSTACLE_DISTANCE_DATA),
MEMINFO(MEMINFO_DATA),
PID_TUNING(PID_TUNING_DATA),
UAVIONIX_ADSB_OUT_CFG(UAVIONIX_ADSB_OUT_CFG_DATA),
COMPONENT_METADATA(COMPONENT_METADATA_DATA),
OSD_PARAM_SHOW_CONFIG_REPLY(OSD_PARAM_SHOW_CONFIG_REPLY_DATA),
PARAM_EXT_REQUEST_READ(PARAM_EXT_REQUEST_READ_DATA),
ISBD_LINK_STATUS(ISBD_LINK_STATUS_DATA),
ODOMETRY(ODOMETRY_DATA),
HIL_GPS(HIL_GPS_DATA),
LOCAL_POSITION_NED_COV(LOCAL_POSITION_NED_COV_DATA),
FLIGHT_INFORMATION(FLIGHT_INFORMATION_DATA),
LOG_REQUEST_LIST(LOG_REQUEST_LIST_DATA),
SERVO_OUTPUT_RAW(SERVO_OUTPUT_RAW_DATA),
MISSION_REQUEST_INT(MISSION_REQUEST_INT_DATA),
ATTITUDE_TARGET(ATTITUDE_TARGET_DATA),
POWER_STATUS(POWER_STATUS_DATA),
CONTROL_SYSTEM_STATE(CONTROL_SYSTEM_STATE_DATA),
ESC_TELEMETRY_1_TO_4(ESC_TELEMETRY_1_TO_4_DATA),
MISSION_ITEM_INT(MISSION_ITEM_INT_DATA),
STATUSTEXT(STATUSTEXT_DATA),
OPEN_DRONE_ID_OPERATOR_ID(OPEN_DRONE_ID_OPERATOR_ID_DATA),
SYSTEM_TIME(SYSTEM_TIME_DATA),
RC_CHANNELS_OVERRIDE(RC_CHANNELS_OVERRIDE_DATA),
WATER_DEPTH(WATER_DEPTH_DATA),
PARAM_REQUEST_LIST(PARAM_REQUEST_LIST_DATA),
ATTITUDE_QUATERNION_COV(ATTITUDE_QUATERNION_COV_DATA),
ENCAPSULATED_DATA(ENCAPSULATED_DATA_DATA),
PARAM_VALUE(PARAM_VALUE_DATA),
CHANGE_OPERATOR_CONTROL_ACK(CHANGE_OPERATOR_CONTROL_ACK_DATA),
PING(PING_DATA),
SET_GPS_GLOBAL_ORIGIN(SET_GPS_GLOBAL_ORIGIN_DATA),
DEEPSTALL(DEEPSTALL_DATA),
GOPRO_SET_REQUEST(GOPRO_SET_REQUEST_DATA),
EKF_STATUS_REPORT(EKF_STATUS_REPORT_DATA),
OSD_PARAM_CONFIG(OSD_PARAM_CONFIG_DATA),
PARAM_EXT_REQUEST_LIST(PARAM_EXT_REQUEST_LIST_DATA),
NAV_CONTROLLER_OUTPUT(NAV_CONTROLLER_OUTPUT_DATA),
UAVIONIX_ADSB_OUT_DYNAMIC(UAVIONIX_ADSB_OUT_DYNAMIC_DATA),
SCALED_IMU2(SCALED_IMU2_DATA),
FENCE_POINT(FENCE_POINT_DATA),
SET_ACTUATOR_CONTROL_TARGET(SET_ACTUATOR_CONTROL_TARGET_DATA),
AOA_SSA(AOA_SSA_DATA),
OPTICAL_FLOW_RAD(OPTICAL_FLOW_RAD_DATA),
VICON_POSITION_ESTIMATE(VICON_POSITION_ESTIMATE_DATA),
VIBRATION(VIBRATION_DATA),
LANDING_TARGET(LANDING_TARGET_DATA),
MISSION_CURRENT(MISSION_CURRENT_DATA),
DATA64(DATA64_DATA),
TIMESYNC(TIMESYNC_DATA),
NAMED_VALUE_FLOAT(NAMED_VALUE_FLOAT_DATA),
ALTITUDE(ALTITUDE_DATA),
HIL_OPTICAL_FLOW(HIL_OPTICAL_FLOW_DATA),
COLLISION(COLLISION_DATA),
REQUEST_EVENT(REQUEST_EVENT_DATA),
CAMERA_FEEDBACK(CAMERA_FEEDBACK_DATA),
GOPRO_GET_REQUEST(GOPRO_GET_REQUEST_DATA),
RESOURCE_REQUEST(RESOURCE_REQUEST_DATA),
V2_EXTENSION(V2_EXTENSION_DATA),
PROTOCOL_VERSION(PROTOCOL_VERSION_DATA),
PARAM_MAP_RC(PARAM_MAP_RC_DATA),
TRAJECTORY_REPRESENTATION_BEZIER(TRAJECTORY_REPRESENTATION_BEZIER_DATA),
PARAM_SET(PARAM_SET_DATA),
ICAROUS_HEARTBEAT(ICAROUS_HEARTBEAT_DATA),
AHRS3(AHRS3_DATA),
TUNNEL(TUNNEL_DATA),
MCU_STATUS(MCU_STATUS_DATA),
EVENT(EVENT_DATA),
SERIAL_CONTROL(SERIAL_CONTROL_DATA),
AUTH_KEY(AUTH_KEY_DATA),
ADSB_VEHICLE(ADSB_VEHICLE_DATA),
SET_POSITION_TARGET_LOCAL_NED(SET_POSITION_TARGET_LOCAL_NED_DATA),
GPS_INPUT(GPS_INPUT_DATA),
MESSAGE_INTERVAL(MESSAGE_INTERVAL_DATA),
LOGGING_DATA_ACKED(LOGGING_DATA_ACKED_DATA),
HERELINK_VIDEO_STREAM_INFORMATION(HERELINK_VIDEO_STREAM_INFORMATION_DATA),
SET_MAG_OFFSETS(SET_MAG_OFFSETS_DATA),
DATA_TRANSMISSION_HANDSHAKE(DATA_TRANSMISSION_HANDSHAKE_DATA),
HIL_CONTROLS(HIL_CONTROLS_DATA),
RANGEFINDER(RANGEFINDER_DATA),
UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT(UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA),
LOGGING_ACK(LOGGING_ACK_DATA),
SAFETY_ALLOWED_AREA(SAFETY_ALLOWED_AREA_DATA),
CANFD_FRAME(CANFD_FRAME_DATA),
MISSION_REQUEST_LIST(MISSION_REQUEST_LIST_DATA),
SET_POSITION_TARGET_GLOBAL_INT(SET_POSITION_TARGET_GLOBAL_INT_DATA),
CAMERA_IMAGE_CAPTURED(CAMERA_IMAGE_CAPTURED_DATA),
COMMAND_INT(COMMAND_INT_DATA),
DATA32(DATA32_DATA),
GLOBAL_POSITION_INT(GLOBAL_POSITION_INT_DATA),
HIL_RC_INPUTS_RAW(HIL_RC_INPUTS_RAW_DATA),
OPEN_DRONE_ID_ARM_STATUS(OPEN_DRONE_ID_ARM_STATUS_DATA),
GIMBAL_MANAGER_SET_PITCHYAW(GIMBAL_MANAGER_SET_PITCHYAW_DATA),
RADIO(RADIO_DATA),
GPS_GLOBAL_ORIGIN(GPS_GLOBAL_ORIGIN_DATA),
MISSION_REQUEST_PARTIAL_LIST(MISSION_REQUEST_PARTIAL_LIST_DATA),
LOG_REQUEST_END(LOG_REQUEST_END_DATA),
LOG_REQUEST_DATA(LOG_REQUEST_DATA_DATA),
SAFETY_SET_ALLOWED_AREA(SAFETY_SET_ALLOWED_AREA_DATA),
SUPPORTED_TUNES(SUPPORTED_TUNES_DATA),
EXTENDED_SYS_STATE(EXTENDED_SYS_STATE_DATA),
DEVICE_OP_WRITE(DEVICE_OP_WRITE_DATA),
GENERATOR_STATUS(GENERATOR_STATUS_DATA),
ATTITUDE_QUATERNION(ATTITUDE_QUATERNION_DATA),
AHRS(AHRS_DATA),
TERRAIN_REPORT(TERRAIN_REPORT_DATA),
OPEN_DRONE_ID_AUTHENTICATION(OPEN_DRONE_ID_AUTHENTICATION_DATA),
RESPONSE_EVENT_ERROR(RESPONSE_EVENT_ERROR_DATA),
SCALED_IMU3(SCALED_IMU3_DATA),
POSITION_TARGET_GLOBAL_INT(POSITION_TARGET_GLOBAL_INT_DATA),
GPS_STATUS(GPS_STATUS_DATA),
UAVCAN_NODE_STATUS(UAVCAN_NODE_STATUS_DATA),
MAG_CAL_REPORT(MAG_CAL_REPORT_DATA),
SCALED_PRESSURE2(SCALED_PRESSURE2_DATA),
CAN_FRAME(CAN_FRAME_DATA),
OPTICAL_FLOW(OPTICAL_FLOW_DATA),
GIMBAL_MANAGER_STATUS(GIMBAL_MANAGER_STATUS_DATA),
TERRAIN_CHECK(TERRAIN_CHECK_DATA),
VIDEO_STREAM_INFORMATION(VIDEO_STREAM_INFORMATION_DATA),
MOUNT_STATUS(MOUNT_STATUS_DATA),
SET_ATTITUDE_TARGET(SET_ATTITUDE_TARGET_DATA),
GIMBAL_MANAGER_SET_ATTITUDE(GIMBAL_MANAGER_SET_ATTITUDE_DATA),
GIMBAL_DEVICE_SET_ATTITUDE(GIMBAL_DEVICE_SET_ATTITUDE_DATA),
HIGHRES_IMU(HIGHRES_IMU_DATA),
GIMBAL_MANAGER_SET_MANUAL_CONTROL(GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA),
CAMERA_TRIGGER(CAMERA_TRIGGER_DATA),
BATTERY2(BATTERY2_DATA),
REMOTE_LOG_BLOCK_STATUS(REMOTE_LOG_BLOCK_STATUS_DATA),
SIMSTATE(SIMSTATE_DATA),
HWSTATUS(HWSTATUS_DATA),
LIMITS_STATUS(LIMITS_STATUS_DATA),
HIGH_LATENCY2(HIGH_LATENCY2_DATA),
STORAGE_INFORMATION(STORAGE_INFORMATION_DATA),
AUTOPILOT_VERSION(AUTOPILOT_VERSION_DATA),
MISSION_ACK(MISSION_ACK_DATA),
FENCE_FETCH_POINT(FENCE_FETCH_POINT_DATA),
MOUNT_CONFIGURE(MOUNT_CONFIGURE_DATA),
TRAJECTORY_REPRESENTATION_WAYPOINTS(TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA),
CHANGE_OPERATOR_CONTROL(CHANGE_OPERATOR_CONTROL_DATA),
COMPONENT_INFORMATION(COMPONENT_INFORMATION_DATA),
SYS_STATUS(SYS_STATUS_DATA),
ADAP_TUNING(ADAP_TUNING_DATA),
GLOBAL_VISION_POSITION_ESTIMATE(GLOBAL_VISION_POSITION_ESTIMATE_DATA),
DIGICAM_CONFIGURE(DIGICAM_CONFIGURE_DATA),
TERRAIN_REQUEST(TERRAIN_REQUEST_DATA),
DATA96(DATA96_DATA),
OSD_PARAM_SHOW_CONFIG(OSD_PARAM_SHOW_CONFIG_DATA),
RADIO_STATUS(RADIO_STATUS_DATA),
RAW_IMU(RAW_IMU_DATA),
MISSION_ITEM(MISSION_ITEM_DATA),
REQUEST_DATA_STREAM(REQUEST_DATA_STREAM_DATA),
VIDEO_STREAM_STATUS(VIDEO_STREAM_STATUS_DATA),
LOG_ERASE(LOG_ERASE_DATA),
MANUAL_CONTROL(MANUAL_CONTROL_DATA),
COMMAND_LONG(COMMAND_LONG_DATA),
MANUAL_SETPOINT(MANUAL_SETPOINT_DATA),
OPEN_DRONE_ID_SYSTEM_UPDATE(OPEN_DRONE_ID_SYSTEM_UPDATE_DATA),
OPEN_DRONE_ID_SYSTEM(OPEN_DRONE_ID_SYSTEM_DATA),
LINK_NODE_STATUS(LINK_NODE_STATUS_DATA),
OPEN_DRONE_ID_SELF_ID(OPEN_DRONE_ID_SELF_ID_DATA),
VISION_POSITION_ESTIMATE(VISION_POSITION_ESTIMATE_DATA),
DEVICE_OP_READ_REPLY(DEVICE_OP_READ_REPLY_DATA),
HYGROMETER_SENSOR(HYGROMETER_SENSOR_DATA),
ATT_POS_MOCAP(ATT_POS_MOCAP_DATA),
RC_CHANNELS(RC_CHANNELS_DATA),
FOLLOW_TARGET(FOLLOW_TARGET_DATA),
HIL_STATE(HIL_STATE_DATA),
HOME_POSITION(HOME_POSITION_DATA),
OPEN_DRONE_ID_LOCATION(OPEN_DRONE_ID_LOCATION_DATA),
DATA_STREAM(DATA_STREAM_DATA),
MISSION_CLEAR_ALL(MISSION_CLEAR_ALL_DATA),
GIMBAL_MANAGER_INFORMATION(GIMBAL_MANAGER_INFORMATION_DATA),
VISION_SPEED_ESTIMATE(VISION_SPEED_ESTIMATE_DATA),
ESC_INFO(ESC_INFO_DATA),
DATA16(DATA16_DATA),
MEMORY_VECT(MEMORY_VECT_DATA),
MAG_CAL_PROGRESS(MAG_CAL_PROGRESS_DATA),
MISSION_ITEM_REACHED(MISSION_ITEM_REACHED_DATA),
MOUNT_ORIENTATION(MOUNT_ORIENTATION_DATA),
DEVICE_OP_READ(DEVICE_OP_READ_DATA),
VFR_HUD(VFR_HUD_DATA),
CURRENT_EVENT_SEQUENCE(CURRENT_EVENT_SEQUENCE_DATA),
ATTITUDE(ATTITUDE_DATA),
SCALED_PRESSURE(SCALED_PRESSURE_DATA),
SENSOR_OFFSETS(SENSOR_OFFSETS_DATA),
VISION_POSITION_DELTA(VISION_POSITION_DELTA_DATA),
LOGGING_DATA(LOGGING_DATA_DATA),
GPS_RTCM_DATA(GPS_RTCM_DATA_DATA),
POSITION_TARGET_LOCAL_NED(POSITION_TARGET_LOCAL_NED_DATA),
MISSION_REQUEST(MISSION_REQUEST_DATA),
CAMERA_FOV_STATUS(CAMERA_FOV_STATUS_DATA),
HEARTBEAT(HEARTBEAT_DATA),
DIGICAM_CONTROL(DIGICAM_CONTROL_DATA),
UTM_GLOBAL_POSITION(UTM_GLOBAL_POSITION_DATA),
RALLY_FETCH_POINT(RALLY_FETCH_POINT_DATA),
OBSTACLE_DISTANCE_3D(OBSTACLE_DISTANCE_3D_DATA),
RALLY_POINT(RALLY_POINT_DATA),
RC_CHANNELS_RAW(RC_CHANNELS_RAW_DATA),
AUTOPILOT_VERSION_REQUEST(AUTOPILOT_VERSION_REQUEST_DATA),
WIND_COV(WIND_COV_DATA),
HIL_ACTUATOR_CONTROLS(HIL_ACTUATOR_CONTROLS_DATA),
CAMERA_SETTINGS(CAMERA_SETTINGS_DATA),
ONBOARD_COMPUTER_STATUS(ONBOARD_COMPUTER_STATUS_DATA),
FILE_TRANSFER_PROTOCOL(FILE_TRANSFER_PROTOCOL_DATA),
GPS_RTK(GPS_RTK_DATA),
GIMBAL_DEVICE_INFORMATION(GIMBAL_DEVICE_INFORMATION_DATA),
LOG_ENTRY(LOG_ENTRY_DATA),
ESC_STATUS(ESC_STATUS_DATA),
HERELINK_TELEM(HERELINK_TELEM_DATA),
GIMBAL_TORQUE_CMD_REPORT(GIMBAL_TORQUE_CMD_REPORT_DATA),
HIGH_LATENCY(HIGH_LATENCY_DATA),
ESC_TELEMETRY_5_TO_8(ESC_TELEMETRY_5_TO_8_DATA),
PLAY_TUNE_V2(PLAY_TUNE_V2_DATA),
SET_HOME_POSITION(SET_HOME_POSITION_DATA),
BATTERY_STATUS(BATTERY_STATUS_DATA),
OPEN_DRONE_ID_BASIC_ID(OPEN_DRONE_ID_BASIC_ID_DATA),
PARAM_EXT_SET(PARAM_EXT_SET_DATA),
PARAM_EXT_VALUE(PARAM_EXT_VALUE_DATA),
ORBIT_EXECUTION_STATUS(ORBIT_EXECUTION_STATUS_DATA),
NAMED_VALUE_INT(NAMED_VALUE_INT_DATA),
LED_CONTROL(LED_CONTROL_DATA),
SMART_BATTERY_INFO(SMART_BATTERY_INFO_DATA),
}
impl Message for MavMessage {
fn parse(version: MavlinkVersion, id: u32, payload: &[u8]) -> Result<Self, ParserError> {
match id {
38u32 => MISSION_WRITE_PARTIAL_LIST_DATA::deser(version, payload)
.map(Self::MISSION_WRITE_PARTIAL_LIST),
50004u32 => CUBEPILOT_FIRMWARE_UPDATE_START_DATA::deser(version, payload)
.map(Self::CUBEPILOT_FIRMWARE_UPDATE_START),
250u32 => DEBUG_VECT_DATA::deser(version, payload).map(Self::DEBUG_VECT),
201u32 => GIMBAL_CONTROL_DATA::deser(version, payload).map(Self::GIMBAL_CONTROL),
177u32 => COMPASSMOT_STATUS_DATA::deser(version, payload).map(Self::COMPASSMOT_STATUS),
257u32 => BUTTON_CHANGE_DATA::deser(version, payload).map(Self::BUTTON_CHANGE),
123u32 => GPS_INJECT_DATA_DATA::deser(version, payload).map(Self::GPS_INJECT_DATA),
179u32 => CAMERA_STATUS_DATA::deser(version, payload).map(Self::CAMERA_STATUS),
217u32 => {
GOPRO_GET_RESPONSE_DATA::deser(version, payload).map(Self::GOPRO_GET_RESPONSE)
}
50001u32 => CUBEPILOT_RAW_RC_DATA::deser(version, payload).map(Self::CUBEPILOT_RAW_RC),
336u32 => CELLULAR_CONFIG_DATA::deser(version, payload).map(Self::CELLULAR_CONFIG),
124u32 => GPS2_RAW_DATA::deser(version, payload).map(Self::GPS2_RAW),
230u32 => ESTIMATOR_STATUS_DATA::deser(version, payload).map(Self::ESTIMATOR_STATUS),
311u32 => UAVCAN_NODE_INFO_DATA::deser(version, payload).map(Self::UAVCAN_NODE_INFO),
301u32 => AIS_VESSEL_DATA::deser(version, payload).map(Self::AIS_VESSEL),
42001u32 => ICAROUS_KINEMATIC_BANDS_DATA::deser(version, payload)
.map(Self::ICAROUS_KINEMATIC_BANDS),
225u32 => EFI_STATUS_DATA::deser(version, payload).map(Self::EFI_STATUS),
388u32 => CAN_FILTER_MODIFY_DATA::deser(version, payload).map(Self::CAN_FILTER_MODIFY),
50005u32 => CUBEPILOT_FIRMWARE_UPDATE_RESP_DATA::deser(version, payload)
.map(Self::CUBEPILOT_FIRMWARE_UPDATE_RESP),
350u32 => DEBUG_FLOAT_ARRAY_DATA::deser(version, payload).map(Self::DEBUG_FLOAT_ARRAY),
299u32 => WIFI_CONFIG_AP_DATA::deser(version, payload).map(Self::WIFI_CONFIG_AP),
153u32 => AP_ADC_DATA::deser(version, payload).map(Self::AP_ADC),
168u32 => WIND_DATA::deser(version, payload).map(Self::WIND),
286u32 => AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::deser(version, payload)
.map(Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE),
26u32 => SCALED_IMU_DATA::deser(version, payload).map(Self::SCALED_IMU),
32u32 => LOCAL_POSITION_NED_DATA::deser(version, payload).map(Self::LOCAL_POSITION_NED),
219u32 => {
GOPRO_SET_RESPONSE_DATA::deser(version, payload).map(Self::GOPRO_SET_RESPONSE)
}
200u32 => GIMBAL_REPORT_DATA::deser(version, payload).map(Self::GIMBAL_REPORT),
11u32 => SET_MODE_DATA::deser(version, payload).map(Self::SET_MODE),
276u32 => CAMERA_TRACKING_GEO_STATUS_DATA::deser(version, payload)
.map(Self::CAMERA_TRACKING_GEO_STATUS),
324u32 => PARAM_EXT_ACK_DATA::deser(version, payload).map(Self::PARAM_EXT_ACK),
11003u32 => {
DEVICE_OP_WRITE_REPLY_DATA::deser(version, payload).map(Self::DEVICE_OP_WRITE_REPLY)
}
174u32 => AIRSPEED_AUTOCAL_DATA::deser(version, payload).map(Self::AIRSPEED_AUTOCAL),
375u32 => ACTUATOR_OUTPUT_STATUS_DATA::deser(version, payload)
.map(Self::ACTUATOR_OUTPUT_STATUS),
120u32 => LOG_DATA_DATA::deser(version, payload).map(Self::LOG_DATA),
89u32 => LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::deser(version, payload)
.map(Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET),
215u32 => GOPRO_HEARTBEAT_DATA::deser(version, payload).map(Self::GOPRO_HEARTBEAT),
259u32 => {
CAMERA_INFORMATION_DATA::deser(version, payload).map(Self::CAMERA_INFORMATION)
}
11034u32 => OSD_PARAM_CONFIG_REPLY_DATA::deser(version, payload)
.map(Self::OSD_PARAM_CONFIG_REPLY),
24u32 => GPS_RAW_INT_DATA::deser(version, payload).map(Self::GPS_RAW_INT),
108u32 => SIM_STATE_DATA::deser(version, payload).map(Self::SIM_STATE),
77u32 => COMMAND_ACK_DATA::deser(version, payload).map(Self::COMMAND_ACK),
143u32 => SCALED_PRESSURE3_DATA::deser(version, payload).map(Self::SCALED_PRESSURE3),
12915u32 => OPEN_DRONE_ID_MESSAGE_PACK_DATA::deser(version, payload)
.map(Self::OPEN_DRONE_ID_MESSAGE_PACK),
339u32 => RAW_RPM_DATA::deser(version, payload).map(Self::RAW_RPM),
128u32 => GPS2_RTK_DATA::deser(version, payload).map(Self::GPS2_RTK),
134u32 => TERRAIN_DATA_DATA::deser(version, payload).map(Self::TERRAIN_DATA),
41u32 => {
MISSION_SET_CURRENT_DATA::deser(version, payload).map(Self::MISSION_SET_CURRENT)
}
140u32 => ACTUATOR_CONTROL_TARGET_DATA::deser(version, payload)
.map(Self::ACTUATOR_CONTROL_TARGET),
157u32 => MOUNT_CONTROL_DATA::deser(version, payload).map(Self::MOUNT_CONTROL),
132u32 => DISTANCE_SENSOR_DATA::deser(version, payload).map(Self::DISTANCE_SENSOR),
380u32 => TIME_ESTIMATE_TO_TARGET_DATA::deser(version, payload)
.map(Self::TIME_ESTIMATE_TO_TARGET),
334u32 => CELLULAR_STATUS_DATA::deser(version, payload).map(Self::CELLULAR_STATUS),
285u32 => GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::deser(version, payload)
.map(Self::GIMBAL_DEVICE_ATTITUDE_STATUS),
63u32 => GLOBAL_POSITION_INT_COV_DATA::deser(version, payload)
.map(Self::GLOBAL_POSITION_INT_COV),
34u32 => RC_CHANNELS_SCALED_DATA::deser(version, payload).map(Self::RC_CHANNELS_SCALED),
256u32 => SETUP_SIGNING_DATA::deser(version, payload).map(Self::SETUP_SIGNING),
262u32 => {
CAMERA_CAPTURE_STATUS_DATA::deser(version, payload).map(Self::CAMERA_CAPTURE_STATUS)
}
184u32 => {
REMOTE_LOG_DATA_BLOCK_DATA::deser(version, payload).map(Self::REMOTE_LOG_DATA_BLOCK)
}
258u32 => PLAY_TUNE_DATA::deser(version, payload).map(Self::PLAY_TUNE),
178u32 => AHRS2_DATA::deser(version, payload).map(Self::AHRS2),
115u32 => {
HIL_STATE_QUATERNION_DATA::deser(version, payload).map(Self::HIL_STATE_QUATERNION)
}
28u32 => RAW_PRESSURE_DATA::deser(version, payload).map(Self::RAW_PRESSURE),
9005u32 => WINCH_STATUS_DATA::deser(version, payload).map(Self::WINCH_STATUS),
275u32 => CAMERA_TRACKING_IMAGE_STATUS_DATA::deser(version, payload)
.map(Self::CAMERA_TRACKING_IMAGE_STATUS),
20u32 => PARAM_REQUEST_READ_DATA::deser(version, payload).map(Self::PARAM_REQUEST_READ),
44u32 => MISSION_COUNT_DATA::deser(version, payload).map(Self::MISSION_COUNT),
226u32 => RPM_DATA::deser(version, payload).map(Self::RPM),
11032u32 => {
ESC_TELEMETRY_9_TO_12_DATA::deser(version, payload).map(Self::ESC_TELEMETRY_9_TO_12)
}
9000u32 => WHEEL_DISTANCE_DATA::deser(version, payload).map(Self::WHEEL_DISTANCE),
254u32 => DEBUG_DATA::deser(version, payload).map(Self::DEBUG),
107u32 => HIL_SENSOR_DATA::deser(version, payload).map(Self::HIL_SENSOR),
80u32 => COMMAND_CANCEL_DATA::deser(version, payload).map(Self::COMMAND_CANCEL),
162u32 => FENCE_STATUS_DATA::deser(version, payload).map(Self::FENCE_STATUS),
330u32 => OBSTACLE_DISTANCE_DATA::deser(version, payload).map(Self::OBSTACLE_DISTANCE),
152u32 => MEMINFO_DATA::deser(version, payload).map(Self::MEMINFO),
194u32 => PID_TUNING_DATA::deser(version, payload).map(Self::PID_TUNING),
10001u32 => {
UAVIONIX_ADSB_OUT_CFG_DATA::deser(version, payload).map(Self::UAVIONIX_ADSB_OUT_CFG)
}
397u32 => {
COMPONENT_METADATA_DATA::deser(version, payload).map(Self::COMPONENT_METADATA)
}
11036u32 => OSD_PARAM_SHOW_CONFIG_REPLY_DATA::deser(version, payload)
.map(Self::OSD_PARAM_SHOW_CONFIG_REPLY),
320u32 => PARAM_EXT_REQUEST_READ_DATA::deser(version, payload)
.map(Self::PARAM_EXT_REQUEST_READ),
335u32 => ISBD_LINK_STATUS_DATA::deser(version, payload).map(Self::ISBD_LINK_STATUS),
331u32 => ODOMETRY_DATA::deser(version, payload).map(Self::ODOMETRY),
113u32 => HIL_GPS_DATA::deser(version, payload).map(Self::HIL_GPS),
64u32 => LOCAL_POSITION_NED_COV_DATA::deser(version, payload)
.map(Self::LOCAL_POSITION_NED_COV),
264u32 => {
FLIGHT_INFORMATION_DATA::deser(version, payload).map(Self::FLIGHT_INFORMATION)
}
117u32 => LOG_REQUEST_LIST_DATA::deser(version, payload).map(Self::LOG_REQUEST_LIST),
36u32 => SERVO_OUTPUT_RAW_DATA::deser(version, payload).map(Self::SERVO_OUTPUT_RAW),
51u32 => {
MISSION_REQUEST_INT_DATA::deser(version, payload).map(Self::MISSION_REQUEST_INT)
}
83u32 => ATTITUDE_TARGET_DATA::deser(version, payload).map(Self::ATTITUDE_TARGET),
125u32 => POWER_STATUS_DATA::deser(version, payload).map(Self::POWER_STATUS),
146u32 => {
CONTROL_SYSTEM_STATE_DATA::deser(version, payload).map(Self::CONTROL_SYSTEM_STATE)
}
11030u32 => {
ESC_TELEMETRY_1_TO_4_DATA::deser(version, payload).map(Self::ESC_TELEMETRY_1_TO_4)
}
73u32 => MISSION_ITEM_INT_DATA::deser(version, payload).map(Self::MISSION_ITEM_INT),
253u32 => STATUSTEXT_DATA::deser(version, payload).map(Self::STATUSTEXT),
12905u32 => OPEN_DRONE_ID_OPERATOR_ID_DATA::deser(version, payload)
.map(Self::OPEN_DRONE_ID_OPERATOR_ID),
2u32 => SYSTEM_TIME_DATA::deser(version, payload).map(Self::SYSTEM_TIME),
70u32 => {
RC_CHANNELS_OVERRIDE_DATA::deser(version, payload).map(Self::RC_CHANNELS_OVERRIDE)
}
11038u32 => WATER_DEPTH_DATA::deser(version, payload).map(Self::WATER_DEPTH),
21u32 => PARAM_REQUEST_LIST_DATA::deser(version, payload).map(Self::PARAM_REQUEST_LIST),
61u32 => ATTITUDE_QUATERNION_COV_DATA::deser(version, payload)
.map(Self::ATTITUDE_QUATERNION_COV),
131u32 => ENCAPSULATED_DATA_DATA::deser(version, payload).map(Self::ENCAPSULATED_DATA),
22u32 => PARAM_VALUE_DATA::deser(version, payload).map(Self::PARAM_VALUE),
6u32 => CHANGE_OPERATOR_CONTROL_ACK_DATA::deser(version, payload)
.map(Self::CHANGE_OPERATOR_CONTROL_ACK),
4u32 => PING_DATA::deser(version, payload).map(Self::PING),
48u32 => {
SET_GPS_GLOBAL_ORIGIN_DATA::deser(version, payload).map(Self::SET_GPS_GLOBAL_ORIGIN)
}
195u32 => DEEPSTALL_DATA::deser(version, payload).map(Self::DEEPSTALL),
218u32 => GOPRO_SET_REQUEST_DATA::deser(version, payload).map(Self::GOPRO_SET_REQUEST),
193u32 => EKF_STATUS_REPORT_DATA::deser(version, payload).map(Self::EKF_STATUS_REPORT),
11033u32 => OSD_PARAM_CONFIG_DATA::deser(version, payload).map(Self::OSD_PARAM_CONFIG),
321u32 => PARAM_EXT_REQUEST_LIST_DATA::deser(version, payload)
.map(Self::PARAM_EXT_REQUEST_LIST),
62u32 => {
NAV_CONTROLLER_OUTPUT_DATA::deser(version, payload).map(Self::NAV_CONTROLLER_OUTPUT)
}
10002u32 => UAVIONIX_ADSB_OUT_DYNAMIC_DATA::deser(version, payload)
.map(Self::UAVIONIX_ADSB_OUT_DYNAMIC),
116u32 => SCALED_IMU2_DATA::deser(version, payload).map(Self::SCALED_IMU2),
160u32 => FENCE_POINT_DATA::deser(version, payload).map(Self::FENCE_POINT),
139u32 => SET_ACTUATOR_CONTROL_TARGET_DATA::deser(version, payload)
.map(Self::SET_ACTUATOR_CONTROL_TARGET),
11020u32 => AOA_SSA_DATA::deser(version, payload).map(Self::AOA_SSA),
106u32 => OPTICAL_FLOW_RAD_DATA::deser(version, payload).map(Self::OPTICAL_FLOW_RAD),
104u32 => VICON_POSITION_ESTIMATE_DATA::deser(version, payload)
.map(Self::VICON_POSITION_ESTIMATE),
241u32 => VIBRATION_DATA::deser(version, payload).map(Self::VIBRATION),
149u32 => LANDING_TARGET_DATA::deser(version, payload).map(Self::LANDING_TARGET),
42u32 => MISSION_CURRENT_DATA::deser(version, payload).map(Self::MISSION_CURRENT),
171u32 => DATA64_DATA::deser(version, payload).map(Self::DATA64),
111u32 => TIMESYNC_DATA::deser(version, payload).map(Self::TIMESYNC),
251u32 => NAMED_VALUE_FLOAT_DATA::deser(version, payload).map(Self::NAMED_VALUE_FLOAT),
141u32 => ALTITUDE_DATA::deser(version, payload).map(Self::ALTITUDE),
114u32 => HIL_OPTICAL_FLOW_DATA::deser(version, payload).map(Self::HIL_OPTICAL_FLOW),
247u32 => COLLISION_DATA::deser(version, payload).map(Self::COLLISION),
412u32 => REQUEST_EVENT_DATA::deser(version, payload).map(Self::REQUEST_EVENT),
180u32 => CAMERA_FEEDBACK_DATA::deser(version, payload).map(Self::CAMERA_FEEDBACK),
216u32 => GOPRO_GET_REQUEST_DATA::deser(version, payload).map(Self::GOPRO_GET_REQUEST),
142u32 => RESOURCE_REQUEST_DATA::deser(version, payload).map(Self::RESOURCE_REQUEST),
248u32 => V2_EXTENSION_DATA::deser(version, payload).map(Self::V2_EXTENSION),
300u32 => PROTOCOL_VERSION_DATA::deser(version, payload).map(Self::PROTOCOL_VERSION),
50u32 => PARAM_MAP_RC_DATA::deser(version, payload).map(Self::PARAM_MAP_RC),
333u32 => TRAJECTORY_REPRESENTATION_BEZIER_DATA::deser(version, payload)
.map(Self::TRAJECTORY_REPRESENTATION_BEZIER),
23u32 => PARAM_SET_DATA::deser(version, payload).map(Self::PARAM_SET),
42000u32 => {
ICAROUS_HEARTBEAT_DATA::deser(version, payload).map(Self::ICAROUS_HEARTBEAT)
}
182u32 => AHRS3_DATA::deser(version, payload).map(Self::AHRS3),
385u32 => TUNNEL_DATA::deser(version, payload).map(Self::TUNNEL),
11039u32 => MCU_STATUS_DATA::deser(version, payload).map(Self::MCU_STATUS),
410u32 => EVENT_DATA::deser(version, payload).map(Self::EVENT),
126u32 => SERIAL_CONTROL_DATA::deser(version, payload).map(Self::SERIAL_CONTROL),
7u32 => AUTH_KEY_DATA::deser(version, payload).map(Self::AUTH_KEY),
246u32 => ADSB_VEHICLE_DATA::deser(version, payload).map(Self::ADSB_VEHICLE),
84u32 => SET_POSITION_TARGET_LOCAL_NED_DATA::deser(version, payload)
.map(Self::SET_POSITION_TARGET_LOCAL_NED),
232u32 => GPS_INPUT_DATA::deser(version, payload).map(Self::GPS_INPUT),
244u32 => MESSAGE_INTERVAL_DATA::deser(version, payload).map(Self::MESSAGE_INTERVAL),
267u32 => {
LOGGING_DATA_ACKED_DATA::deser(version, payload).map(Self::LOGGING_DATA_ACKED)
}
50002u32 => HERELINK_VIDEO_STREAM_INFORMATION_DATA::deser(version, payload)
.map(Self::HERELINK_VIDEO_STREAM_INFORMATION),
151u32 => SET_MAG_OFFSETS_DATA::deser(version, payload).map(Self::SET_MAG_OFFSETS),
130u32 => DATA_TRANSMISSION_HANDSHAKE_DATA::deser(version, payload)
.map(Self::DATA_TRANSMISSION_HANDSHAKE),
91u32 => HIL_CONTROLS_DATA::deser(version, payload).map(Self::HIL_CONTROLS),
173u32 => RANGEFINDER_DATA::deser(version, payload).map(Self::RANGEFINDER),
10003u32 => UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::deser(version, payload)
.map(Self::UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT),
268u32 => LOGGING_ACK_DATA::deser(version, payload).map(Self::LOGGING_ACK),
55u32 => {
SAFETY_ALLOWED_AREA_DATA::deser(version, payload).map(Self::SAFETY_ALLOWED_AREA)
}
387u32 => CANFD_FRAME_DATA::deser(version, payload).map(Self::CANFD_FRAME),
43u32 => {
MISSION_REQUEST_LIST_DATA::deser(version, payload).map(Self::MISSION_REQUEST_LIST)
}
86u32 => SET_POSITION_TARGET_GLOBAL_INT_DATA::deser(version, payload)
.map(Self::SET_POSITION_TARGET_GLOBAL_INT),
263u32 => {
CAMERA_IMAGE_CAPTURED_DATA::deser(version, payload).map(Self::CAMERA_IMAGE_CAPTURED)
}
75u32 => COMMAND_INT_DATA::deser(version, payload).map(Self::COMMAND_INT),
170u32 => DATA32_DATA::deser(version, payload).map(Self::DATA32),
33u32 => {
GLOBAL_POSITION_INT_DATA::deser(version, payload).map(Self::GLOBAL_POSITION_INT)
}
92u32 => HIL_RC_INPUTS_RAW_DATA::deser(version, payload).map(Self::HIL_RC_INPUTS_RAW),
12918u32 => OPEN_DRONE_ID_ARM_STATUS_DATA::deser(version, payload)
.map(Self::OPEN_DRONE_ID_ARM_STATUS),
287u32 => GIMBAL_MANAGER_SET_PITCHYAW_DATA::deser(version, payload)
.map(Self::GIMBAL_MANAGER_SET_PITCHYAW),
166u32 => RADIO_DATA::deser(version, payload).map(Self::RADIO),
49u32 => GPS_GLOBAL_ORIGIN_DATA::deser(version, payload).map(Self::GPS_GLOBAL_ORIGIN),
37u32 => MISSION_REQUEST_PARTIAL_LIST_DATA::deser(version, payload)
.map(Self::MISSION_REQUEST_PARTIAL_LIST),
122u32 => LOG_REQUEST_END_DATA::deser(version, payload).map(Self::LOG_REQUEST_END),
119u32 => LOG_REQUEST_DATA_DATA::deser(version, payload).map(Self::LOG_REQUEST_DATA),
54u32 => SAFETY_SET_ALLOWED_AREA_DATA::deser(version, payload)
.map(Self::SAFETY_SET_ALLOWED_AREA),
401u32 => SUPPORTED_TUNES_DATA::deser(version, payload).map(Self::SUPPORTED_TUNES),
245u32 => {
EXTENDED_SYS_STATE_DATA::deser(version, payload).map(Self::EXTENDED_SYS_STATE)
}
11002u32 => DEVICE_OP_WRITE_DATA::deser(version, payload).map(Self::DEVICE_OP_WRITE),
373u32 => GENERATOR_STATUS_DATA::deser(version, payload).map(Self::GENERATOR_STATUS),
31u32 => {
ATTITUDE_QUATERNION_DATA::deser(version, payload).map(Self::ATTITUDE_QUATERNION)
}
163u32 => AHRS_DATA::deser(version, payload).map(Self::AHRS),
136u32 => TERRAIN_REPORT_DATA::deser(version, payload).map(Self::TERRAIN_REPORT),
12902u32 => OPEN_DRONE_ID_AUTHENTICATION_DATA::deser(version, payload)
.map(Self::OPEN_DRONE_ID_AUTHENTICATION),
413u32 => {
RESPONSE_EVENT_ERROR_DATA::deser(version, payload).map(Self::RESPONSE_EVENT_ERROR)
}
129u32 => SCALED_IMU3_DATA::deser(version, payload).map(Self::SCALED_IMU3),
87u32 => POSITION_TARGET_GLOBAL_INT_DATA::deser(version, payload)
.map(Self::POSITION_TARGET_GLOBAL_INT),
25u32 => GPS_STATUS_DATA::deser(version, payload).map(Self::GPS_STATUS),
310u32 => {
UAVCAN_NODE_STATUS_DATA::deser(version, payload).map(Self::UAVCAN_NODE_STATUS)
}
192u32 => MAG_CAL_REPORT_DATA::deser(version, payload).map(Self::MAG_CAL_REPORT),
137u32 => SCALED_PRESSURE2_DATA::deser(version, payload).map(Self::SCALED_PRESSURE2),
386u32 => CAN_FRAME_DATA::deser(version, payload).map(Self::CAN_FRAME),
100u32 => OPTICAL_FLOW_DATA::deser(version, payload).map(Self::OPTICAL_FLOW),
281u32 => {
GIMBAL_MANAGER_STATUS_DATA::deser(version, payload).map(Self::GIMBAL_MANAGER_STATUS)
}
135u32 => TERRAIN_CHECK_DATA::deser(version, payload).map(Self::TERRAIN_CHECK),
269u32 => VIDEO_STREAM_INFORMATION_DATA::deser(version, payload)
.map(Self::VIDEO_STREAM_INFORMATION),
158u32 => MOUNT_STATUS_DATA::deser(version, payload).map(Self::MOUNT_STATUS),
82u32 => {
SET_ATTITUDE_TARGET_DATA::deser(version, payload).map(Self::SET_ATTITUDE_TARGET)
}
282u32 => GIMBAL_MANAGER_SET_ATTITUDE_DATA::deser(version, payload)
.map(Self::GIMBAL_MANAGER_SET_ATTITUDE),
284u32 => GIMBAL_DEVICE_SET_ATTITUDE_DATA::deser(version, payload)
.map(Self::GIMBAL_DEVICE_SET_ATTITUDE),
105u32 => HIGHRES_IMU_DATA::deser(version, payload).map(Self::HIGHRES_IMU),
288u32 => GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::deser(version, payload)
.map(Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL),
112u32 => CAMERA_TRIGGER_DATA::deser(version, payload).map(Self::CAMERA_TRIGGER),
181u32 => BATTERY2_DATA::deser(version, payload).map(Self::BATTERY2),
185u32 => REMOTE_LOG_BLOCK_STATUS_DATA::deser(version, payload)
.map(Self::REMOTE_LOG_BLOCK_STATUS),
164u32 => SIMSTATE_DATA::deser(version, payload).map(Self::SIMSTATE),
165u32 => HWSTATUS_DATA::deser(version, payload).map(Self::HWSTATUS),
167u32 => LIMITS_STATUS_DATA::deser(version, payload).map(Self::LIMITS_STATUS),
235u32 => HIGH_LATENCY2_DATA::deser(version, payload).map(Self::HIGH_LATENCY2),
261u32 => {
STORAGE_INFORMATION_DATA::deser(version, payload).map(Self::STORAGE_INFORMATION)
}
148u32 => AUTOPILOT_VERSION_DATA::deser(version, payload).map(Self::AUTOPILOT_VERSION),
47u32 => MISSION_ACK_DATA::deser(version, payload).map(Self::MISSION_ACK),
161u32 => FENCE_FETCH_POINT_DATA::deser(version, payload).map(Self::FENCE_FETCH_POINT),
156u32 => MOUNT_CONFIGURE_DATA::deser(version, payload).map(Self::MOUNT_CONFIGURE),
332u32 => TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::deser(version, payload)
.map(Self::TRAJECTORY_REPRESENTATION_WAYPOINTS),
5u32 => CHANGE_OPERATOR_CONTROL_DATA::deser(version, payload)
.map(Self::CHANGE_OPERATOR_CONTROL),
395u32 => {
COMPONENT_INFORMATION_DATA::deser(version, payload).map(Self::COMPONENT_INFORMATION)
}
1u32 => SYS_STATUS_DATA::deser(version, payload).map(Self::SYS_STATUS),
11010u32 => ADAP_TUNING_DATA::deser(version, payload).map(Self::ADAP_TUNING),
101u32 => GLOBAL_VISION_POSITION_ESTIMATE_DATA::deser(version, payload)
.map(Self::GLOBAL_VISION_POSITION_ESTIMATE),
154u32 => DIGICAM_CONFIGURE_DATA::deser(version, payload).map(Self::DIGICAM_CONFIGURE),
133u32 => TERRAIN_REQUEST_DATA::deser(version, payload).map(Self::TERRAIN_REQUEST),
172u32 => DATA96_DATA::deser(version, payload).map(Self::DATA96),
11035u32 => {
OSD_PARAM_SHOW_CONFIG_DATA::deser(version, payload).map(Self::OSD_PARAM_SHOW_CONFIG)
}
109u32 => RADIO_STATUS_DATA::deser(version, payload).map(Self::RADIO_STATUS),
27u32 => RAW_IMU_DATA::deser(version, payload).map(Self::RAW_IMU),
39u32 => MISSION_ITEM_DATA::deser(version, payload).map(Self::MISSION_ITEM),
66u32 => {
REQUEST_DATA_STREAM_DATA::deser(version, payload).map(Self::REQUEST_DATA_STREAM)
}
270u32 => {
VIDEO_STREAM_STATUS_DATA::deser(version, payload).map(Self::VIDEO_STREAM_STATUS)
}
121u32 => LOG_ERASE_DATA::deser(version, payload).map(Self::LOG_ERASE),
69u32 => MANUAL_CONTROL_DATA::deser(version, payload).map(Self::MANUAL_CONTROL),
76u32 => COMMAND_LONG_DATA::deser(version, payload).map(Self::COMMAND_LONG),
81u32 => MANUAL_SETPOINT_DATA::deser(version, payload).map(Self::MANUAL_SETPOINT),
12919u32 => OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::deser(version, payload)
.map(Self::OPEN_DRONE_ID_SYSTEM_UPDATE),
12904u32 => {
OPEN_DRONE_ID_SYSTEM_DATA::deser(version, payload).map(Self::OPEN_DRONE_ID_SYSTEM)
}
8u32 => LINK_NODE_STATUS_DATA::deser(version, payload).map(Self::LINK_NODE_STATUS),
12903u32 => {
OPEN_DRONE_ID_SELF_ID_DATA::deser(version, payload).map(Self::OPEN_DRONE_ID_SELF_ID)
}
102u32 => VISION_POSITION_ESTIMATE_DATA::deser(version, payload)
.map(Self::VISION_POSITION_ESTIMATE),
11001u32 => {
DEVICE_OP_READ_REPLY_DATA::deser(version, payload).map(Self::DEVICE_OP_READ_REPLY)
}
12920u32 => {
HYGROMETER_SENSOR_DATA::deser(version, payload).map(Self::HYGROMETER_SENSOR)
}
138u32 => ATT_POS_MOCAP_DATA::deser(version, payload).map(Self::ATT_POS_MOCAP),
65u32 => RC_CHANNELS_DATA::deser(version, payload).map(Self::RC_CHANNELS),
144u32 => FOLLOW_TARGET_DATA::deser(version, payload).map(Self::FOLLOW_TARGET),
90u32 => HIL_STATE_DATA::deser(version, payload).map(Self::HIL_STATE),
242u32 => HOME_POSITION_DATA::deser(version, payload).map(Self::HOME_POSITION),
12901u32 => OPEN_DRONE_ID_LOCATION_DATA::deser(version, payload)
.map(Self::OPEN_DRONE_ID_LOCATION),
67u32 => DATA_STREAM_DATA::deser(version, payload).map(Self::DATA_STREAM),
45u32 => MISSION_CLEAR_ALL_DATA::deser(version, payload).map(Self::MISSION_CLEAR_ALL),
280u32 => GIMBAL_MANAGER_INFORMATION_DATA::deser(version, payload)
.map(Self::GIMBAL_MANAGER_INFORMATION),
103u32 => {
VISION_SPEED_ESTIMATE_DATA::deser(version, payload).map(Self::VISION_SPEED_ESTIMATE)
}
290u32 => ESC_INFO_DATA::deser(version, payload).map(Self::ESC_INFO),
169u32 => DATA16_DATA::deser(version, payload).map(Self::DATA16),
249u32 => MEMORY_VECT_DATA::deser(version, payload).map(Self::MEMORY_VECT),
191u32 => MAG_CAL_PROGRESS_DATA::deser(version, payload).map(Self::MAG_CAL_PROGRESS),
46u32 => {
MISSION_ITEM_REACHED_DATA::deser(version, payload).map(Self::MISSION_ITEM_REACHED)
}
265u32 => MOUNT_ORIENTATION_DATA::deser(version, payload).map(Self::MOUNT_ORIENTATION),
11000u32 => DEVICE_OP_READ_DATA::deser(version, payload).map(Self::DEVICE_OP_READ),
74u32 => VFR_HUD_DATA::deser(version, payload).map(Self::VFR_HUD),
411u32 => CURRENT_EVENT_SEQUENCE_DATA::deser(version, payload)
.map(Self::CURRENT_EVENT_SEQUENCE),
30u32 => ATTITUDE_DATA::deser(version, payload).map(Self::ATTITUDE),
29u32 => SCALED_PRESSURE_DATA::deser(version, payload).map(Self::SCALED_PRESSURE),
150u32 => SENSOR_OFFSETS_DATA::deser(version, payload).map(Self::SENSOR_OFFSETS),
11011u32 => {
VISION_POSITION_DELTA_DATA::deser(version, payload).map(Self::VISION_POSITION_DELTA)
}
266u32 => LOGGING_DATA_DATA::deser(version, payload).map(Self::LOGGING_DATA),
233u32 => GPS_RTCM_DATA_DATA::deser(version, payload).map(Self::GPS_RTCM_DATA),
85u32 => POSITION_TARGET_LOCAL_NED_DATA::deser(version, payload)
.map(Self::POSITION_TARGET_LOCAL_NED),
40u32 => MISSION_REQUEST_DATA::deser(version, payload).map(Self::MISSION_REQUEST),
271u32 => CAMERA_FOV_STATUS_DATA::deser(version, payload).map(Self::CAMERA_FOV_STATUS),
0u32 => HEARTBEAT_DATA::deser(version, payload).map(Self::HEARTBEAT),
155u32 => DIGICAM_CONTROL_DATA::deser(version, payload).map(Self::DIGICAM_CONTROL),
340u32 => {
UTM_GLOBAL_POSITION_DATA::deser(version, payload).map(Self::UTM_GLOBAL_POSITION)
}
176u32 => RALLY_FETCH_POINT_DATA::deser(version, payload).map(Self::RALLY_FETCH_POINT),
11037u32 => {
OBSTACLE_DISTANCE_3D_DATA::deser(version, payload).map(Self::OBSTACLE_DISTANCE_3D)
}
175u32 => RALLY_POINT_DATA::deser(version, payload).map(Self::RALLY_POINT),
35u32 => RC_CHANNELS_RAW_DATA::deser(version, payload).map(Self::RC_CHANNELS_RAW),
183u32 => AUTOPILOT_VERSION_REQUEST_DATA::deser(version, payload)
.map(Self::AUTOPILOT_VERSION_REQUEST),
231u32 => WIND_COV_DATA::deser(version, payload).map(Self::WIND_COV),
93u32 => {
HIL_ACTUATOR_CONTROLS_DATA::deser(version, payload).map(Self::HIL_ACTUATOR_CONTROLS)
}
260u32 => CAMERA_SETTINGS_DATA::deser(version, payload).map(Self::CAMERA_SETTINGS),
390u32 => ONBOARD_COMPUTER_STATUS_DATA::deser(version, payload)
.map(Self::ONBOARD_COMPUTER_STATUS),
110u32 => FILE_TRANSFER_PROTOCOL_DATA::deser(version, payload)
.map(Self::FILE_TRANSFER_PROTOCOL),
127u32 => GPS_RTK_DATA::deser(version, payload).map(Self::GPS_RTK),
283u32 => GIMBAL_DEVICE_INFORMATION_DATA::deser(version, payload)
.map(Self::GIMBAL_DEVICE_INFORMATION),
118u32 => LOG_ENTRY_DATA::deser(version, payload).map(Self::LOG_ENTRY),
291u32 => ESC_STATUS_DATA::deser(version, payload).map(Self::ESC_STATUS),
50003u32 => HERELINK_TELEM_DATA::deser(version, payload).map(Self::HERELINK_TELEM),
214u32 => GIMBAL_TORQUE_CMD_REPORT_DATA::deser(version, payload)
.map(Self::GIMBAL_TORQUE_CMD_REPORT),
234u32 => HIGH_LATENCY_DATA::deser(version, payload).map(Self::HIGH_LATENCY),
11031u32 => {
ESC_TELEMETRY_5_TO_8_DATA::deser(version, payload).map(Self::ESC_TELEMETRY_5_TO_8)
}
400u32 => PLAY_TUNE_V2_DATA::deser(version, payload).map(Self::PLAY_TUNE_V2),
243u32 => SET_HOME_POSITION_DATA::deser(version, payload).map(Self::SET_HOME_POSITION),
147u32 => BATTERY_STATUS_DATA::deser(version, payload).map(Self::BATTERY_STATUS),
12900u32 => OPEN_DRONE_ID_BASIC_ID_DATA::deser(version, payload)
.map(Self::OPEN_DRONE_ID_BASIC_ID),
323u32 => PARAM_EXT_SET_DATA::deser(version, payload).map(Self::PARAM_EXT_SET),
322u32 => PARAM_EXT_VALUE_DATA::deser(version, payload).map(Self::PARAM_EXT_VALUE),
360u32 => ORBIT_EXECUTION_STATUS_DATA::deser(version, payload)
.map(Self::ORBIT_EXECUTION_STATUS),
252u32 => NAMED_VALUE_INT_DATA::deser(version, payload).map(Self::NAMED_VALUE_INT),
186u32 => LED_CONTROL_DATA::deser(version, payload).map(Self::LED_CONTROL),
370u32 => {
SMART_BATTERY_INFO_DATA::deser(version, payload).map(Self::SMART_BATTERY_INFO)
}
_ => Err(ParserError::UnknownMessage { id }),
}
}
fn message_name(&self) -> &'static str {
match self {
Self::MISSION_WRITE_PARTIAL_LIST(..) => "MISSION_WRITE_PARTIAL_LIST",
Self::CUBEPILOT_FIRMWARE_UPDATE_START(..) => "CUBEPILOT_FIRMWARE_UPDATE_START",
Self::DEBUG_VECT(..) => "DEBUG_VECT",
Self::GIMBAL_CONTROL(..) => "GIMBAL_CONTROL",
Self::COMPASSMOT_STATUS(..) => "COMPASSMOT_STATUS",
Self::BUTTON_CHANGE(..) => "BUTTON_CHANGE",
Self::GPS_INJECT_DATA(..) => "GPS_INJECT_DATA",
Self::CAMERA_STATUS(..) => "CAMERA_STATUS",
Self::GOPRO_GET_RESPONSE(..) => "GOPRO_GET_RESPONSE",
Self::CUBEPILOT_RAW_RC(..) => "CUBEPILOT_RAW_RC",
Self::CELLULAR_CONFIG(..) => "CELLULAR_CONFIG",
Self::GPS2_RAW(..) => "GPS2_RAW",
Self::ESTIMATOR_STATUS(..) => "ESTIMATOR_STATUS",
Self::UAVCAN_NODE_INFO(..) => "UAVCAN_NODE_INFO",
Self::AIS_VESSEL(..) => "AIS_VESSEL",
Self::ICAROUS_KINEMATIC_BANDS(..) => "ICAROUS_KINEMATIC_BANDS",
Self::EFI_STATUS(..) => "EFI_STATUS",
Self::CAN_FILTER_MODIFY(..) => "CAN_FILTER_MODIFY",
Self::CUBEPILOT_FIRMWARE_UPDATE_RESP(..) => "CUBEPILOT_FIRMWARE_UPDATE_RESP",
Self::DEBUG_FLOAT_ARRAY(..) => "DEBUG_FLOAT_ARRAY",
Self::WIFI_CONFIG_AP(..) => "WIFI_CONFIG_AP",
Self::AP_ADC(..) => "AP_ADC",
Self::WIND(..) => "WIND",
Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(..) => "AUTOPILOT_STATE_FOR_GIMBAL_DEVICE",
Self::SCALED_IMU(..) => "SCALED_IMU",
Self::LOCAL_POSITION_NED(..) => "LOCAL_POSITION_NED",
Self::GOPRO_SET_RESPONSE(..) => "GOPRO_SET_RESPONSE",
Self::GIMBAL_REPORT(..) => "GIMBAL_REPORT",
Self::SET_MODE(..) => "SET_MODE",
Self::CAMERA_TRACKING_GEO_STATUS(..) => "CAMERA_TRACKING_GEO_STATUS",
Self::PARAM_EXT_ACK(..) => "PARAM_EXT_ACK",
Self::DEVICE_OP_WRITE_REPLY(..) => "DEVICE_OP_WRITE_REPLY",
Self::AIRSPEED_AUTOCAL(..) => "AIRSPEED_AUTOCAL",
Self::ACTUATOR_OUTPUT_STATUS(..) => "ACTUATOR_OUTPUT_STATUS",
Self::LOG_DATA(..) => "LOG_DATA",
Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(..) => {
"LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET"
}
Self::GOPRO_HEARTBEAT(..) => "GOPRO_HEARTBEAT",
Self::CAMERA_INFORMATION(..) => "CAMERA_INFORMATION",
Self::OSD_PARAM_CONFIG_REPLY(..) => "OSD_PARAM_CONFIG_REPLY",
Self::GPS_RAW_INT(..) => "GPS_RAW_INT",
Self::SIM_STATE(..) => "SIM_STATE",
Self::COMMAND_ACK(..) => "COMMAND_ACK",
Self::SCALED_PRESSURE3(..) => "SCALED_PRESSURE3",
Self::OPEN_DRONE_ID_MESSAGE_PACK(..) => "OPEN_DRONE_ID_MESSAGE_PACK",
Self::RAW_RPM(..) => "RAW_RPM",
Self::GPS2_RTK(..) => "GPS2_RTK",
Self::TERRAIN_DATA(..) => "TERRAIN_DATA",
Self::MISSION_SET_CURRENT(..) => "MISSION_SET_CURRENT",
Self::ACTUATOR_CONTROL_TARGET(..) => "ACTUATOR_CONTROL_TARGET",
Self::MOUNT_CONTROL(..) => "MOUNT_CONTROL",
Self::DISTANCE_SENSOR(..) => "DISTANCE_SENSOR",
Self::TIME_ESTIMATE_TO_TARGET(..) => "TIME_ESTIMATE_TO_TARGET",
Self::CELLULAR_STATUS(..) => "CELLULAR_STATUS",
Self::GIMBAL_DEVICE_ATTITUDE_STATUS(..) => "GIMBAL_DEVICE_ATTITUDE_STATUS",
Self::GLOBAL_POSITION_INT_COV(..) => "GLOBAL_POSITION_INT_COV",
Self::RC_CHANNELS_SCALED(..) => "RC_CHANNELS_SCALED",
Self::SETUP_SIGNING(..) => "SETUP_SIGNING",
Self::CAMERA_CAPTURE_STATUS(..) => "CAMERA_CAPTURE_STATUS",
Self::REMOTE_LOG_DATA_BLOCK(..) => "REMOTE_LOG_DATA_BLOCK",
Self::PLAY_TUNE(..) => "PLAY_TUNE",
Self::AHRS2(..) => "AHRS2",
Self::HIL_STATE_QUATERNION(..) => "HIL_STATE_QUATERNION",
Self::RAW_PRESSURE(..) => "RAW_PRESSURE",
Self::WINCH_STATUS(..) => "WINCH_STATUS",
Self::CAMERA_TRACKING_IMAGE_STATUS(..) => "CAMERA_TRACKING_IMAGE_STATUS",
Self::PARAM_REQUEST_READ(..) => "PARAM_REQUEST_READ",
Self::MISSION_COUNT(..) => "MISSION_COUNT",
Self::RPM(..) => "RPM",
Self::ESC_TELEMETRY_9_TO_12(..) => "ESC_TELEMETRY_9_TO_12",
Self::WHEEL_DISTANCE(..) => "WHEEL_DISTANCE",
Self::DEBUG(..) => "DEBUG",
Self::HIL_SENSOR(..) => "HIL_SENSOR",
Self::COMMAND_CANCEL(..) => "COMMAND_CANCEL",
Self::FENCE_STATUS(..) => "FENCE_STATUS",
Self::OBSTACLE_DISTANCE(..) => "OBSTACLE_DISTANCE",
Self::MEMINFO(..) => "MEMINFO",
Self::PID_TUNING(..) => "PID_TUNING",
Self::UAVIONIX_ADSB_OUT_CFG(..) => "UAVIONIX_ADSB_OUT_CFG",
Self::COMPONENT_METADATA(..) => "COMPONENT_METADATA",
Self::OSD_PARAM_SHOW_CONFIG_REPLY(..) => "OSD_PARAM_SHOW_CONFIG_REPLY",
Self::PARAM_EXT_REQUEST_READ(..) => "PARAM_EXT_REQUEST_READ",
Self::ISBD_LINK_STATUS(..) => "ISBD_LINK_STATUS",
Self::ODOMETRY(..) => "ODOMETRY",
Self::HIL_GPS(..) => "HIL_GPS",
Self::LOCAL_POSITION_NED_COV(..) => "LOCAL_POSITION_NED_COV",
Self::FLIGHT_INFORMATION(..) => "FLIGHT_INFORMATION",
Self::LOG_REQUEST_LIST(..) => "LOG_REQUEST_LIST",
Self::SERVO_OUTPUT_RAW(..) => "SERVO_OUTPUT_RAW",
Self::MISSION_REQUEST_INT(..) => "MISSION_REQUEST_INT",
Self::ATTITUDE_TARGET(..) => "ATTITUDE_TARGET",
Self::POWER_STATUS(..) => "POWER_STATUS",
Self::CONTROL_SYSTEM_STATE(..) => "CONTROL_SYSTEM_STATE",
Self::ESC_TELEMETRY_1_TO_4(..) => "ESC_TELEMETRY_1_TO_4",
Self::MISSION_ITEM_INT(..) => "MISSION_ITEM_INT",
Self::STATUSTEXT(..) => "STATUSTEXT",
Self::OPEN_DRONE_ID_OPERATOR_ID(..) => "OPEN_DRONE_ID_OPERATOR_ID",
Self::SYSTEM_TIME(..) => "SYSTEM_TIME",
Self::RC_CHANNELS_OVERRIDE(..) => "RC_CHANNELS_OVERRIDE",
Self::WATER_DEPTH(..) => "WATER_DEPTH",
Self::PARAM_REQUEST_LIST(..) => "PARAM_REQUEST_LIST",
Self::ATTITUDE_QUATERNION_COV(..) => "ATTITUDE_QUATERNION_COV",
Self::ENCAPSULATED_DATA(..) => "ENCAPSULATED_DATA",
Self::PARAM_VALUE(..) => "PARAM_VALUE",
Self::CHANGE_OPERATOR_CONTROL_ACK(..) => "CHANGE_OPERATOR_CONTROL_ACK",
Self::PING(..) => "PING",
Self::SET_GPS_GLOBAL_ORIGIN(..) => "SET_GPS_GLOBAL_ORIGIN",
Self::DEEPSTALL(..) => "DEEPSTALL",
Self::GOPRO_SET_REQUEST(..) => "GOPRO_SET_REQUEST",
Self::EKF_STATUS_REPORT(..) => "EKF_STATUS_REPORT",
Self::OSD_PARAM_CONFIG(..) => "OSD_PARAM_CONFIG",
Self::PARAM_EXT_REQUEST_LIST(..) => "PARAM_EXT_REQUEST_LIST",
Self::NAV_CONTROLLER_OUTPUT(..) => "NAV_CONTROLLER_OUTPUT",
Self::UAVIONIX_ADSB_OUT_DYNAMIC(..) => "UAVIONIX_ADSB_OUT_DYNAMIC",
Self::SCALED_IMU2(..) => "SCALED_IMU2",
Self::FENCE_POINT(..) => "FENCE_POINT",
Self::SET_ACTUATOR_CONTROL_TARGET(..) => "SET_ACTUATOR_CONTROL_TARGET",
Self::AOA_SSA(..) => "AOA_SSA",
Self::OPTICAL_FLOW_RAD(..) => "OPTICAL_FLOW_RAD",
Self::VICON_POSITION_ESTIMATE(..) => "VICON_POSITION_ESTIMATE",
Self::VIBRATION(..) => "VIBRATION",
Self::LANDING_TARGET(..) => "LANDING_TARGET",
Self::MISSION_CURRENT(..) => "MISSION_CURRENT",
Self::DATA64(..) => "DATA64",
Self::TIMESYNC(..) => "TIMESYNC",
Self::NAMED_VALUE_FLOAT(..) => "NAMED_VALUE_FLOAT",
Self::ALTITUDE(..) => "ALTITUDE",
Self::HIL_OPTICAL_FLOW(..) => "HIL_OPTICAL_FLOW",
Self::COLLISION(..) => "COLLISION",
Self::REQUEST_EVENT(..) => "REQUEST_EVENT",
Self::CAMERA_FEEDBACK(..) => "CAMERA_FEEDBACK",
Self::GOPRO_GET_REQUEST(..) => "GOPRO_GET_REQUEST",
Self::RESOURCE_REQUEST(..) => "RESOURCE_REQUEST",
Self::V2_EXTENSION(..) => "V2_EXTENSION",
Self::PROTOCOL_VERSION(..) => "PROTOCOL_VERSION",
Self::PARAM_MAP_RC(..) => "PARAM_MAP_RC",
Self::TRAJECTORY_REPRESENTATION_BEZIER(..) => "TRAJECTORY_REPRESENTATION_BEZIER",
Self::PARAM_SET(..) => "PARAM_SET",
Self::ICAROUS_HEARTBEAT(..) => "ICAROUS_HEARTBEAT",
Self::AHRS3(..) => "AHRS3",
Self::TUNNEL(..) => "TUNNEL",
Self::MCU_STATUS(..) => "MCU_STATUS",
Self::EVENT(..) => "EVENT",
Self::SERIAL_CONTROL(..) => "SERIAL_CONTROL",
Self::AUTH_KEY(..) => "AUTH_KEY",
Self::ADSB_VEHICLE(..) => "ADSB_VEHICLE",
Self::SET_POSITION_TARGET_LOCAL_NED(..) => "SET_POSITION_TARGET_LOCAL_NED",
Self::GPS_INPUT(..) => "GPS_INPUT",
Self::MESSAGE_INTERVAL(..) => "MESSAGE_INTERVAL",
Self::LOGGING_DATA_ACKED(..) => "LOGGING_DATA_ACKED",
Self::HERELINK_VIDEO_STREAM_INFORMATION(..) => "HERELINK_VIDEO_STREAM_INFORMATION",
Self::SET_MAG_OFFSETS(..) => "SET_MAG_OFFSETS",
Self::DATA_TRANSMISSION_HANDSHAKE(..) => "DATA_TRANSMISSION_HANDSHAKE",
Self::HIL_CONTROLS(..) => "HIL_CONTROLS",
Self::RANGEFINDER(..) => "RANGEFINDER",
Self::UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT(..) => {
"UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT"
}
Self::LOGGING_ACK(..) => "LOGGING_ACK",
Self::SAFETY_ALLOWED_AREA(..) => "SAFETY_ALLOWED_AREA",
Self::CANFD_FRAME(..) => "CANFD_FRAME",
Self::MISSION_REQUEST_LIST(..) => "MISSION_REQUEST_LIST",
Self::SET_POSITION_TARGET_GLOBAL_INT(..) => "SET_POSITION_TARGET_GLOBAL_INT",
Self::CAMERA_IMAGE_CAPTURED(..) => "CAMERA_IMAGE_CAPTURED",
Self::COMMAND_INT(..) => "COMMAND_INT",
Self::DATA32(..) => "DATA32",
Self::GLOBAL_POSITION_INT(..) => "GLOBAL_POSITION_INT",
Self::HIL_RC_INPUTS_RAW(..) => "HIL_RC_INPUTS_RAW",
Self::OPEN_DRONE_ID_ARM_STATUS(..) => "OPEN_DRONE_ID_ARM_STATUS",
Self::GIMBAL_MANAGER_SET_PITCHYAW(..) => "GIMBAL_MANAGER_SET_PITCHYAW",
Self::RADIO(..) => "RADIO",
Self::GPS_GLOBAL_ORIGIN(..) => "GPS_GLOBAL_ORIGIN",
Self::MISSION_REQUEST_PARTIAL_LIST(..) => "MISSION_REQUEST_PARTIAL_LIST",
Self::LOG_REQUEST_END(..) => "LOG_REQUEST_END",
Self::LOG_REQUEST_DATA(..) => "LOG_REQUEST_DATA",
Self::SAFETY_SET_ALLOWED_AREA(..) => "SAFETY_SET_ALLOWED_AREA",
Self::SUPPORTED_TUNES(..) => "SUPPORTED_TUNES",
Self::EXTENDED_SYS_STATE(..) => "EXTENDED_SYS_STATE",
Self::DEVICE_OP_WRITE(..) => "DEVICE_OP_WRITE",
Self::GENERATOR_STATUS(..) => "GENERATOR_STATUS",
Self::ATTITUDE_QUATERNION(..) => "ATTITUDE_QUATERNION",
Self::AHRS(..) => "AHRS",
Self::TERRAIN_REPORT(..) => "TERRAIN_REPORT",
Self::OPEN_DRONE_ID_AUTHENTICATION(..) => "OPEN_DRONE_ID_AUTHENTICATION",
Self::RESPONSE_EVENT_ERROR(..) => "RESPONSE_EVENT_ERROR",
Self::SCALED_IMU3(..) => "SCALED_IMU3",
Self::POSITION_TARGET_GLOBAL_INT(..) => "POSITION_TARGET_GLOBAL_INT",
Self::GPS_STATUS(..) => "GPS_STATUS",
Self::UAVCAN_NODE_STATUS(..) => "UAVCAN_NODE_STATUS",
Self::MAG_CAL_REPORT(..) => "MAG_CAL_REPORT",
Self::SCALED_PRESSURE2(..) => "SCALED_PRESSURE2",
Self::CAN_FRAME(..) => "CAN_FRAME",
Self::OPTICAL_FLOW(..) => "OPTICAL_FLOW",
Self::GIMBAL_MANAGER_STATUS(..) => "GIMBAL_MANAGER_STATUS",
Self::TERRAIN_CHECK(..) => "TERRAIN_CHECK",
Self::VIDEO_STREAM_INFORMATION(..) => "VIDEO_STREAM_INFORMATION",
Self::MOUNT_STATUS(..) => "MOUNT_STATUS",
Self::SET_ATTITUDE_TARGET(..) => "SET_ATTITUDE_TARGET",
Self::GIMBAL_MANAGER_SET_ATTITUDE(..) => "GIMBAL_MANAGER_SET_ATTITUDE",
Self::GIMBAL_DEVICE_SET_ATTITUDE(..) => "GIMBAL_DEVICE_SET_ATTITUDE",
Self::HIGHRES_IMU(..) => "HIGHRES_IMU",
Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(..) => "GIMBAL_MANAGER_SET_MANUAL_CONTROL",
Self::CAMERA_TRIGGER(..) => "CAMERA_TRIGGER",
Self::BATTERY2(..) => "BATTERY2",
Self::REMOTE_LOG_BLOCK_STATUS(..) => "REMOTE_LOG_BLOCK_STATUS",
Self::SIMSTATE(..) => "SIMSTATE",
Self::HWSTATUS(..) => "HWSTATUS",
Self::LIMITS_STATUS(..) => "LIMITS_STATUS",
Self::HIGH_LATENCY2(..) => "HIGH_LATENCY2",
Self::STORAGE_INFORMATION(..) => "STORAGE_INFORMATION",
Self::AUTOPILOT_VERSION(..) => "AUTOPILOT_VERSION",
Self::MISSION_ACK(..) => "MISSION_ACK",
Self::FENCE_FETCH_POINT(..) => "FENCE_FETCH_POINT",
Self::MOUNT_CONFIGURE(..) => "MOUNT_CONFIGURE",
Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(..) => "TRAJECTORY_REPRESENTATION_WAYPOINTS",
Self::CHANGE_OPERATOR_CONTROL(..) => "CHANGE_OPERATOR_CONTROL",
Self::COMPONENT_INFORMATION(..) => "COMPONENT_INFORMATION",
Self::SYS_STATUS(..) => "SYS_STATUS",
Self::ADAP_TUNING(..) => "ADAP_TUNING",
Self::GLOBAL_VISION_POSITION_ESTIMATE(..) => "GLOBAL_VISION_POSITION_ESTIMATE",
Self::DIGICAM_CONFIGURE(..) => "DIGICAM_CONFIGURE",
Self::TERRAIN_REQUEST(..) => "TERRAIN_REQUEST",
Self::DATA96(..) => "DATA96",
Self::OSD_PARAM_SHOW_CONFIG(..) => "OSD_PARAM_SHOW_CONFIG",
Self::RADIO_STATUS(..) => "RADIO_STATUS",
Self::RAW_IMU(..) => "RAW_IMU",
Self::MISSION_ITEM(..) => "MISSION_ITEM",
Self::REQUEST_DATA_STREAM(..) => "REQUEST_DATA_STREAM",
Self::VIDEO_STREAM_STATUS(..) => "VIDEO_STREAM_STATUS",
Self::LOG_ERASE(..) => "LOG_ERASE",
Self::MANUAL_CONTROL(..) => "MANUAL_CONTROL",
Self::COMMAND_LONG(..) => "COMMAND_LONG",
Self::MANUAL_SETPOINT(..) => "MANUAL_SETPOINT",
Self::OPEN_DRONE_ID_SYSTEM_UPDATE(..) => "OPEN_DRONE_ID_SYSTEM_UPDATE",
Self::OPEN_DRONE_ID_SYSTEM(..) => "OPEN_DRONE_ID_SYSTEM",
Self::LINK_NODE_STATUS(..) => "LINK_NODE_STATUS",
Self::OPEN_DRONE_ID_SELF_ID(..) => "OPEN_DRONE_ID_SELF_ID",
Self::VISION_POSITION_ESTIMATE(..) => "VISION_POSITION_ESTIMATE",
Self::DEVICE_OP_READ_REPLY(..) => "DEVICE_OP_READ_REPLY",
Self::HYGROMETER_SENSOR(..) => "HYGROMETER_SENSOR",
Self::ATT_POS_MOCAP(..) => "ATT_POS_MOCAP",
Self::RC_CHANNELS(..) => "RC_CHANNELS",
Self::FOLLOW_TARGET(..) => "FOLLOW_TARGET",
Self::HIL_STATE(..) => "HIL_STATE",
Self::HOME_POSITION(..) => "HOME_POSITION",
Self::OPEN_DRONE_ID_LOCATION(..) => "OPEN_DRONE_ID_LOCATION",
Self::DATA_STREAM(..) => "DATA_STREAM",
Self::MISSION_CLEAR_ALL(..) => "MISSION_CLEAR_ALL",
Self::GIMBAL_MANAGER_INFORMATION(..) => "GIMBAL_MANAGER_INFORMATION",
Self::VISION_SPEED_ESTIMATE(..) => "VISION_SPEED_ESTIMATE",
Self::ESC_INFO(..) => "ESC_INFO",
Self::DATA16(..) => "DATA16",
Self::MEMORY_VECT(..) => "MEMORY_VECT",
Self::MAG_CAL_PROGRESS(..) => "MAG_CAL_PROGRESS",
Self::MISSION_ITEM_REACHED(..) => "MISSION_ITEM_REACHED",
Self::MOUNT_ORIENTATION(..) => "MOUNT_ORIENTATION",
Self::DEVICE_OP_READ(..) => "DEVICE_OP_READ",
Self::VFR_HUD(..) => "VFR_HUD",
Self::CURRENT_EVENT_SEQUENCE(..) => "CURRENT_EVENT_SEQUENCE",
Self::ATTITUDE(..) => "ATTITUDE",
Self::SCALED_PRESSURE(..) => "SCALED_PRESSURE",
Self::SENSOR_OFFSETS(..) => "SENSOR_OFFSETS",
Self::VISION_POSITION_DELTA(..) => "VISION_POSITION_DELTA",
Self::LOGGING_DATA(..) => "LOGGING_DATA",
Self::GPS_RTCM_DATA(..) => "GPS_RTCM_DATA",
Self::POSITION_TARGET_LOCAL_NED(..) => "POSITION_TARGET_LOCAL_NED",
Self::MISSION_REQUEST(..) => "MISSION_REQUEST",
Self::CAMERA_FOV_STATUS(..) => "CAMERA_FOV_STATUS",
Self::HEARTBEAT(..) => "HEARTBEAT",
Self::DIGICAM_CONTROL(..) => "DIGICAM_CONTROL",
Self::UTM_GLOBAL_POSITION(..) => "UTM_GLOBAL_POSITION",
Self::RALLY_FETCH_POINT(..) => "RALLY_FETCH_POINT",
Self::OBSTACLE_DISTANCE_3D(..) => "OBSTACLE_DISTANCE_3D",
Self::RALLY_POINT(..) => "RALLY_POINT",
Self::RC_CHANNELS_RAW(..) => "RC_CHANNELS_RAW",
Self::AUTOPILOT_VERSION_REQUEST(..) => "AUTOPILOT_VERSION_REQUEST",
Self::WIND_COV(..) => "WIND_COV",
Self::HIL_ACTUATOR_CONTROLS(..) => "HIL_ACTUATOR_CONTROLS",
Self::CAMERA_SETTINGS(..) => "CAMERA_SETTINGS",
Self::ONBOARD_COMPUTER_STATUS(..) => "ONBOARD_COMPUTER_STATUS",
Self::FILE_TRANSFER_PROTOCOL(..) => "FILE_TRANSFER_PROTOCOL",
Self::GPS_RTK(..) => "GPS_RTK",
Self::GIMBAL_DEVICE_INFORMATION(..) => "GIMBAL_DEVICE_INFORMATION",
Self::LOG_ENTRY(..) => "LOG_ENTRY",
Self::ESC_STATUS(..) => "ESC_STATUS",
Self::HERELINK_TELEM(..) => "HERELINK_TELEM",
Self::GIMBAL_TORQUE_CMD_REPORT(..) => "GIMBAL_TORQUE_CMD_REPORT",
Self::HIGH_LATENCY(..) => "HIGH_LATENCY",
Self::ESC_TELEMETRY_5_TO_8(..) => "ESC_TELEMETRY_5_TO_8",
Self::PLAY_TUNE_V2(..) => "PLAY_TUNE_V2",
Self::SET_HOME_POSITION(..) => "SET_HOME_POSITION",
Self::BATTERY_STATUS(..) => "BATTERY_STATUS",
Self::OPEN_DRONE_ID_BASIC_ID(..) => "OPEN_DRONE_ID_BASIC_ID",
Self::PARAM_EXT_SET(..) => "PARAM_EXT_SET",
Self::PARAM_EXT_VALUE(..) => "PARAM_EXT_VALUE",
Self::ORBIT_EXECUTION_STATUS(..) => "ORBIT_EXECUTION_STATUS",
Self::NAMED_VALUE_INT(..) => "NAMED_VALUE_INT",
Self::LED_CONTROL(..) => "LED_CONTROL",
Self::SMART_BATTERY_INFO(..) => "SMART_BATTERY_INFO",
}
}
fn message_id(&self) -> u32 {
match self {
Self::MISSION_WRITE_PARTIAL_LIST(..) => 38u32,
Self::CUBEPILOT_FIRMWARE_UPDATE_START(..) => 50004u32,
Self::DEBUG_VECT(..) => 250u32,
Self::GIMBAL_CONTROL(..) => 201u32,
Self::COMPASSMOT_STATUS(..) => 177u32,
Self::BUTTON_CHANGE(..) => 257u32,
Self::GPS_INJECT_DATA(..) => 123u32,
Self::CAMERA_STATUS(..) => 179u32,
Self::GOPRO_GET_RESPONSE(..) => 217u32,
Self::CUBEPILOT_RAW_RC(..) => 50001u32,
Self::CELLULAR_CONFIG(..) => 336u32,
Self::GPS2_RAW(..) => 124u32,
Self::ESTIMATOR_STATUS(..) => 230u32,
Self::UAVCAN_NODE_INFO(..) => 311u32,
Self::AIS_VESSEL(..) => 301u32,
Self::ICAROUS_KINEMATIC_BANDS(..) => 42001u32,
Self::EFI_STATUS(..) => 225u32,
Self::CAN_FILTER_MODIFY(..) => 388u32,
Self::CUBEPILOT_FIRMWARE_UPDATE_RESP(..) => 50005u32,
Self::DEBUG_FLOAT_ARRAY(..) => 350u32,
Self::WIFI_CONFIG_AP(..) => 299u32,
Self::AP_ADC(..) => 153u32,
Self::WIND(..) => 168u32,
Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(..) => 286u32,
Self::SCALED_IMU(..) => 26u32,
Self::LOCAL_POSITION_NED(..) => 32u32,
Self::GOPRO_SET_RESPONSE(..) => 219u32,
Self::GIMBAL_REPORT(..) => 200u32,
Self::SET_MODE(..) => 11u32,
Self::CAMERA_TRACKING_GEO_STATUS(..) => 276u32,
Self::PARAM_EXT_ACK(..) => 324u32,
Self::DEVICE_OP_WRITE_REPLY(..) => 11003u32,
Self::AIRSPEED_AUTOCAL(..) => 174u32,
Self::ACTUATOR_OUTPUT_STATUS(..) => 375u32,
Self::LOG_DATA(..) => 120u32,
Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(..) => 89u32,
Self::GOPRO_HEARTBEAT(..) => 215u32,
Self::CAMERA_INFORMATION(..) => 259u32,
Self::OSD_PARAM_CONFIG_REPLY(..) => 11034u32,
Self::GPS_RAW_INT(..) => 24u32,
Self::SIM_STATE(..) => 108u32,
Self::COMMAND_ACK(..) => 77u32,
Self::SCALED_PRESSURE3(..) => 143u32,
Self::OPEN_DRONE_ID_MESSAGE_PACK(..) => 12915u32,
Self::RAW_RPM(..) => 339u32,
Self::GPS2_RTK(..) => 128u32,
Self::TERRAIN_DATA(..) => 134u32,
Self::MISSION_SET_CURRENT(..) => 41u32,
Self::ACTUATOR_CONTROL_TARGET(..) => 140u32,
Self::MOUNT_CONTROL(..) => 157u32,
Self::DISTANCE_SENSOR(..) => 132u32,
Self::TIME_ESTIMATE_TO_TARGET(..) => 380u32,
Self::CELLULAR_STATUS(..) => 334u32,
Self::GIMBAL_DEVICE_ATTITUDE_STATUS(..) => 285u32,
Self::GLOBAL_POSITION_INT_COV(..) => 63u32,
Self::RC_CHANNELS_SCALED(..) => 34u32,
Self::SETUP_SIGNING(..) => 256u32,
Self::CAMERA_CAPTURE_STATUS(..) => 262u32,
Self::REMOTE_LOG_DATA_BLOCK(..) => 184u32,
Self::PLAY_TUNE(..) => 258u32,
Self::AHRS2(..) => 178u32,
Self::HIL_STATE_QUATERNION(..) => 115u32,
Self::RAW_PRESSURE(..) => 28u32,
Self::WINCH_STATUS(..) => 9005u32,
Self::CAMERA_TRACKING_IMAGE_STATUS(..) => 275u32,
Self::PARAM_REQUEST_READ(..) => 20u32,
Self::MISSION_COUNT(..) => 44u32,
Self::RPM(..) => 226u32,
Self::ESC_TELEMETRY_9_TO_12(..) => 11032u32,
Self::WHEEL_DISTANCE(..) => 9000u32,
Self::DEBUG(..) => 254u32,
Self::HIL_SENSOR(..) => 107u32,
Self::COMMAND_CANCEL(..) => 80u32,
Self::FENCE_STATUS(..) => 162u32,
Self::OBSTACLE_DISTANCE(..) => 330u32,
Self::MEMINFO(..) => 152u32,
Self::PID_TUNING(..) => 194u32,
Self::UAVIONIX_ADSB_OUT_CFG(..) => 10001u32,
Self::COMPONENT_METADATA(..) => 397u32,
Self::OSD_PARAM_SHOW_CONFIG_REPLY(..) => 11036u32,
Self::PARAM_EXT_REQUEST_READ(..) => 320u32,
Self::ISBD_LINK_STATUS(..) => 335u32,
Self::ODOMETRY(..) => 331u32,
Self::HIL_GPS(..) => 113u32,
Self::LOCAL_POSITION_NED_COV(..) => 64u32,
Self::FLIGHT_INFORMATION(..) => 264u32,
Self::LOG_REQUEST_LIST(..) => 117u32,
Self::SERVO_OUTPUT_RAW(..) => 36u32,
Self::MISSION_REQUEST_INT(..) => 51u32,
Self::ATTITUDE_TARGET(..) => 83u32,
Self::POWER_STATUS(..) => 125u32,
Self::CONTROL_SYSTEM_STATE(..) => 146u32,
Self::ESC_TELEMETRY_1_TO_4(..) => 11030u32,
Self::MISSION_ITEM_INT(..) => 73u32,
Self::STATUSTEXT(..) => 253u32,
Self::OPEN_DRONE_ID_OPERATOR_ID(..) => 12905u32,
Self::SYSTEM_TIME(..) => 2u32,
Self::RC_CHANNELS_OVERRIDE(..) => 70u32,
Self::WATER_DEPTH(..) => 11038u32,
Self::PARAM_REQUEST_LIST(..) => 21u32,
Self::ATTITUDE_QUATERNION_COV(..) => 61u32,
Self::ENCAPSULATED_DATA(..) => 131u32,
Self::PARAM_VALUE(..) => 22u32,
Self::CHANGE_OPERATOR_CONTROL_ACK(..) => 6u32,
Self::PING(..) => 4u32,
Self::SET_GPS_GLOBAL_ORIGIN(..) => 48u32,
Self::DEEPSTALL(..) => 195u32,
Self::GOPRO_SET_REQUEST(..) => 218u32,
Self::EKF_STATUS_REPORT(..) => 193u32,
Self::OSD_PARAM_CONFIG(..) => 11033u32,
Self::PARAM_EXT_REQUEST_LIST(..) => 321u32,
Self::NAV_CONTROLLER_OUTPUT(..) => 62u32,
Self::UAVIONIX_ADSB_OUT_DYNAMIC(..) => 10002u32,
Self::SCALED_IMU2(..) => 116u32,
Self::FENCE_POINT(..) => 160u32,
Self::SET_ACTUATOR_CONTROL_TARGET(..) => 139u32,
Self::AOA_SSA(..) => 11020u32,
Self::OPTICAL_FLOW_RAD(..) => 106u32,
Self::VICON_POSITION_ESTIMATE(..) => 104u32,
Self::VIBRATION(..) => 241u32,
Self::LANDING_TARGET(..) => 149u32,
Self::MISSION_CURRENT(..) => 42u32,
Self::DATA64(..) => 171u32,
Self::TIMESYNC(..) => 111u32,
Self::NAMED_VALUE_FLOAT(..) => 251u32,
Self::ALTITUDE(..) => 141u32,
Self::HIL_OPTICAL_FLOW(..) => 114u32,
Self::COLLISION(..) => 247u32,
Self::REQUEST_EVENT(..) => 412u32,
Self::CAMERA_FEEDBACK(..) => 180u32,
Self::GOPRO_GET_REQUEST(..) => 216u32,
Self::RESOURCE_REQUEST(..) => 142u32,
Self::V2_EXTENSION(..) => 248u32,
Self::PROTOCOL_VERSION(..) => 300u32,
Self::PARAM_MAP_RC(..) => 50u32,
Self::TRAJECTORY_REPRESENTATION_BEZIER(..) => 333u32,
Self::PARAM_SET(..) => 23u32,
Self::ICAROUS_HEARTBEAT(..) => 42000u32,
Self::AHRS3(..) => 182u32,
Self::TUNNEL(..) => 385u32,
Self::MCU_STATUS(..) => 11039u32,
Self::EVENT(..) => 410u32,
Self::SERIAL_CONTROL(..) => 126u32,
Self::AUTH_KEY(..) => 7u32,
Self::ADSB_VEHICLE(..) => 246u32,
Self::SET_POSITION_TARGET_LOCAL_NED(..) => 84u32,
Self::GPS_INPUT(..) => 232u32,
Self::MESSAGE_INTERVAL(..) => 244u32,
Self::LOGGING_DATA_ACKED(..) => 267u32,
Self::HERELINK_VIDEO_STREAM_INFORMATION(..) => 50002u32,
Self::SET_MAG_OFFSETS(..) => 151u32,
Self::DATA_TRANSMISSION_HANDSHAKE(..) => 130u32,
Self::HIL_CONTROLS(..) => 91u32,
Self::RANGEFINDER(..) => 173u32,
Self::UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT(..) => 10003u32,
Self::LOGGING_ACK(..) => 268u32,
Self::SAFETY_ALLOWED_AREA(..) => 55u32,
Self::CANFD_FRAME(..) => 387u32,
Self::MISSION_REQUEST_LIST(..) => 43u32,
Self::SET_POSITION_TARGET_GLOBAL_INT(..) => 86u32,
Self::CAMERA_IMAGE_CAPTURED(..) => 263u32,
Self::COMMAND_INT(..) => 75u32,
Self::DATA32(..) => 170u32,
Self::GLOBAL_POSITION_INT(..) => 33u32,
Self::HIL_RC_INPUTS_RAW(..) => 92u32,
Self::OPEN_DRONE_ID_ARM_STATUS(..) => 12918u32,
Self::GIMBAL_MANAGER_SET_PITCHYAW(..) => 287u32,
Self::RADIO(..) => 166u32,
Self::GPS_GLOBAL_ORIGIN(..) => 49u32,
Self::MISSION_REQUEST_PARTIAL_LIST(..) => 37u32,
Self::LOG_REQUEST_END(..) => 122u32,
Self::LOG_REQUEST_DATA(..) => 119u32,
Self::SAFETY_SET_ALLOWED_AREA(..) => 54u32,
Self::SUPPORTED_TUNES(..) => 401u32,
Self::EXTENDED_SYS_STATE(..) => 245u32,
Self::DEVICE_OP_WRITE(..) => 11002u32,
Self::GENERATOR_STATUS(..) => 373u32,
Self::ATTITUDE_QUATERNION(..) => 31u32,
Self::AHRS(..) => 163u32,
Self::TERRAIN_REPORT(..) => 136u32,
Self::OPEN_DRONE_ID_AUTHENTICATION(..) => 12902u32,
Self::RESPONSE_EVENT_ERROR(..) => 413u32,
Self::SCALED_IMU3(..) => 129u32,
Self::POSITION_TARGET_GLOBAL_INT(..) => 87u32,
Self::GPS_STATUS(..) => 25u32,
Self::UAVCAN_NODE_STATUS(..) => 310u32,
Self::MAG_CAL_REPORT(..) => 192u32,
Self::SCALED_PRESSURE2(..) => 137u32,
Self::CAN_FRAME(..) => 386u32,
Self::OPTICAL_FLOW(..) => 100u32,
Self::GIMBAL_MANAGER_STATUS(..) => 281u32,
Self::TERRAIN_CHECK(..) => 135u32,
Self::VIDEO_STREAM_INFORMATION(..) => 269u32,
Self::MOUNT_STATUS(..) => 158u32,
Self::SET_ATTITUDE_TARGET(..) => 82u32,
Self::GIMBAL_MANAGER_SET_ATTITUDE(..) => 282u32,
Self::GIMBAL_DEVICE_SET_ATTITUDE(..) => 284u32,
Self::HIGHRES_IMU(..) => 105u32,
Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(..) => 288u32,
Self::CAMERA_TRIGGER(..) => 112u32,
Self::BATTERY2(..) => 181u32,
Self::REMOTE_LOG_BLOCK_STATUS(..) => 185u32,
Self::SIMSTATE(..) => 164u32,
Self::HWSTATUS(..) => 165u32,
Self::LIMITS_STATUS(..) => 167u32,
Self::HIGH_LATENCY2(..) => 235u32,
Self::STORAGE_INFORMATION(..) => 261u32,
Self::AUTOPILOT_VERSION(..) => 148u32,
Self::MISSION_ACK(..) => 47u32,
Self::FENCE_FETCH_POINT(..) => 161u32,
Self::MOUNT_CONFIGURE(..) => 156u32,
Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(..) => 332u32,
Self::CHANGE_OPERATOR_CONTROL(..) => 5u32,
Self::COMPONENT_INFORMATION(..) => 395u32,
Self::SYS_STATUS(..) => 1u32,
Self::ADAP_TUNING(..) => 11010u32,
Self::GLOBAL_VISION_POSITION_ESTIMATE(..) => 101u32,
Self::DIGICAM_CONFIGURE(..) => 154u32,
Self::TERRAIN_REQUEST(..) => 133u32,
Self::DATA96(..) => 172u32,
Self::OSD_PARAM_SHOW_CONFIG(..) => 11035u32,
Self::RADIO_STATUS(..) => 109u32,
Self::RAW_IMU(..) => 27u32,
Self::MISSION_ITEM(..) => 39u32,
Self::REQUEST_DATA_STREAM(..) => 66u32,
Self::VIDEO_STREAM_STATUS(..) => 270u32,
Self::LOG_ERASE(..) => 121u32,
Self::MANUAL_CONTROL(..) => 69u32,
Self::COMMAND_LONG(..) => 76u32,
Self::MANUAL_SETPOINT(..) => 81u32,
Self::OPEN_DRONE_ID_SYSTEM_UPDATE(..) => 12919u32,
Self::OPEN_DRONE_ID_SYSTEM(..) => 12904u32,
Self::LINK_NODE_STATUS(..) => 8u32,
Self::OPEN_DRONE_ID_SELF_ID(..) => 12903u32,
Self::VISION_POSITION_ESTIMATE(..) => 102u32,
Self::DEVICE_OP_READ_REPLY(..) => 11001u32,
Self::HYGROMETER_SENSOR(..) => 12920u32,
Self::ATT_POS_MOCAP(..) => 138u32,
Self::RC_CHANNELS(..) => 65u32,
Self::FOLLOW_TARGET(..) => 144u32,
Self::HIL_STATE(..) => 90u32,
Self::HOME_POSITION(..) => 242u32,
Self::OPEN_DRONE_ID_LOCATION(..) => 12901u32,
Self::DATA_STREAM(..) => 67u32,
Self::MISSION_CLEAR_ALL(..) => 45u32,
Self::GIMBAL_MANAGER_INFORMATION(..) => 280u32,
Self::VISION_SPEED_ESTIMATE(..) => 103u32,
Self::ESC_INFO(..) => 290u32,
Self::DATA16(..) => 169u32,
Self::MEMORY_VECT(..) => 249u32,
Self::MAG_CAL_PROGRESS(..) => 191u32,
Self::MISSION_ITEM_REACHED(..) => 46u32,
Self::MOUNT_ORIENTATION(..) => 265u32,
Self::DEVICE_OP_READ(..) => 11000u32,
Self::VFR_HUD(..) => 74u32,
Self::CURRENT_EVENT_SEQUENCE(..) => 411u32,
Self::ATTITUDE(..) => 30u32,
Self::SCALED_PRESSURE(..) => 29u32,
Self::SENSOR_OFFSETS(..) => 150u32,
Self::VISION_POSITION_DELTA(..) => 11011u32,
Self::LOGGING_DATA(..) => 266u32,
Self::GPS_RTCM_DATA(..) => 233u32,
Self::POSITION_TARGET_LOCAL_NED(..) => 85u32,
Self::MISSION_REQUEST(..) => 40u32,
Self::CAMERA_FOV_STATUS(..) => 271u32,
Self::HEARTBEAT(..) => 0u32,
Self::DIGICAM_CONTROL(..) => 155u32,
Self::UTM_GLOBAL_POSITION(..) => 340u32,
Self::RALLY_FETCH_POINT(..) => 176u32,
Self::OBSTACLE_DISTANCE_3D(..) => 11037u32,
Self::RALLY_POINT(..) => 175u32,
Self::RC_CHANNELS_RAW(..) => 35u32,
Self::AUTOPILOT_VERSION_REQUEST(..) => 183u32,
Self::WIND_COV(..) => 231u32,
Self::HIL_ACTUATOR_CONTROLS(..) => 93u32,
Self::CAMERA_SETTINGS(..) => 260u32,
Self::ONBOARD_COMPUTER_STATUS(..) => 390u32,
Self::FILE_TRANSFER_PROTOCOL(..) => 110u32,
Self::GPS_RTK(..) => 127u32,
Self::GIMBAL_DEVICE_INFORMATION(..) => 283u32,
Self::LOG_ENTRY(..) => 118u32,
Self::ESC_STATUS(..) => 291u32,
Self::HERELINK_TELEM(..) => 50003u32,
Self::GIMBAL_TORQUE_CMD_REPORT(..) => 214u32,
Self::HIGH_LATENCY(..) => 234u32,
Self::ESC_TELEMETRY_5_TO_8(..) => 11031u32,
Self::PLAY_TUNE_V2(..) => 400u32,
Self::SET_HOME_POSITION(..) => 243u32,
Self::BATTERY_STATUS(..) => 147u32,
Self::OPEN_DRONE_ID_BASIC_ID(..) => 12900u32,
Self::PARAM_EXT_SET(..) => 323u32,
Self::PARAM_EXT_VALUE(..) => 322u32,
Self::ORBIT_EXECUTION_STATUS(..) => 360u32,
Self::NAMED_VALUE_INT(..) => 252u32,
Self::LED_CONTROL(..) => 186u32,
Self::SMART_BATTERY_INFO(..) => 370u32,
}
}
fn message_id_from_name(name: &str) -> Result<u32, &'static str> {
match name {
"MISSION_WRITE_PARTIAL_LIST" => Ok(38u32),
"CUBEPILOT_FIRMWARE_UPDATE_START" => Ok(50004u32),
"DEBUG_VECT" => Ok(250u32),
"GIMBAL_CONTROL" => Ok(201u32),
"COMPASSMOT_STATUS" => Ok(177u32),
"BUTTON_CHANGE" => Ok(257u32),
"GPS_INJECT_DATA" => Ok(123u32),
"CAMERA_STATUS" => Ok(179u32),
"GOPRO_GET_RESPONSE" => Ok(217u32),
"CUBEPILOT_RAW_RC" => Ok(50001u32),
"CELLULAR_CONFIG" => Ok(336u32),
"GPS2_RAW" => Ok(124u32),
"ESTIMATOR_STATUS" => Ok(230u32),
"UAVCAN_NODE_INFO" => Ok(311u32),
"AIS_VESSEL" => Ok(301u32),
"ICAROUS_KINEMATIC_BANDS" => Ok(42001u32),
"EFI_STATUS" => Ok(225u32),
"CAN_FILTER_MODIFY" => Ok(388u32),
"CUBEPILOT_FIRMWARE_UPDATE_RESP" => Ok(50005u32),
"DEBUG_FLOAT_ARRAY" => Ok(350u32),
"WIFI_CONFIG_AP" => Ok(299u32),
"AP_ADC" => Ok(153u32),
"WIND" => Ok(168u32),
"AUTOPILOT_STATE_FOR_GIMBAL_DEVICE" => Ok(286u32),
"SCALED_IMU" => Ok(26u32),
"LOCAL_POSITION_NED" => Ok(32u32),
"GOPRO_SET_RESPONSE" => Ok(219u32),
"GIMBAL_REPORT" => Ok(200u32),
"SET_MODE" => Ok(11u32),
"CAMERA_TRACKING_GEO_STATUS" => Ok(276u32),
"PARAM_EXT_ACK" => Ok(324u32),
"DEVICE_OP_WRITE_REPLY" => Ok(11003u32),
"AIRSPEED_AUTOCAL" => Ok(174u32),
"ACTUATOR_OUTPUT_STATUS" => Ok(375u32),
"LOG_DATA" => Ok(120u32),
"LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET" => Ok(89u32),
"GOPRO_HEARTBEAT" => Ok(215u32),
"CAMERA_INFORMATION" => Ok(259u32),
"OSD_PARAM_CONFIG_REPLY" => Ok(11034u32),
"GPS_RAW_INT" => Ok(24u32),
"SIM_STATE" => Ok(108u32),
"COMMAND_ACK" => Ok(77u32),
"SCALED_PRESSURE3" => Ok(143u32),
"OPEN_DRONE_ID_MESSAGE_PACK" => Ok(12915u32),
"RAW_RPM" => Ok(339u32),
"GPS2_RTK" => Ok(128u32),
"TERRAIN_DATA" => Ok(134u32),
"MISSION_SET_CURRENT" => Ok(41u32),
"ACTUATOR_CONTROL_TARGET" => Ok(140u32),
"MOUNT_CONTROL" => Ok(157u32),
"DISTANCE_SENSOR" => Ok(132u32),
"TIME_ESTIMATE_TO_TARGET" => Ok(380u32),
"CELLULAR_STATUS" => Ok(334u32),
"GIMBAL_DEVICE_ATTITUDE_STATUS" => Ok(285u32),
"GLOBAL_POSITION_INT_COV" => Ok(63u32),
"RC_CHANNELS_SCALED" => Ok(34u32),
"SETUP_SIGNING" => Ok(256u32),
"CAMERA_CAPTURE_STATUS" => Ok(262u32),
"REMOTE_LOG_DATA_BLOCK" => Ok(184u32),
"PLAY_TUNE" => Ok(258u32),
"AHRS2" => Ok(178u32),
"HIL_STATE_QUATERNION" => Ok(115u32),
"RAW_PRESSURE" => Ok(28u32),
"WINCH_STATUS" => Ok(9005u32),
"CAMERA_TRACKING_IMAGE_STATUS" => Ok(275u32),
"PARAM_REQUEST_READ" => Ok(20u32),
"MISSION_COUNT" => Ok(44u32),
"RPM" => Ok(226u32),
"ESC_TELEMETRY_9_TO_12" => Ok(11032u32),
"WHEEL_DISTANCE" => Ok(9000u32),
"DEBUG" => Ok(254u32),
"HIL_SENSOR" => Ok(107u32),
"COMMAND_CANCEL" => Ok(80u32),
"FENCE_STATUS" => Ok(162u32),
"OBSTACLE_DISTANCE" => Ok(330u32),
"MEMINFO" => Ok(152u32),
"PID_TUNING" => Ok(194u32),
"UAVIONIX_ADSB_OUT_CFG" => Ok(10001u32),
"COMPONENT_METADATA" => Ok(397u32),
"OSD_PARAM_SHOW_CONFIG_REPLY" => Ok(11036u32),
"PARAM_EXT_REQUEST_READ" => Ok(320u32),
"ISBD_LINK_STATUS" => Ok(335u32),
"ODOMETRY" => Ok(331u32),
"HIL_GPS" => Ok(113u32),
"LOCAL_POSITION_NED_COV" => Ok(64u32),
"FLIGHT_INFORMATION" => Ok(264u32),
"LOG_REQUEST_LIST" => Ok(117u32),
"SERVO_OUTPUT_RAW" => Ok(36u32),
"MISSION_REQUEST_INT" => Ok(51u32),
"ATTITUDE_TARGET" => Ok(83u32),
"POWER_STATUS" => Ok(125u32),
"CONTROL_SYSTEM_STATE" => Ok(146u32),
"ESC_TELEMETRY_1_TO_4" => Ok(11030u32),
"MISSION_ITEM_INT" => Ok(73u32),
"STATUSTEXT" => Ok(253u32),
"OPEN_DRONE_ID_OPERATOR_ID" => Ok(12905u32),
"SYSTEM_TIME" => Ok(2u32),
"RC_CHANNELS_OVERRIDE" => Ok(70u32),
"WATER_DEPTH" => Ok(11038u32),
"PARAM_REQUEST_LIST" => Ok(21u32),
"ATTITUDE_QUATERNION_COV" => Ok(61u32),
"ENCAPSULATED_DATA" => Ok(131u32),
"PARAM_VALUE" => Ok(22u32),
"CHANGE_OPERATOR_CONTROL_ACK" => Ok(6u32),
"PING" => Ok(4u32),
"SET_GPS_GLOBAL_ORIGIN" => Ok(48u32),
"DEEPSTALL" => Ok(195u32),
"GOPRO_SET_REQUEST" => Ok(218u32),
"EKF_STATUS_REPORT" => Ok(193u32),
"OSD_PARAM_CONFIG" => Ok(11033u32),
"PARAM_EXT_REQUEST_LIST" => Ok(321u32),
"NAV_CONTROLLER_OUTPUT" => Ok(62u32),
"UAVIONIX_ADSB_OUT_DYNAMIC" => Ok(10002u32),
"SCALED_IMU2" => Ok(116u32),
"FENCE_POINT" => Ok(160u32),
"SET_ACTUATOR_CONTROL_TARGET" => Ok(139u32),
"AOA_SSA" => Ok(11020u32),
"OPTICAL_FLOW_RAD" => Ok(106u32),
"VICON_POSITION_ESTIMATE" => Ok(104u32),
"VIBRATION" => Ok(241u32),
"LANDING_TARGET" => Ok(149u32),
"MISSION_CURRENT" => Ok(42u32),
"DATA64" => Ok(171u32),
"TIMESYNC" => Ok(111u32),
"NAMED_VALUE_FLOAT" => Ok(251u32),
"ALTITUDE" => Ok(141u32),
"HIL_OPTICAL_FLOW" => Ok(114u32),
"COLLISION" => Ok(247u32),
"REQUEST_EVENT" => Ok(412u32),
"CAMERA_FEEDBACK" => Ok(180u32),
"GOPRO_GET_REQUEST" => Ok(216u32),
"RESOURCE_REQUEST" => Ok(142u32),
"V2_EXTENSION" => Ok(248u32),
"PROTOCOL_VERSION" => Ok(300u32),
"PARAM_MAP_RC" => Ok(50u32),
"TRAJECTORY_REPRESENTATION_BEZIER" => Ok(333u32),
"PARAM_SET" => Ok(23u32),
"ICAROUS_HEARTBEAT" => Ok(42000u32),
"AHRS3" => Ok(182u32),
"TUNNEL" => Ok(385u32),
"MCU_STATUS" => Ok(11039u32),
"EVENT" => Ok(410u32),
"SERIAL_CONTROL" => Ok(126u32),
"AUTH_KEY" => Ok(7u32),
"ADSB_VEHICLE" => Ok(246u32),
"SET_POSITION_TARGET_LOCAL_NED" => Ok(84u32),
"GPS_INPUT" => Ok(232u32),
"MESSAGE_INTERVAL" => Ok(244u32),
"LOGGING_DATA_ACKED" => Ok(267u32),
"HERELINK_VIDEO_STREAM_INFORMATION" => Ok(50002u32),
"SET_MAG_OFFSETS" => Ok(151u32),
"DATA_TRANSMISSION_HANDSHAKE" => Ok(130u32),
"HIL_CONTROLS" => Ok(91u32),
"RANGEFINDER" => Ok(173u32),
"UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT" => Ok(10003u32),
"LOGGING_ACK" => Ok(268u32),
"SAFETY_ALLOWED_AREA" => Ok(55u32),
"CANFD_FRAME" => Ok(387u32),
"MISSION_REQUEST_LIST" => Ok(43u32),
"SET_POSITION_TARGET_GLOBAL_INT" => Ok(86u32),
"CAMERA_IMAGE_CAPTURED" => Ok(263u32),
"COMMAND_INT" => Ok(75u32),
"DATA32" => Ok(170u32),
"GLOBAL_POSITION_INT" => Ok(33u32),
"HIL_RC_INPUTS_RAW" => Ok(92u32),
"OPEN_DRONE_ID_ARM_STATUS" => Ok(12918u32),
"GIMBAL_MANAGER_SET_PITCHYAW" => Ok(287u32),
"RADIO" => Ok(166u32),
"GPS_GLOBAL_ORIGIN" => Ok(49u32),
"MISSION_REQUEST_PARTIAL_LIST" => Ok(37u32),
"LOG_REQUEST_END" => Ok(122u32),
"LOG_REQUEST_DATA" => Ok(119u32),
"SAFETY_SET_ALLOWED_AREA" => Ok(54u32),
"SUPPORTED_TUNES" => Ok(401u32),
"EXTENDED_SYS_STATE" => Ok(245u32),
"DEVICE_OP_WRITE" => Ok(11002u32),
"GENERATOR_STATUS" => Ok(373u32),
"ATTITUDE_QUATERNION" => Ok(31u32),
"AHRS" => Ok(163u32),
"TERRAIN_REPORT" => Ok(136u32),
"OPEN_DRONE_ID_AUTHENTICATION" => Ok(12902u32),
"RESPONSE_EVENT_ERROR" => Ok(413u32),
"SCALED_IMU3" => Ok(129u32),
"POSITION_TARGET_GLOBAL_INT" => Ok(87u32),
"GPS_STATUS" => Ok(25u32),
"UAVCAN_NODE_STATUS" => Ok(310u32),
"MAG_CAL_REPORT" => Ok(192u32),
"SCALED_PRESSURE2" => Ok(137u32),
"CAN_FRAME" => Ok(386u32),
"OPTICAL_FLOW" => Ok(100u32),
"GIMBAL_MANAGER_STATUS" => Ok(281u32),
"TERRAIN_CHECK" => Ok(135u32),
"VIDEO_STREAM_INFORMATION" => Ok(269u32),
"MOUNT_STATUS" => Ok(158u32),
"SET_ATTITUDE_TARGET" => Ok(82u32),
"GIMBAL_MANAGER_SET_ATTITUDE" => Ok(282u32),
"GIMBAL_DEVICE_SET_ATTITUDE" => Ok(284u32),
"HIGHRES_IMU" => Ok(105u32),
"GIMBAL_MANAGER_SET_MANUAL_CONTROL" => Ok(288u32),
"CAMERA_TRIGGER" => Ok(112u32),
"BATTERY2" => Ok(181u32),
"REMOTE_LOG_BLOCK_STATUS" => Ok(185u32),
"SIMSTATE" => Ok(164u32),
"HWSTATUS" => Ok(165u32),
"LIMITS_STATUS" => Ok(167u32),
"HIGH_LATENCY2" => Ok(235u32),
"STORAGE_INFORMATION" => Ok(261u32),
"AUTOPILOT_VERSION" => Ok(148u32),
"MISSION_ACK" => Ok(47u32),
"FENCE_FETCH_POINT" => Ok(161u32),
"MOUNT_CONFIGURE" => Ok(156u32),
"TRAJECTORY_REPRESENTATION_WAYPOINTS" => Ok(332u32),
"CHANGE_OPERATOR_CONTROL" => Ok(5u32),
"COMPONENT_INFORMATION" => Ok(395u32),
"SYS_STATUS" => Ok(1u32),
"ADAP_TUNING" => Ok(11010u32),
"GLOBAL_VISION_POSITION_ESTIMATE" => Ok(101u32),
"DIGICAM_CONFIGURE" => Ok(154u32),
"TERRAIN_REQUEST" => Ok(133u32),
"DATA96" => Ok(172u32),
"OSD_PARAM_SHOW_CONFIG" => Ok(11035u32),
"RADIO_STATUS" => Ok(109u32),
"RAW_IMU" => Ok(27u32),
"MISSION_ITEM" => Ok(39u32),
"REQUEST_DATA_STREAM" => Ok(66u32),
"VIDEO_STREAM_STATUS" => Ok(270u32),
"LOG_ERASE" => Ok(121u32),
"MANUAL_CONTROL" => Ok(69u32),
"COMMAND_LONG" => Ok(76u32),
"MANUAL_SETPOINT" => Ok(81u32),
"OPEN_DRONE_ID_SYSTEM_UPDATE" => Ok(12919u32),
"OPEN_DRONE_ID_SYSTEM" => Ok(12904u32),
"LINK_NODE_STATUS" => Ok(8u32),
"OPEN_DRONE_ID_SELF_ID" => Ok(12903u32),
"VISION_POSITION_ESTIMATE" => Ok(102u32),
"DEVICE_OP_READ_REPLY" => Ok(11001u32),
"HYGROMETER_SENSOR" => Ok(12920u32),
"ATT_POS_MOCAP" => Ok(138u32),
"RC_CHANNELS" => Ok(65u32),
"FOLLOW_TARGET" => Ok(144u32),
"HIL_STATE" => Ok(90u32),
"HOME_POSITION" => Ok(242u32),
"OPEN_DRONE_ID_LOCATION" => Ok(12901u32),
"DATA_STREAM" => Ok(67u32),
"MISSION_CLEAR_ALL" => Ok(45u32),
"GIMBAL_MANAGER_INFORMATION" => Ok(280u32),
"VISION_SPEED_ESTIMATE" => Ok(103u32),
"ESC_INFO" => Ok(290u32),
"DATA16" => Ok(169u32),
"MEMORY_VECT" => Ok(249u32),
"MAG_CAL_PROGRESS" => Ok(191u32),
"MISSION_ITEM_REACHED" => Ok(46u32),
"MOUNT_ORIENTATION" => Ok(265u32),
"DEVICE_OP_READ" => Ok(11000u32),
"VFR_HUD" => Ok(74u32),
"CURRENT_EVENT_SEQUENCE" => Ok(411u32),
"ATTITUDE" => Ok(30u32),
"SCALED_PRESSURE" => Ok(29u32),
"SENSOR_OFFSETS" => Ok(150u32),
"VISION_POSITION_DELTA" => Ok(11011u32),
"LOGGING_DATA" => Ok(266u32),
"GPS_RTCM_DATA" => Ok(233u32),
"POSITION_TARGET_LOCAL_NED" => Ok(85u32),
"MISSION_REQUEST" => Ok(40u32),
"CAMERA_FOV_STATUS" => Ok(271u32),
"HEARTBEAT" => Ok(0u32),
"DIGICAM_CONTROL" => Ok(155u32),
"UTM_GLOBAL_POSITION" => Ok(340u32),
"RALLY_FETCH_POINT" => Ok(176u32),
"OBSTACLE_DISTANCE_3D" => Ok(11037u32),
"RALLY_POINT" => Ok(175u32),
"RC_CHANNELS_RAW" => Ok(35u32),
"AUTOPILOT_VERSION_REQUEST" => Ok(183u32),
"WIND_COV" => Ok(231u32),
"HIL_ACTUATOR_CONTROLS" => Ok(93u32),
"CAMERA_SETTINGS" => Ok(260u32),
"ONBOARD_COMPUTER_STATUS" => Ok(390u32),
"FILE_TRANSFER_PROTOCOL" => Ok(110u32),
"GPS_RTK" => Ok(127u32),
"GIMBAL_DEVICE_INFORMATION" => Ok(283u32),
"LOG_ENTRY" => Ok(118u32),
"ESC_STATUS" => Ok(291u32),
"HERELINK_TELEM" => Ok(50003u32),
"GIMBAL_TORQUE_CMD_REPORT" => Ok(214u32),
"HIGH_LATENCY" => Ok(234u32),
"ESC_TELEMETRY_5_TO_8" => Ok(11031u32),
"PLAY_TUNE_V2" => Ok(400u32),
"SET_HOME_POSITION" => Ok(243u32),
"BATTERY_STATUS" => Ok(147u32),
"OPEN_DRONE_ID_BASIC_ID" => Ok(12900u32),
"PARAM_EXT_SET" => Ok(323u32),
"PARAM_EXT_VALUE" => Ok(322u32),
"ORBIT_EXECUTION_STATUS" => Ok(360u32),
"NAMED_VALUE_INT" => Ok(252u32),
"LED_CONTROL" => Ok(186u32),
"SMART_BATTERY_INFO" => Ok(370u32),
_ => Err("Invalid message name."),
}
}
fn default_message_from_id(id: u32) -> Result<Self, &'static str> {
match id {
38u32 => Ok(Self::MISSION_WRITE_PARTIAL_LIST(
MISSION_WRITE_PARTIAL_LIST_DATA::default(),
)),
50004u32 => Ok(Self::CUBEPILOT_FIRMWARE_UPDATE_START(
CUBEPILOT_FIRMWARE_UPDATE_START_DATA::default(),
)),
250u32 => Ok(Self::DEBUG_VECT(DEBUG_VECT_DATA::default())),
201u32 => Ok(Self::GIMBAL_CONTROL(GIMBAL_CONTROL_DATA::default())),
177u32 => Ok(Self::COMPASSMOT_STATUS(COMPASSMOT_STATUS_DATA::default())),
257u32 => Ok(Self::BUTTON_CHANGE(BUTTON_CHANGE_DATA::default())),
123u32 => Ok(Self::GPS_INJECT_DATA(GPS_INJECT_DATA_DATA::default())),
179u32 => Ok(Self::CAMERA_STATUS(CAMERA_STATUS_DATA::default())),
217u32 => Ok(Self::GOPRO_GET_RESPONSE(GOPRO_GET_RESPONSE_DATA::default())),
50001u32 => Ok(Self::CUBEPILOT_RAW_RC(CUBEPILOT_RAW_RC_DATA::default())),
336u32 => Ok(Self::CELLULAR_CONFIG(CELLULAR_CONFIG_DATA::default())),
124u32 => Ok(Self::GPS2_RAW(GPS2_RAW_DATA::default())),
230u32 => Ok(Self::ESTIMATOR_STATUS(ESTIMATOR_STATUS_DATA::default())),
311u32 => Ok(Self::UAVCAN_NODE_INFO(UAVCAN_NODE_INFO_DATA::default())),
301u32 => Ok(Self::AIS_VESSEL(AIS_VESSEL_DATA::default())),
42001u32 => Ok(Self::ICAROUS_KINEMATIC_BANDS(
ICAROUS_KINEMATIC_BANDS_DATA::default(),
)),
225u32 => Ok(Self::EFI_STATUS(EFI_STATUS_DATA::default())),
388u32 => Ok(Self::CAN_FILTER_MODIFY(CAN_FILTER_MODIFY_DATA::default())),
50005u32 => Ok(Self::CUBEPILOT_FIRMWARE_UPDATE_RESP(
CUBEPILOT_FIRMWARE_UPDATE_RESP_DATA::default(),
)),
350u32 => Ok(Self::DEBUG_FLOAT_ARRAY(DEBUG_FLOAT_ARRAY_DATA::default())),
299u32 => Ok(Self::WIFI_CONFIG_AP(WIFI_CONFIG_AP_DATA::default())),
153u32 => Ok(Self::AP_ADC(AP_ADC_DATA::default())),
168u32 => Ok(Self::WIND(WIND_DATA::default())),
286u32 => Ok(Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(
AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::default(),
)),
26u32 => Ok(Self::SCALED_IMU(SCALED_IMU_DATA::default())),
32u32 => Ok(Self::LOCAL_POSITION_NED(LOCAL_POSITION_NED_DATA::default())),
219u32 => Ok(Self::GOPRO_SET_RESPONSE(GOPRO_SET_RESPONSE_DATA::default())),
200u32 => Ok(Self::GIMBAL_REPORT(GIMBAL_REPORT_DATA::default())),
11u32 => Ok(Self::SET_MODE(SET_MODE_DATA::default())),
276u32 => Ok(Self::CAMERA_TRACKING_GEO_STATUS(
CAMERA_TRACKING_GEO_STATUS_DATA::default(),
)),
324u32 => Ok(Self::PARAM_EXT_ACK(PARAM_EXT_ACK_DATA::default())),
11003u32 => Ok(Self::DEVICE_OP_WRITE_REPLY(
DEVICE_OP_WRITE_REPLY_DATA::default(),
)),
174u32 => Ok(Self::AIRSPEED_AUTOCAL(AIRSPEED_AUTOCAL_DATA::default())),
375u32 => Ok(Self::ACTUATOR_OUTPUT_STATUS(
ACTUATOR_OUTPUT_STATUS_DATA::default(),
)),
120u32 => Ok(Self::LOG_DATA(LOG_DATA_DATA::default())),
89u32 => Ok(Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(
LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::default(),
)),
215u32 => Ok(Self::GOPRO_HEARTBEAT(GOPRO_HEARTBEAT_DATA::default())),
259u32 => Ok(Self::CAMERA_INFORMATION(CAMERA_INFORMATION_DATA::default())),
11034u32 => Ok(Self::OSD_PARAM_CONFIG_REPLY(
OSD_PARAM_CONFIG_REPLY_DATA::default(),
)),
24u32 => Ok(Self::GPS_RAW_INT(GPS_RAW_INT_DATA::default())),
108u32 => Ok(Self::SIM_STATE(SIM_STATE_DATA::default())),
77u32 => Ok(Self::COMMAND_ACK(COMMAND_ACK_DATA::default())),
143u32 => Ok(Self::SCALED_PRESSURE3(SCALED_PRESSURE3_DATA::default())),
12915u32 => Ok(Self::OPEN_DRONE_ID_MESSAGE_PACK(
OPEN_DRONE_ID_MESSAGE_PACK_DATA::default(),
)),
339u32 => Ok(Self::RAW_RPM(RAW_RPM_DATA::default())),
128u32 => Ok(Self::GPS2_RTK(GPS2_RTK_DATA::default())),
134u32 => Ok(Self::TERRAIN_DATA(TERRAIN_DATA_DATA::default())),
41u32 => Ok(Self::MISSION_SET_CURRENT(
MISSION_SET_CURRENT_DATA::default(),
)),
140u32 => Ok(Self::ACTUATOR_CONTROL_TARGET(
ACTUATOR_CONTROL_TARGET_DATA::default(),
)),
157u32 => Ok(Self::MOUNT_CONTROL(MOUNT_CONTROL_DATA::default())),
132u32 => Ok(Self::DISTANCE_SENSOR(DISTANCE_SENSOR_DATA::default())),
380u32 => Ok(Self::TIME_ESTIMATE_TO_TARGET(
TIME_ESTIMATE_TO_TARGET_DATA::default(),
)),
334u32 => Ok(Self::CELLULAR_STATUS(CELLULAR_STATUS_DATA::default())),
285u32 => Ok(Self::GIMBAL_DEVICE_ATTITUDE_STATUS(
GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::default(),
)),
63u32 => Ok(Self::GLOBAL_POSITION_INT_COV(
GLOBAL_POSITION_INT_COV_DATA::default(),
)),
34u32 => Ok(Self::RC_CHANNELS_SCALED(RC_CHANNELS_SCALED_DATA::default())),
256u32 => Ok(Self::SETUP_SIGNING(SETUP_SIGNING_DATA::default())),
262u32 => Ok(Self::CAMERA_CAPTURE_STATUS(
CAMERA_CAPTURE_STATUS_DATA::default(),
)),
184u32 => Ok(Self::REMOTE_LOG_DATA_BLOCK(
REMOTE_LOG_DATA_BLOCK_DATA::default(),
)),
258u32 => Ok(Self::PLAY_TUNE(PLAY_TUNE_DATA::default())),
178u32 => Ok(Self::AHRS2(AHRS2_DATA::default())),
115u32 => Ok(Self::HIL_STATE_QUATERNION(
HIL_STATE_QUATERNION_DATA::default(),
)),
28u32 => Ok(Self::RAW_PRESSURE(RAW_PRESSURE_DATA::default())),
9005u32 => Ok(Self::WINCH_STATUS(WINCH_STATUS_DATA::default())),
275u32 => Ok(Self::CAMERA_TRACKING_IMAGE_STATUS(
CAMERA_TRACKING_IMAGE_STATUS_DATA::default(),
)),
20u32 => Ok(Self::PARAM_REQUEST_READ(PARAM_REQUEST_READ_DATA::default())),
44u32 => Ok(Self::MISSION_COUNT(MISSION_COUNT_DATA::default())),
226u32 => Ok(Self::RPM(RPM_DATA::default())),
11032u32 => Ok(Self::ESC_TELEMETRY_9_TO_12(
ESC_TELEMETRY_9_TO_12_DATA::default(),
)),
9000u32 => Ok(Self::WHEEL_DISTANCE(WHEEL_DISTANCE_DATA::default())),
254u32 => Ok(Self::DEBUG(DEBUG_DATA::default())),
107u32 => Ok(Self::HIL_SENSOR(HIL_SENSOR_DATA::default())),
80u32 => Ok(Self::COMMAND_CANCEL(COMMAND_CANCEL_DATA::default())),
162u32 => Ok(Self::FENCE_STATUS(FENCE_STATUS_DATA::default())),
330u32 => Ok(Self::OBSTACLE_DISTANCE(OBSTACLE_DISTANCE_DATA::default())),
152u32 => Ok(Self::MEMINFO(MEMINFO_DATA::default())),
194u32 => Ok(Self::PID_TUNING(PID_TUNING_DATA::default())),
10001u32 => Ok(Self::UAVIONIX_ADSB_OUT_CFG(
UAVIONIX_ADSB_OUT_CFG_DATA::default(),
)),
397u32 => Ok(Self::COMPONENT_METADATA(COMPONENT_METADATA_DATA::default())),
11036u32 => Ok(Self::OSD_PARAM_SHOW_CONFIG_REPLY(
OSD_PARAM_SHOW_CONFIG_REPLY_DATA::default(),
)),
320u32 => Ok(Self::PARAM_EXT_REQUEST_READ(
PARAM_EXT_REQUEST_READ_DATA::default(),
)),
335u32 => Ok(Self::ISBD_LINK_STATUS(ISBD_LINK_STATUS_DATA::default())),
331u32 => Ok(Self::ODOMETRY(ODOMETRY_DATA::default())),
113u32 => Ok(Self::HIL_GPS(HIL_GPS_DATA::default())),
64u32 => Ok(Self::LOCAL_POSITION_NED_COV(
LOCAL_POSITION_NED_COV_DATA::default(),
)),
264u32 => Ok(Self::FLIGHT_INFORMATION(FLIGHT_INFORMATION_DATA::default())),
117u32 => Ok(Self::LOG_REQUEST_LIST(LOG_REQUEST_LIST_DATA::default())),
36u32 => Ok(Self::SERVO_OUTPUT_RAW(SERVO_OUTPUT_RAW_DATA::default())),
51u32 => Ok(Self::MISSION_REQUEST_INT(
MISSION_REQUEST_INT_DATA::default(),
)),
83u32 => Ok(Self::ATTITUDE_TARGET(ATTITUDE_TARGET_DATA::default())),
125u32 => Ok(Self::POWER_STATUS(POWER_STATUS_DATA::default())),
146u32 => Ok(Self::CONTROL_SYSTEM_STATE(
CONTROL_SYSTEM_STATE_DATA::default(),
)),
11030u32 => Ok(Self::ESC_TELEMETRY_1_TO_4(
ESC_TELEMETRY_1_TO_4_DATA::default(),
)),
73u32 => Ok(Self::MISSION_ITEM_INT(MISSION_ITEM_INT_DATA::default())),
253u32 => Ok(Self::STATUSTEXT(STATUSTEXT_DATA::default())),
12905u32 => Ok(Self::OPEN_DRONE_ID_OPERATOR_ID(
OPEN_DRONE_ID_OPERATOR_ID_DATA::default(),
)),
2u32 => Ok(Self::SYSTEM_TIME(SYSTEM_TIME_DATA::default())),
70u32 => Ok(Self::RC_CHANNELS_OVERRIDE(
RC_CHANNELS_OVERRIDE_DATA::default(),
)),
11038u32 => Ok(Self::WATER_DEPTH(WATER_DEPTH_DATA::default())),
21u32 => Ok(Self::PARAM_REQUEST_LIST(PARAM_REQUEST_LIST_DATA::default())),
61u32 => Ok(Self::ATTITUDE_QUATERNION_COV(
ATTITUDE_QUATERNION_COV_DATA::default(),
)),
131u32 => Ok(Self::ENCAPSULATED_DATA(ENCAPSULATED_DATA_DATA::default())),
22u32 => Ok(Self::PARAM_VALUE(PARAM_VALUE_DATA::default())),
6u32 => Ok(Self::CHANGE_OPERATOR_CONTROL_ACK(
CHANGE_OPERATOR_CONTROL_ACK_DATA::default(),
)),
4u32 => Ok(Self::PING(PING_DATA::default())),
48u32 => Ok(Self::SET_GPS_GLOBAL_ORIGIN(
SET_GPS_GLOBAL_ORIGIN_DATA::default(),
)),
195u32 => Ok(Self::DEEPSTALL(DEEPSTALL_DATA::default())),
218u32 => Ok(Self::GOPRO_SET_REQUEST(GOPRO_SET_REQUEST_DATA::default())),
193u32 => Ok(Self::EKF_STATUS_REPORT(EKF_STATUS_REPORT_DATA::default())),
11033u32 => Ok(Self::OSD_PARAM_CONFIG(OSD_PARAM_CONFIG_DATA::default())),
321u32 => Ok(Self::PARAM_EXT_REQUEST_LIST(
PARAM_EXT_REQUEST_LIST_DATA::default(),
)),
62u32 => Ok(Self::NAV_CONTROLLER_OUTPUT(
NAV_CONTROLLER_OUTPUT_DATA::default(),
)),
10002u32 => Ok(Self::UAVIONIX_ADSB_OUT_DYNAMIC(
UAVIONIX_ADSB_OUT_DYNAMIC_DATA::default(),
)),
116u32 => Ok(Self::SCALED_IMU2(SCALED_IMU2_DATA::default())),
160u32 => Ok(Self::FENCE_POINT(FENCE_POINT_DATA::default())),
139u32 => Ok(Self::SET_ACTUATOR_CONTROL_TARGET(
SET_ACTUATOR_CONTROL_TARGET_DATA::default(),
)),
11020u32 => Ok(Self::AOA_SSA(AOA_SSA_DATA::default())),
106u32 => Ok(Self::OPTICAL_FLOW_RAD(OPTICAL_FLOW_RAD_DATA::default())),
104u32 => Ok(Self::VICON_POSITION_ESTIMATE(
VICON_POSITION_ESTIMATE_DATA::default(),
)),
241u32 => Ok(Self::VIBRATION(VIBRATION_DATA::default())),
149u32 => Ok(Self::LANDING_TARGET(LANDING_TARGET_DATA::default())),
42u32 => Ok(Self::MISSION_CURRENT(MISSION_CURRENT_DATA::default())),
171u32 => Ok(Self::DATA64(DATA64_DATA::default())),
111u32 => Ok(Self::TIMESYNC(TIMESYNC_DATA::default())),
251u32 => Ok(Self::NAMED_VALUE_FLOAT(NAMED_VALUE_FLOAT_DATA::default())),
141u32 => Ok(Self::ALTITUDE(ALTITUDE_DATA::default())),
114u32 => Ok(Self::HIL_OPTICAL_FLOW(HIL_OPTICAL_FLOW_DATA::default())),
247u32 => Ok(Self::COLLISION(COLLISION_DATA::default())),
412u32 => Ok(Self::REQUEST_EVENT(REQUEST_EVENT_DATA::default())),
180u32 => Ok(Self::CAMERA_FEEDBACK(CAMERA_FEEDBACK_DATA::default())),
216u32 => Ok(Self::GOPRO_GET_REQUEST(GOPRO_GET_REQUEST_DATA::default())),
142u32 => Ok(Self::RESOURCE_REQUEST(RESOURCE_REQUEST_DATA::default())),
248u32 => Ok(Self::V2_EXTENSION(V2_EXTENSION_DATA::default())),
300u32 => Ok(Self::PROTOCOL_VERSION(PROTOCOL_VERSION_DATA::default())),
50u32 => Ok(Self::PARAM_MAP_RC(PARAM_MAP_RC_DATA::default())),
333u32 => Ok(Self::TRAJECTORY_REPRESENTATION_BEZIER(
TRAJECTORY_REPRESENTATION_BEZIER_DATA::default(),
)),
23u32 => Ok(Self::PARAM_SET(PARAM_SET_DATA::default())),
42000u32 => Ok(Self::ICAROUS_HEARTBEAT(ICAROUS_HEARTBEAT_DATA::default())),
182u32 => Ok(Self::AHRS3(AHRS3_DATA::default())),
385u32 => Ok(Self::TUNNEL(TUNNEL_DATA::default())),
11039u32 => Ok(Self::MCU_STATUS(MCU_STATUS_DATA::default())),
410u32 => Ok(Self::EVENT(EVENT_DATA::default())),
126u32 => Ok(Self::SERIAL_CONTROL(SERIAL_CONTROL_DATA::default())),
7u32 => Ok(Self::AUTH_KEY(AUTH_KEY_DATA::default())),
246u32 => Ok(Self::ADSB_VEHICLE(ADSB_VEHICLE_DATA::default())),
84u32 => Ok(Self::SET_POSITION_TARGET_LOCAL_NED(
SET_POSITION_TARGET_LOCAL_NED_DATA::default(),
)),
232u32 => Ok(Self::GPS_INPUT(GPS_INPUT_DATA::default())),
244u32 => Ok(Self::MESSAGE_INTERVAL(MESSAGE_INTERVAL_DATA::default())),
267u32 => Ok(Self::LOGGING_DATA_ACKED(LOGGING_DATA_ACKED_DATA::default())),
50002u32 => Ok(Self::HERELINK_VIDEO_STREAM_INFORMATION(
HERELINK_VIDEO_STREAM_INFORMATION_DATA::default(),
)),
151u32 => Ok(Self::SET_MAG_OFFSETS(SET_MAG_OFFSETS_DATA::default())),
130u32 => Ok(Self::DATA_TRANSMISSION_HANDSHAKE(
DATA_TRANSMISSION_HANDSHAKE_DATA::default(),
)),
91u32 => Ok(Self::HIL_CONTROLS(HIL_CONTROLS_DATA::default())),
173u32 => Ok(Self::RANGEFINDER(RANGEFINDER_DATA::default())),
10003u32 => Ok(Self::UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT(
UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::default(),
)),
268u32 => Ok(Self::LOGGING_ACK(LOGGING_ACK_DATA::default())),
55u32 => Ok(Self::SAFETY_ALLOWED_AREA(
SAFETY_ALLOWED_AREA_DATA::default(),
)),
387u32 => Ok(Self::CANFD_FRAME(CANFD_FRAME_DATA::default())),
43u32 => Ok(Self::MISSION_REQUEST_LIST(
MISSION_REQUEST_LIST_DATA::default(),
)),
86u32 => Ok(Self::SET_POSITION_TARGET_GLOBAL_INT(
SET_POSITION_TARGET_GLOBAL_INT_DATA::default(),
)),
263u32 => Ok(Self::CAMERA_IMAGE_CAPTURED(
CAMERA_IMAGE_CAPTURED_DATA::default(),
)),
75u32 => Ok(Self::COMMAND_INT(COMMAND_INT_DATA::default())),
170u32 => Ok(Self::DATA32(DATA32_DATA::default())),
33u32 => Ok(Self::GLOBAL_POSITION_INT(
GLOBAL_POSITION_INT_DATA::default(),
)),
92u32 => Ok(Self::HIL_RC_INPUTS_RAW(HIL_RC_INPUTS_RAW_DATA::default())),
12918u32 => Ok(Self::OPEN_DRONE_ID_ARM_STATUS(
OPEN_DRONE_ID_ARM_STATUS_DATA::default(),
)),
287u32 => Ok(Self::GIMBAL_MANAGER_SET_PITCHYAW(
GIMBAL_MANAGER_SET_PITCHYAW_DATA::default(),
)),
166u32 => Ok(Self::RADIO(RADIO_DATA::default())),
49u32 => Ok(Self::GPS_GLOBAL_ORIGIN(GPS_GLOBAL_ORIGIN_DATA::default())),
37u32 => Ok(Self::MISSION_REQUEST_PARTIAL_LIST(
MISSION_REQUEST_PARTIAL_LIST_DATA::default(),
)),
122u32 => Ok(Self::LOG_REQUEST_END(LOG_REQUEST_END_DATA::default())),
119u32 => Ok(Self::LOG_REQUEST_DATA(LOG_REQUEST_DATA_DATA::default())),
54u32 => Ok(Self::SAFETY_SET_ALLOWED_AREA(
SAFETY_SET_ALLOWED_AREA_DATA::default(),
)),
401u32 => Ok(Self::SUPPORTED_TUNES(SUPPORTED_TUNES_DATA::default())),
245u32 => Ok(Self::EXTENDED_SYS_STATE(EXTENDED_SYS_STATE_DATA::default())),
11002u32 => Ok(Self::DEVICE_OP_WRITE(DEVICE_OP_WRITE_DATA::default())),
373u32 => Ok(Self::GENERATOR_STATUS(GENERATOR_STATUS_DATA::default())),
31u32 => Ok(Self::ATTITUDE_QUATERNION(
ATTITUDE_QUATERNION_DATA::default(),
)),
163u32 => Ok(Self::AHRS(AHRS_DATA::default())),
136u32 => Ok(Self::TERRAIN_REPORT(TERRAIN_REPORT_DATA::default())),
12902u32 => Ok(Self::OPEN_DRONE_ID_AUTHENTICATION(
OPEN_DRONE_ID_AUTHENTICATION_DATA::default(),
)),
413u32 => Ok(Self::RESPONSE_EVENT_ERROR(
RESPONSE_EVENT_ERROR_DATA::default(),
)),
129u32 => Ok(Self::SCALED_IMU3(SCALED_IMU3_DATA::default())),
87u32 => Ok(Self::POSITION_TARGET_GLOBAL_INT(
POSITION_TARGET_GLOBAL_INT_DATA::default(),
)),
25u32 => Ok(Self::GPS_STATUS(GPS_STATUS_DATA::default())),
310u32 => Ok(Self::UAVCAN_NODE_STATUS(UAVCAN_NODE_STATUS_DATA::default())),
192u32 => Ok(Self::MAG_CAL_REPORT(MAG_CAL_REPORT_DATA::default())),
137u32 => Ok(Self::SCALED_PRESSURE2(SCALED_PRESSURE2_DATA::default())),
386u32 => Ok(Self::CAN_FRAME(CAN_FRAME_DATA::default())),
100u32 => Ok(Self::OPTICAL_FLOW(OPTICAL_FLOW_DATA::default())),
281u32 => Ok(Self::GIMBAL_MANAGER_STATUS(
GIMBAL_MANAGER_STATUS_DATA::default(),
)),
135u32 => Ok(Self::TERRAIN_CHECK(TERRAIN_CHECK_DATA::default())),
269u32 => Ok(Self::VIDEO_STREAM_INFORMATION(
VIDEO_STREAM_INFORMATION_DATA::default(),
)),
158u32 => Ok(Self::MOUNT_STATUS(MOUNT_STATUS_DATA::default())),
82u32 => Ok(Self::SET_ATTITUDE_TARGET(
SET_ATTITUDE_TARGET_DATA::default(),
)),
282u32 => Ok(Self::GIMBAL_MANAGER_SET_ATTITUDE(
GIMBAL_MANAGER_SET_ATTITUDE_DATA::default(),
)),
284u32 => Ok(Self::GIMBAL_DEVICE_SET_ATTITUDE(
GIMBAL_DEVICE_SET_ATTITUDE_DATA::default(),
)),
105u32 => Ok(Self::HIGHRES_IMU(HIGHRES_IMU_DATA::default())),
288u32 => Ok(Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(
GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::default(),
)),
112u32 => Ok(Self::CAMERA_TRIGGER(CAMERA_TRIGGER_DATA::default())),
181u32 => Ok(Self::BATTERY2(BATTERY2_DATA::default())),
185u32 => Ok(Self::REMOTE_LOG_BLOCK_STATUS(
REMOTE_LOG_BLOCK_STATUS_DATA::default(),
)),
164u32 => Ok(Self::SIMSTATE(SIMSTATE_DATA::default())),
165u32 => Ok(Self::HWSTATUS(HWSTATUS_DATA::default())),
167u32 => Ok(Self::LIMITS_STATUS(LIMITS_STATUS_DATA::default())),
235u32 => Ok(Self::HIGH_LATENCY2(HIGH_LATENCY2_DATA::default())),
261u32 => Ok(Self::STORAGE_INFORMATION(
STORAGE_INFORMATION_DATA::default(),
)),
148u32 => Ok(Self::AUTOPILOT_VERSION(AUTOPILOT_VERSION_DATA::default())),
47u32 => Ok(Self::MISSION_ACK(MISSION_ACK_DATA::default())),
161u32 => Ok(Self::FENCE_FETCH_POINT(FENCE_FETCH_POINT_DATA::default())),
156u32 => Ok(Self::MOUNT_CONFIGURE(MOUNT_CONFIGURE_DATA::default())),
332u32 => Ok(Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(
TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::default(),
)),
5u32 => Ok(Self::CHANGE_OPERATOR_CONTROL(
CHANGE_OPERATOR_CONTROL_DATA::default(),
)),
395u32 => Ok(Self::COMPONENT_INFORMATION(
COMPONENT_INFORMATION_DATA::default(),
)),
1u32 => Ok(Self::SYS_STATUS(SYS_STATUS_DATA::default())),
11010u32 => Ok(Self::ADAP_TUNING(ADAP_TUNING_DATA::default())),
101u32 => Ok(Self::GLOBAL_VISION_POSITION_ESTIMATE(
GLOBAL_VISION_POSITION_ESTIMATE_DATA::default(),
)),
154u32 => Ok(Self::DIGICAM_CONFIGURE(DIGICAM_CONFIGURE_DATA::default())),
133u32 => Ok(Self::TERRAIN_REQUEST(TERRAIN_REQUEST_DATA::default())),
172u32 => Ok(Self::DATA96(DATA96_DATA::default())),
11035u32 => Ok(Self::OSD_PARAM_SHOW_CONFIG(
OSD_PARAM_SHOW_CONFIG_DATA::default(),
)),
109u32 => Ok(Self::RADIO_STATUS(RADIO_STATUS_DATA::default())),
27u32 => Ok(Self::RAW_IMU(RAW_IMU_DATA::default())),
39u32 => Ok(Self::MISSION_ITEM(MISSION_ITEM_DATA::default())),
66u32 => Ok(Self::REQUEST_DATA_STREAM(
REQUEST_DATA_STREAM_DATA::default(),
)),
270u32 => Ok(Self::VIDEO_STREAM_STATUS(
VIDEO_STREAM_STATUS_DATA::default(),
)),
121u32 => Ok(Self::LOG_ERASE(LOG_ERASE_DATA::default())),
69u32 => Ok(Self::MANUAL_CONTROL(MANUAL_CONTROL_DATA::default())),
76u32 => Ok(Self::COMMAND_LONG(COMMAND_LONG_DATA::default())),
81u32 => Ok(Self::MANUAL_SETPOINT(MANUAL_SETPOINT_DATA::default())),
12919u32 => Ok(Self::OPEN_DRONE_ID_SYSTEM_UPDATE(
OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::default(),
)),
12904u32 => Ok(Self::OPEN_DRONE_ID_SYSTEM(
OPEN_DRONE_ID_SYSTEM_DATA::default(),
)),
8u32 => Ok(Self::LINK_NODE_STATUS(LINK_NODE_STATUS_DATA::default())),
12903u32 => Ok(Self::OPEN_DRONE_ID_SELF_ID(
OPEN_DRONE_ID_SELF_ID_DATA::default(),
)),
102u32 => Ok(Self::VISION_POSITION_ESTIMATE(
VISION_POSITION_ESTIMATE_DATA::default(),
)),
11001u32 => Ok(Self::DEVICE_OP_READ_REPLY(
DEVICE_OP_READ_REPLY_DATA::default(),
)),
12920u32 => Ok(Self::HYGROMETER_SENSOR(HYGROMETER_SENSOR_DATA::default())),
138u32 => Ok(Self::ATT_POS_MOCAP(ATT_POS_MOCAP_DATA::default())),
65u32 => Ok(Self::RC_CHANNELS(RC_CHANNELS_DATA::default())),
144u32 => Ok(Self::FOLLOW_TARGET(FOLLOW_TARGET_DATA::default())),
90u32 => Ok(Self::HIL_STATE(HIL_STATE_DATA::default())),
242u32 => Ok(Self::HOME_POSITION(HOME_POSITION_DATA::default())),
12901u32 => Ok(Self::OPEN_DRONE_ID_LOCATION(
OPEN_DRONE_ID_LOCATION_DATA::default(),
)),
67u32 => Ok(Self::DATA_STREAM(DATA_STREAM_DATA::default())),
45u32 => Ok(Self::MISSION_CLEAR_ALL(MISSION_CLEAR_ALL_DATA::default())),
280u32 => Ok(Self::GIMBAL_MANAGER_INFORMATION(
GIMBAL_MANAGER_INFORMATION_DATA::default(),
)),
103u32 => Ok(Self::VISION_SPEED_ESTIMATE(
VISION_SPEED_ESTIMATE_DATA::default(),
)),
290u32 => Ok(Self::ESC_INFO(ESC_INFO_DATA::default())),
169u32 => Ok(Self::DATA16(DATA16_DATA::default())),
249u32 => Ok(Self::MEMORY_VECT(MEMORY_VECT_DATA::default())),
191u32 => Ok(Self::MAG_CAL_PROGRESS(MAG_CAL_PROGRESS_DATA::default())),
46u32 => Ok(Self::MISSION_ITEM_REACHED(
MISSION_ITEM_REACHED_DATA::default(),
)),
265u32 => Ok(Self::MOUNT_ORIENTATION(MOUNT_ORIENTATION_DATA::default())),
11000u32 => Ok(Self::DEVICE_OP_READ(DEVICE_OP_READ_DATA::default())),
74u32 => Ok(Self::VFR_HUD(VFR_HUD_DATA::default())),
411u32 => Ok(Self::CURRENT_EVENT_SEQUENCE(
CURRENT_EVENT_SEQUENCE_DATA::default(),
)),
30u32 => Ok(Self::ATTITUDE(ATTITUDE_DATA::default())),
29u32 => Ok(Self::SCALED_PRESSURE(SCALED_PRESSURE_DATA::default())),
150u32 => Ok(Self::SENSOR_OFFSETS(SENSOR_OFFSETS_DATA::default())),
11011u32 => Ok(Self::VISION_POSITION_DELTA(
VISION_POSITION_DELTA_DATA::default(),
)),
266u32 => Ok(Self::LOGGING_DATA(LOGGING_DATA_DATA::default())),
233u32 => Ok(Self::GPS_RTCM_DATA(GPS_RTCM_DATA_DATA::default())),
85u32 => Ok(Self::POSITION_TARGET_LOCAL_NED(
POSITION_TARGET_LOCAL_NED_DATA::default(),
)),
40u32 => Ok(Self::MISSION_REQUEST(MISSION_REQUEST_DATA::default())),
271u32 => Ok(Self::CAMERA_FOV_STATUS(CAMERA_FOV_STATUS_DATA::default())),
0u32 => Ok(Self::HEARTBEAT(HEARTBEAT_DATA::default())),
155u32 => Ok(Self::DIGICAM_CONTROL(DIGICAM_CONTROL_DATA::default())),
340u32 => Ok(Self::UTM_GLOBAL_POSITION(
UTM_GLOBAL_POSITION_DATA::default(),
)),
176u32 => Ok(Self::RALLY_FETCH_POINT(RALLY_FETCH_POINT_DATA::default())),
11037u32 => Ok(Self::OBSTACLE_DISTANCE_3D(
OBSTACLE_DISTANCE_3D_DATA::default(),
)),
175u32 => Ok(Self::RALLY_POINT(RALLY_POINT_DATA::default())),
35u32 => Ok(Self::RC_CHANNELS_RAW(RC_CHANNELS_RAW_DATA::default())),
183u32 => Ok(Self::AUTOPILOT_VERSION_REQUEST(
AUTOPILOT_VERSION_REQUEST_DATA::default(),
)),
231u32 => Ok(Self::WIND_COV(WIND_COV_DATA::default())),
93u32 => Ok(Self::HIL_ACTUATOR_CONTROLS(
HIL_ACTUATOR_CONTROLS_DATA::default(),
)),
260u32 => Ok(Self::CAMERA_SETTINGS(CAMERA_SETTINGS_DATA::default())),
390u32 => Ok(Self::ONBOARD_COMPUTER_STATUS(
ONBOARD_COMPUTER_STATUS_DATA::default(),
)),
110u32 => Ok(Self::FILE_TRANSFER_PROTOCOL(
FILE_TRANSFER_PROTOCOL_DATA::default(),
)),
127u32 => Ok(Self::GPS_RTK(GPS_RTK_DATA::default())),
283u32 => Ok(Self::GIMBAL_DEVICE_INFORMATION(
GIMBAL_DEVICE_INFORMATION_DATA::default(),
)),
118u32 => Ok(Self::LOG_ENTRY(LOG_ENTRY_DATA::default())),
291u32 => Ok(Self::ESC_STATUS(ESC_STATUS_DATA::default())),
50003u32 => Ok(Self::HERELINK_TELEM(HERELINK_TELEM_DATA::default())),
214u32 => Ok(Self::GIMBAL_TORQUE_CMD_REPORT(
GIMBAL_TORQUE_CMD_REPORT_DATA::default(),
)),
234u32 => Ok(Self::HIGH_LATENCY(HIGH_LATENCY_DATA::default())),
11031u32 => Ok(Self::ESC_TELEMETRY_5_TO_8(
ESC_TELEMETRY_5_TO_8_DATA::default(),
)),
400u32 => Ok(Self::PLAY_TUNE_V2(PLAY_TUNE_V2_DATA::default())),
243u32 => Ok(Self::SET_HOME_POSITION(SET_HOME_POSITION_DATA::default())),
147u32 => Ok(Self::BATTERY_STATUS(BATTERY_STATUS_DATA::default())),
12900u32 => Ok(Self::OPEN_DRONE_ID_BASIC_ID(
OPEN_DRONE_ID_BASIC_ID_DATA::default(),
)),
323u32 => Ok(Self::PARAM_EXT_SET(PARAM_EXT_SET_DATA::default())),
322u32 => Ok(Self::PARAM_EXT_VALUE(PARAM_EXT_VALUE_DATA::default())),
360u32 => Ok(Self::ORBIT_EXECUTION_STATUS(
ORBIT_EXECUTION_STATUS_DATA::default(),
)),
252u32 => Ok(Self::NAMED_VALUE_INT(NAMED_VALUE_INT_DATA::default())),
186u32 => Ok(Self::LED_CONTROL(LED_CONTROL_DATA::default())),
370u32 => Ok(Self::SMART_BATTERY_INFO(SMART_BATTERY_INFO_DATA::default())),
_ => Err("Invalid message id."),
}
}
fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
match self {
Self::MISSION_WRITE_PARTIAL_LIST(body) => body.ser(version, bytes),
Self::CUBEPILOT_FIRMWARE_UPDATE_START(body) => body.ser(version, bytes),
Self::DEBUG_VECT(body) => body.ser(version, bytes),
Self::GIMBAL_CONTROL(body) => body.ser(version, bytes),
Self::COMPASSMOT_STATUS(body) => body.ser(version, bytes),
Self::BUTTON_CHANGE(body) => body.ser(version, bytes),
Self::GPS_INJECT_DATA(body) => body.ser(version, bytes),
Self::CAMERA_STATUS(body) => body.ser(version, bytes),
Self::GOPRO_GET_RESPONSE(body) => body.ser(version, bytes),
Self::CUBEPILOT_RAW_RC(body) => body.ser(version, bytes),
Self::CELLULAR_CONFIG(body) => body.ser(version, bytes),
Self::GPS2_RAW(body) => body.ser(version, bytes),
Self::ESTIMATOR_STATUS(body) => body.ser(version, bytes),
Self::UAVCAN_NODE_INFO(body) => body.ser(version, bytes),
Self::AIS_VESSEL(body) => body.ser(version, bytes),
Self::ICAROUS_KINEMATIC_BANDS(body) => body.ser(version, bytes),
Self::EFI_STATUS(body) => body.ser(version, bytes),
Self::CAN_FILTER_MODIFY(body) => body.ser(version, bytes),
Self::CUBEPILOT_FIRMWARE_UPDATE_RESP(body) => body.ser(version, bytes),
Self::DEBUG_FLOAT_ARRAY(body) => body.ser(version, bytes),
Self::WIFI_CONFIG_AP(body) => body.ser(version, bytes),
Self::AP_ADC(body) => body.ser(version, bytes),
Self::WIND(body) => body.ser(version, bytes),
Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(body) => body.ser(version, bytes),
Self::SCALED_IMU(body) => body.ser(version, bytes),
Self::LOCAL_POSITION_NED(body) => body.ser(version, bytes),
Self::GOPRO_SET_RESPONSE(body) => body.ser(version, bytes),
Self::GIMBAL_REPORT(body) => body.ser(version, bytes),
Self::SET_MODE(body) => body.ser(version, bytes),
Self::CAMERA_TRACKING_GEO_STATUS(body) => body.ser(version, bytes),
Self::PARAM_EXT_ACK(body) => body.ser(version, bytes),
Self::DEVICE_OP_WRITE_REPLY(body) => body.ser(version, bytes),
Self::AIRSPEED_AUTOCAL(body) => body.ser(version, bytes),
Self::ACTUATOR_OUTPUT_STATUS(body) => body.ser(version, bytes),
Self::LOG_DATA(body) => body.ser(version, bytes),
Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(body) => body.ser(version, bytes),
Self::GOPRO_HEARTBEAT(body) => body.ser(version, bytes),
Self::CAMERA_INFORMATION(body) => body.ser(version, bytes),
Self::OSD_PARAM_CONFIG_REPLY(body) => body.ser(version, bytes),
Self::GPS_RAW_INT(body) => body.ser(version, bytes),
Self::SIM_STATE(body) => body.ser(version, bytes),
Self::COMMAND_ACK(body) => body.ser(version, bytes),
Self::SCALED_PRESSURE3(body) => body.ser(version, bytes),
Self::OPEN_DRONE_ID_MESSAGE_PACK(body) => body.ser(version, bytes),
Self::RAW_RPM(body) => body.ser(version, bytes),
Self::GPS2_RTK(body) => body.ser(version, bytes),
Self::TERRAIN_DATA(body) => body.ser(version, bytes),
Self::MISSION_SET_CURRENT(body) => body.ser(version, bytes),
Self::ACTUATOR_CONTROL_TARGET(body) => body.ser(version, bytes),
Self::MOUNT_CONTROL(body) => body.ser(version, bytes),
Self::DISTANCE_SENSOR(body) => body.ser(version, bytes),
Self::TIME_ESTIMATE_TO_TARGET(body) => body.ser(version, bytes),
Self::CELLULAR_STATUS(body) => body.ser(version, bytes),
Self::GIMBAL_DEVICE_ATTITUDE_STATUS(body) => body.ser(version, bytes),
Self::GLOBAL_POSITION_INT_COV(body) => body.ser(version, bytes),
Self::RC_CHANNELS_SCALED(body) => body.ser(version, bytes),
Self::SETUP_SIGNING(body) => body.ser(version, bytes),
Self::CAMERA_CAPTURE_STATUS(body) => body.ser(version, bytes),
Self::REMOTE_LOG_DATA_BLOCK(body) => body.ser(version, bytes),
Self::PLAY_TUNE(body) => body.ser(version, bytes),
Self::AHRS2(body) => body.ser(version, bytes),
Self::HIL_STATE_QUATERNION(body) => body.ser(version, bytes),
Self::RAW_PRESSURE(body) => body.ser(version, bytes),
Self::WINCH_STATUS(body) => body.ser(version, bytes),
Self::CAMERA_TRACKING_IMAGE_STATUS(body) => body.ser(version, bytes),
Self::PARAM_REQUEST_READ(body) => body.ser(version, bytes),
Self::MISSION_COUNT(body) => body.ser(version, bytes),
Self::RPM(body) => body.ser(version, bytes),
Self::ESC_TELEMETRY_9_TO_12(body) => body.ser(version, bytes),
Self::WHEEL_DISTANCE(body) => body.ser(version, bytes),
Self::DEBUG(body) => body.ser(version, bytes),
Self::HIL_SENSOR(body) => body.ser(version, bytes),
Self::COMMAND_CANCEL(body) => body.ser(version, bytes),
Self::FENCE_STATUS(body) => body.ser(version, bytes),
Self::OBSTACLE_DISTANCE(body) => body.ser(version, bytes),
Self::MEMINFO(body) => body.ser(version, bytes),
Self::PID_TUNING(body) => body.ser(version, bytes),
Self::UAVIONIX_ADSB_OUT_CFG(body) => body.ser(version, bytes),
Self::COMPONENT_METADATA(body) => body.ser(version, bytes),
Self::OSD_PARAM_SHOW_CONFIG_REPLY(body) => body.ser(version, bytes),
Self::PARAM_EXT_REQUEST_READ(body) => body.ser(version, bytes),
Self::ISBD_LINK_STATUS(body) => body.ser(version, bytes),
Self::ODOMETRY(body) => body.ser(version, bytes),
Self::HIL_GPS(body) => body.ser(version, bytes),
Self::LOCAL_POSITION_NED_COV(body) => body.ser(version, bytes),
Self::FLIGHT_INFORMATION(body) => body.ser(version, bytes),
Self::LOG_REQUEST_LIST(body) => body.ser(version, bytes),
Self::SERVO_OUTPUT_RAW(body) => body.ser(version, bytes),
Self::MISSION_REQUEST_INT(body) => body.ser(version, bytes),
Self::ATTITUDE_TARGET(body) => body.ser(version, bytes),
Self::POWER_STATUS(body) => body.ser(version, bytes),
Self::CONTROL_SYSTEM_STATE(body) => body.ser(version, bytes),
Self::ESC_TELEMETRY_1_TO_4(body) => body.ser(version, bytes),
Self::MISSION_ITEM_INT(body) => body.ser(version, bytes),
Self::STATUSTEXT(body) => body.ser(version, bytes),
Self::OPEN_DRONE_ID_OPERATOR_ID(body) => body.ser(version, bytes),
Self::SYSTEM_TIME(body) => body.ser(version, bytes),
Self::RC_CHANNELS_OVERRIDE(body) => body.ser(version, bytes),
Self::WATER_DEPTH(body) => body.ser(version, bytes),
Self::PARAM_REQUEST_LIST(body) => body.ser(version, bytes),
Self::ATTITUDE_QUATERNION_COV(body) => body.ser(version, bytes),
Self::ENCAPSULATED_DATA(body) => body.ser(version, bytes),
Self::PARAM_VALUE(body) => body.ser(version, bytes),
Self::CHANGE_OPERATOR_CONTROL_ACK(body) => body.ser(version, bytes),
Self::PING(body) => body.ser(version, bytes),
Self::SET_GPS_GLOBAL_ORIGIN(body) => body.ser(version, bytes),
Self::DEEPSTALL(body) => body.ser(version, bytes),
Self::GOPRO_SET_REQUEST(body) => body.ser(version, bytes),
Self::EKF_STATUS_REPORT(body) => body.ser(version, bytes),
Self::OSD_PARAM_CONFIG(body) => body.ser(version, bytes),
Self::PARAM_EXT_REQUEST_LIST(body) => body.ser(version, bytes),
Self::NAV_CONTROLLER_OUTPUT(body) => body.ser(version, bytes),
Self::UAVIONIX_ADSB_OUT_DYNAMIC(body) => body.ser(version, bytes),
Self::SCALED_IMU2(body) => body.ser(version, bytes),
Self::FENCE_POINT(body) => body.ser(version, bytes),
Self::SET_ACTUATOR_CONTROL_TARGET(body) => body.ser(version, bytes),
Self::AOA_SSA(body) => body.ser(version, bytes),
Self::OPTICAL_FLOW_RAD(body) => body.ser(version, bytes),
Self::VICON_POSITION_ESTIMATE(body) => body.ser(version, bytes),
Self::VIBRATION(body) => body.ser(version, bytes),
Self::LANDING_TARGET(body) => body.ser(version, bytes),
Self::MISSION_CURRENT(body) => body.ser(version, bytes),
Self::DATA64(body) => body.ser(version, bytes),
Self::TIMESYNC(body) => body.ser(version, bytes),
Self::NAMED_VALUE_FLOAT(body) => body.ser(version, bytes),
Self::ALTITUDE(body) => body.ser(version, bytes),
Self::HIL_OPTICAL_FLOW(body) => body.ser(version, bytes),
Self::COLLISION(body) => body.ser(version, bytes),
Self::REQUEST_EVENT(body) => body.ser(version, bytes),
Self::CAMERA_FEEDBACK(body) => body.ser(version, bytes),
Self::GOPRO_GET_REQUEST(body) => body.ser(version, bytes),
Self::RESOURCE_REQUEST(body) => body.ser(version, bytes),
Self::V2_EXTENSION(body) => body.ser(version, bytes),
Self::PROTOCOL_VERSION(body) => body.ser(version, bytes),
Self::PARAM_MAP_RC(body) => body.ser(version, bytes),
Self::TRAJECTORY_REPRESENTATION_BEZIER(body) => body.ser(version, bytes),
Self::PARAM_SET(body) => body.ser(version, bytes),
Self::ICAROUS_HEARTBEAT(body) => body.ser(version, bytes),
Self::AHRS3(body) => body.ser(version, bytes),
Self::TUNNEL(body) => body.ser(version, bytes),
Self::MCU_STATUS(body) => body.ser(version, bytes),
Self::EVENT(body) => body.ser(version, bytes),
Self::SERIAL_CONTROL(body) => body.ser(version, bytes),
Self::AUTH_KEY(body) => body.ser(version, bytes),
Self::ADSB_VEHICLE(body) => body.ser(version, bytes),
Self::SET_POSITION_TARGET_LOCAL_NED(body) => body.ser(version, bytes),
Self::GPS_INPUT(body) => body.ser(version, bytes),
Self::MESSAGE_INTERVAL(body) => body.ser(version, bytes),
Self::LOGGING_DATA_ACKED(body) => body.ser(version, bytes),
Self::HERELINK_VIDEO_STREAM_INFORMATION(body) => body.ser(version, bytes),
Self::SET_MAG_OFFSETS(body) => body.ser(version, bytes),
Self::DATA_TRANSMISSION_HANDSHAKE(body) => body.ser(version, bytes),
Self::HIL_CONTROLS(body) => body.ser(version, bytes),
Self::RANGEFINDER(body) => body.ser(version, bytes),
Self::UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT(body) => body.ser(version, bytes),
Self::LOGGING_ACK(body) => body.ser(version, bytes),
Self::SAFETY_ALLOWED_AREA(body) => body.ser(version, bytes),
Self::CANFD_FRAME(body) => body.ser(version, bytes),
Self::MISSION_REQUEST_LIST(body) => body.ser(version, bytes),
Self::SET_POSITION_TARGET_GLOBAL_INT(body) => body.ser(version, bytes),
Self::CAMERA_IMAGE_CAPTURED(body) => body.ser(version, bytes),
Self::COMMAND_INT(body) => body.ser(version, bytes),
Self::DATA32(body) => body.ser(version, bytes),
Self::GLOBAL_POSITION_INT(body) => body.ser(version, bytes),
Self::HIL_RC_INPUTS_RAW(body) => body.ser(version, bytes),
Self::OPEN_DRONE_ID_ARM_STATUS(body) => body.ser(version, bytes),
Self::GIMBAL_MANAGER_SET_PITCHYAW(body) => body.ser(version, bytes),
Self::RADIO(body) => body.ser(version, bytes),
Self::GPS_GLOBAL_ORIGIN(body) => body.ser(version, bytes),
Self::MISSION_REQUEST_PARTIAL_LIST(body) => body.ser(version, bytes),
Self::LOG_REQUEST_END(body) => body.ser(version, bytes),
Self::LOG_REQUEST_DATA(body) => body.ser(version, bytes),
Self::SAFETY_SET_ALLOWED_AREA(body) => body.ser(version, bytes),
Self::SUPPORTED_TUNES(body) => body.ser(version, bytes),
Self::EXTENDED_SYS_STATE(body) => body.ser(version, bytes),
Self::DEVICE_OP_WRITE(body) => body.ser(version, bytes),
Self::GENERATOR_STATUS(body) => body.ser(version, bytes),
Self::ATTITUDE_QUATERNION(body) => body.ser(version, bytes),
Self::AHRS(body) => body.ser(version, bytes),
Self::TERRAIN_REPORT(body) => body.ser(version, bytes),
Self::OPEN_DRONE_ID_AUTHENTICATION(body) => body.ser(version, bytes),
Self::RESPONSE_EVENT_ERROR(body) => body.ser(version, bytes),
Self::SCALED_IMU3(body) => body.ser(version, bytes),
Self::POSITION_TARGET_GLOBAL_INT(body) => body.ser(version, bytes),
Self::GPS_STATUS(body) => body.ser(version, bytes),
Self::UAVCAN_NODE_STATUS(body) => body.ser(version, bytes),
Self::MAG_CAL_REPORT(body) => body.ser(version, bytes),
Self::SCALED_PRESSURE2(body) => body.ser(version, bytes),
Self::CAN_FRAME(body) => body.ser(version, bytes),
Self::OPTICAL_FLOW(body) => body.ser(version, bytes),
Self::GIMBAL_MANAGER_STATUS(body) => body.ser(version, bytes),
Self::TERRAIN_CHECK(body) => body.ser(version, bytes),
Self::VIDEO_STREAM_INFORMATION(body) => body.ser(version, bytes),
Self::MOUNT_STATUS(body) => body.ser(version, bytes),
Self::SET_ATTITUDE_TARGET(body) => body.ser(version, bytes),
Self::GIMBAL_MANAGER_SET_ATTITUDE(body) => body.ser(version, bytes),
Self::GIMBAL_DEVICE_SET_ATTITUDE(body) => body.ser(version, bytes),
Self::HIGHRES_IMU(body) => body.ser(version, bytes),
Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(body) => body.ser(version, bytes),
Self::CAMERA_TRIGGER(body) => body.ser(version, bytes),
Self::BATTERY2(body) => body.ser(version, bytes),
Self::REMOTE_LOG_BLOCK_STATUS(body) => body.ser(version, bytes),
Self::SIMSTATE(body) => body.ser(version, bytes),
Self::HWSTATUS(body) => body.ser(version, bytes),
Self::LIMITS_STATUS(body) => body.ser(version, bytes),
Self::HIGH_LATENCY2(body) => body.ser(version, bytes),
Self::STORAGE_INFORMATION(body) => body.ser(version, bytes),
Self::AUTOPILOT_VERSION(body) => body.ser(version, bytes),
Self::MISSION_ACK(body) => body.ser(version, bytes),
Self::FENCE_FETCH_POINT(body) => body.ser(version, bytes),
Self::MOUNT_CONFIGURE(body) => body.ser(version, bytes),
Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(body) => body.ser(version, bytes),
Self::CHANGE_OPERATOR_CONTROL(body) => body.ser(version, bytes),
Self::COMPONENT_INFORMATION(body) => body.ser(version, bytes),
Self::SYS_STATUS(body) => body.ser(version, bytes),
Self::ADAP_TUNING(body) => body.ser(version, bytes),
Self::GLOBAL_VISION_POSITION_ESTIMATE(body) => body.ser(version, bytes),
Self::DIGICAM_CONFIGURE(body) => body.ser(version, bytes),
Self::TERRAIN_REQUEST(body) => body.ser(version, bytes),
Self::DATA96(body) => body.ser(version, bytes),
Self::OSD_PARAM_SHOW_CONFIG(body) => body.ser(version, bytes),
Self::RADIO_STATUS(body) => body.ser(version, bytes),
Self::RAW_IMU(body) => body.ser(version, bytes),
Self::MISSION_ITEM(body) => body.ser(version, bytes),
Self::REQUEST_DATA_STREAM(body) => body.ser(version, bytes),
Self::VIDEO_STREAM_STATUS(body) => body.ser(version, bytes),
Self::LOG_ERASE(body) => body.ser(version, bytes),
Self::MANUAL_CONTROL(body) => body.ser(version, bytes),
Self::COMMAND_LONG(body) => body.ser(version, bytes),
Self::MANUAL_SETPOINT(body) => body.ser(version, bytes),
Self::OPEN_DRONE_ID_SYSTEM_UPDATE(body) => body.ser(version, bytes),
Self::OPEN_DRONE_ID_SYSTEM(body) => body.ser(version, bytes),
Self::LINK_NODE_STATUS(body) => body.ser(version, bytes),
Self::OPEN_DRONE_ID_SELF_ID(body) => body.ser(version, bytes),
Self::VISION_POSITION_ESTIMATE(body) => body.ser(version, bytes),
Self::DEVICE_OP_READ_REPLY(body) => body.ser(version, bytes),
Self::HYGROMETER_SENSOR(body) => body.ser(version, bytes),
Self::ATT_POS_MOCAP(body) => body.ser(version, bytes),
Self::RC_CHANNELS(body) => body.ser(version, bytes),
Self::FOLLOW_TARGET(body) => body.ser(version, bytes),
Self::HIL_STATE(body) => body.ser(version, bytes),
Self::HOME_POSITION(body) => body.ser(version, bytes),
Self::OPEN_DRONE_ID_LOCATION(body) => body.ser(version, bytes),
Self::DATA_STREAM(body) => body.ser(version, bytes),
Self::MISSION_CLEAR_ALL(body) => body.ser(version, bytes),
Self::GIMBAL_MANAGER_INFORMATION(body) => body.ser(version, bytes),
Self::VISION_SPEED_ESTIMATE(body) => body.ser(version, bytes),
Self::ESC_INFO(body) => body.ser(version, bytes),
Self::DATA16(body) => body.ser(version, bytes),
Self::MEMORY_VECT(body) => body.ser(version, bytes),
Self::MAG_CAL_PROGRESS(body) => body.ser(version, bytes),
Self::MISSION_ITEM_REACHED(body) => body.ser(version, bytes),
Self::MOUNT_ORIENTATION(body) => body.ser(version, bytes),
Self::DEVICE_OP_READ(body) => body.ser(version, bytes),
Self::VFR_HUD(body) => body.ser(version, bytes),
Self::CURRENT_EVENT_SEQUENCE(body) => body.ser(version, bytes),
Self::ATTITUDE(body) => body.ser(version, bytes),
Self::SCALED_PRESSURE(body) => body.ser(version, bytes),
Self::SENSOR_OFFSETS(body) => body.ser(version, bytes),
Self::VISION_POSITION_DELTA(body) => body.ser(version, bytes),
Self::LOGGING_DATA(body) => body.ser(version, bytes),
Self::GPS_RTCM_DATA(body) => body.ser(version, bytes),
Self::POSITION_TARGET_LOCAL_NED(body) => body.ser(version, bytes),
Self::MISSION_REQUEST(body) => body.ser(version, bytes),
Self::CAMERA_FOV_STATUS(body) => body.ser(version, bytes),
Self::HEARTBEAT(body) => body.ser(version, bytes),
Self::DIGICAM_CONTROL(body) => body.ser(version, bytes),
Self::UTM_GLOBAL_POSITION(body) => body.ser(version, bytes),
Self::RALLY_FETCH_POINT(body) => body.ser(version, bytes),
Self::OBSTACLE_DISTANCE_3D(body) => body.ser(version, bytes),
Self::RALLY_POINT(body) => body.ser(version, bytes),
Self::RC_CHANNELS_RAW(body) => body.ser(version, bytes),
Self::AUTOPILOT_VERSION_REQUEST(body) => body.ser(version, bytes),
Self::WIND_COV(body) => body.ser(version, bytes),
Self::HIL_ACTUATOR_CONTROLS(body) => body.ser(version, bytes),
Self::CAMERA_SETTINGS(body) => body.ser(version, bytes),
Self::ONBOARD_COMPUTER_STATUS(body) => body.ser(version, bytes),
Self::FILE_TRANSFER_PROTOCOL(body) => body.ser(version, bytes),
Self::GPS_RTK(body) => body.ser(version, bytes),
Self::GIMBAL_DEVICE_INFORMATION(body) => body.ser(version, bytes),
Self::LOG_ENTRY(body) => body.ser(version, bytes),
Self::ESC_STATUS(body) => body.ser(version, bytes),
Self::HERELINK_TELEM(body) => body.ser(version, bytes),
Self::GIMBAL_TORQUE_CMD_REPORT(body) => body.ser(version, bytes),
Self::HIGH_LATENCY(body) => body.ser(version, bytes),
Self::ESC_TELEMETRY_5_TO_8(body) => body.ser(version, bytes),
Self::PLAY_TUNE_V2(body) => body.ser(version, bytes),
Self::SET_HOME_POSITION(body) => body.ser(version, bytes),
Self::BATTERY_STATUS(body) => body.ser(version, bytes),
Self::OPEN_DRONE_ID_BASIC_ID(body) => body.ser(version, bytes),
Self::PARAM_EXT_SET(body) => body.ser(version, bytes),
Self::PARAM_EXT_VALUE(body) => body.ser(version, bytes),
Self::ORBIT_EXECUTION_STATUS(body) => body.ser(version, bytes),
Self::NAMED_VALUE_INT(body) => body.ser(version, bytes),
Self::LED_CONTROL(body) => body.ser(version, bytes),
Self::SMART_BATTERY_INFO(body) => body.ser(version, bytes),
}
}
fn extra_crc(id: u32) -> u8 {
match id {
38u32 => 9u8,
50004u32 => 240u8,
250u32 => 49u8,
201u32 => 205u8,
177u32 => 240u8,
257u32 => 131u8,
123u32 => 250u8,
179u32 => 189u8,
217u32 => 202u8,
50001u32 => 1u8,
336u32 => 245u8,
124u32 => 87u8,
230u32 => 163u8,
311u32 => 95u8,
301u32 => 243u8,
42001u32 => 239u8,
225u32 => 208u8,
388u32 => 8u8,
50005u32 => 152u8,
350u32 => 232u8,
299u32 => 19u8,
153u32 => 188u8,
168u32 => 1u8,
286u32 => 210u8,
26u32 => 170u8,
32u32 => 185u8,
219u32 => 162u8,
200u32 => 134u8,
11u32 => 89u8,
276u32 => 18u8,
324u32 => 132u8,
11003u32 => 64u8,
174u32 => 167u8,
375u32 => 251u8,
120u32 => 134u8,
89u32 => 231u8,
215u32 => 101u8,
259u32 => 92u8,
11034u32 => 79u8,
24u32 => 24u8,
108u32 => 32u8,
77u32 => 143u8,
143u32 => 131u8,
12915u32 => 94u8,
339u32 => 199u8,
128u32 => 226u8,
134u32 => 229u8,
41u32 => 28u8,
140u32 => 181u8,
157u32 => 21u8,
132u32 => 85u8,
380u32 => 232u8,
334u32 => 72u8,
285u32 => 137u8,
63u32 => 119u8,
34u32 => 237u8,
256u32 => 71u8,
262u32 => 12u8,
184u32 => 159u8,
258u32 => 187u8,
178u32 => 47u8,
115u32 => 4u8,
28u32 => 67u8,
9005u32 => 117u8,
275u32 => 126u8,
20u32 => 214u8,
44u32 => 221u8,
226u32 => 207u8,
11032u32 => 85u8,
9000u32 => 113u8,
254u32 => 46u8,
107u32 => 108u8,
80u32 => 14u8,
162u32 => 189u8,
330u32 => 23u8,
152u32 => 208u8,
194u32 => 98u8,
10001u32 => 209u8,
397u32 => 182u8,
11036u32 => 177u8,
320u32 => 243u8,
335u32 => 225u8,
331u32 => 91u8,
113u32 => 124u8,
64u32 => 191u8,
264u32 => 49u8,
117u32 => 128u8,
36u32 => 222u8,
51u32 => 196u8,
83u32 => 22u8,
125u32 => 203u8,
146u32 => 103u8,
11030u32 => 144u8,
73u32 => 38u8,
253u32 => 83u8,
12905u32 => 49u8,
2u32 => 137u8,
70u32 => 124u8,
11038u32 => 47u8,
21u32 => 159u8,
61u32 => 167u8,
131u32 => 223u8,
22u32 => 220u8,
6u32 => 104u8,
4u32 => 237u8,
48u32 => 41u8,
195u32 => 120u8,
218u32 => 17u8,
193u32 => 71u8,
11033u32 => 195u8,
321u32 => 88u8,
62u32 => 183u8,
10002u32 => 186u8,
116u32 => 76u8,
160u32 => 78u8,
139u32 => 168u8,
11020u32 => 205u8,
106u32 => 138u8,
104u32 => 56u8,
241u32 => 90u8,
149u32 => 200u8,
42u32 => 28u8,
171u32 => 181u8,
111u32 => 34u8,
251u32 => 170u8,
141u32 => 47u8,
114u32 => 237u8,
247u32 => 81u8,
412u32 => 33u8,
180u32 => 52u8,
216u32 => 50u8,
142u32 => 72u8,
248u32 => 8u8,
300u32 => 217u8,
50u32 => 78u8,
333u32 => 231u8,
23u32 => 168u8,
42000u32 => 227u8,
182u32 => 229u8,
385u32 => 147u8,
11039u32 => 142u8,
410u32 => 160u8,
126u32 => 220u8,
7u32 => 119u8,
246u32 => 184u8,
84u32 => 143u8,
232u32 => 151u8,
244u32 => 95u8,
267u32 => 35u8,
50002u32 => 181u8,
151u32 => 219u8,
130u32 => 29u8,
91u32 => 63u8,
173u32 => 83u8,
10003u32 => 4u8,
268u32 => 14u8,
55u32 => 3u8,
387u32 => 4u8,
43u32 => 132u8,
86u32 => 5u8,
263u32 => 133u8,
75u32 => 158u8,
170u32 => 73u8,
33u32 => 104u8,
92u32 => 54u8,
12918u32 => 139u8,
287u32 => 1u8,
166u32 => 21u8,
49u32 => 39u8,
37u32 => 212u8,
122u32 => 203u8,
119u32 => 116u8,
54u32 => 15u8,
401u32 => 183u8,
245u32 => 130u8,
11002u32 => 234u8,
373u32 => 117u8,
31u32 => 246u8,
163u32 => 127u8,
136u32 => 1u8,
12902u32 => 140u8,
413u32 => 77u8,
129u32 => 46u8,
87u32 => 150u8,
25u32 => 23u8,
310u32 => 28u8,
192u32 => 36u8,
137u32 => 195u8,
386u32 => 132u8,
100u32 => 175u8,
281u32 => 48u8,
135u32 => 203u8,
269u32 => 109u8,
158u32 => 134u8,
82u32 => 49u8,
282u32 => 123u8,
284u32 => 99u8,
105u32 => 93u8,
288u32 => 20u8,
112u32 => 174u8,
181u32 => 174u8,
185u32 => 186u8,
164u32 => 154u8,
165u32 => 21u8,
167u32 => 144u8,
235u32 => 179u8,
261u32 => 179u8,
148u32 => 178u8,
47u32 => 153u8,
161u32 => 68u8,
156u32 => 19u8,
332u32 => 236u8,
5u32 => 217u8,
395u32 => 0u8,
1u32 => 124u8,
11010u32 => 46u8,
101u32 => 102u8,
154u32 => 84u8,
133u32 => 6u8,
172u32 => 22u8,
11035u32 => 128u8,
109u32 => 185u8,
27u32 => 144u8,
39u32 => 254u8,
66u32 => 148u8,
270u32 => 59u8,
121u32 => 237u8,
69u32 => 243u8,
76u32 => 152u8,
81u32 => 106u8,
12919u32 => 7u8,
12904u32 => 77u8,
8u32 => 117u8,
12903u32 => 249u8,
102u32 => 158u8,
11001u32 => 15u8,
12920u32 => 20u8,
138u32 => 109u8,
65u32 => 118u8,
144u32 => 127u8,
90u32 => 183u8,
242u32 => 104u8,
12901u32 => 254u8,
67u32 => 21u8,
45u32 => 232u8,
280u32 => 70u8,
103u32 => 208u8,
290u32 => 251u8,
169u32 => 234u8,
249u32 => 204u8,
191u32 => 92u8,
46u32 => 11u8,
265u32 => 26u8,
11000u32 => 134u8,
74u32 => 20u8,
411u32 => 106u8,
30u32 => 39u8,
29u32 => 115u8,
150u32 => 134u8,
11011u32 => 106u8,
266u32 => 193u8,
233u32 => 35u8,
85u32 => 140u8,
40u32 => 230u8,
271u32 => 22u8,
0u32 => 50u8,
155u32 => 22u8,
340u32 => 99u8,
176u32 => 234u8,
11037u32 => 130u8,
175u32 => 138u8,
35u32 => 244u8,
183u32 => 85u8,
231u32 => 105u8,
93u32 => 47u8,
260u32 => 146u8,
390u32 => 156u8,
110u32 => 84u8,
127u32 => 25u8,
283u32 => 74u8,
118u32 => 56u8,
291u32 => 10u8,
50003u32 => 53u8,
214u32 => 69u8,
234u32 => 150u8,
11031u32 => 133u8,
400u32 => 110u8,
243u32 => 85u8,
147u32 => 154u8,
12900u32 => 114u8,
323u32 => 78u8,
322u32 => 243u8,
360u32 => 11u8,
252u32 => 44u8,
186u32 => 72u8,
370u32 => 75u8,
_ => 0,
}
}
}