pub enum MavMessage {
Show 63 variants SENSOR_OFFSETS(SENSOR_OFFSETS_DATA), SET_MAG_OFFSETS(SET_MAG_OFFSETS_DATA), MEMINFO(MEMINFO_DATA), AP_ADC(AP_ADC_DATA), DIGICAM_CONFIGURE(DIGICAM_CONFIGURE_DATA), DIGICAM_CONTROL(DIGICAM_CONTROL_DATA), MOUNT_CONFIGURE(MOUNT_CONFIGURE_DATA), MOUNT_CONTROL(MOUNT_CONTROL_DATA), MOUNT_STATUS(MOUNT_STATUS_DATA), FENCE_POINT(FENCE_POINT_DATA), FENCE_FETCH_POINT(FENCE_FETCH_POINT_DATA), AHRS(AHRS_DATA), SIMSTATE(SIMSTATE_DATA), HWSTATUS(HWSTATUS_DATA), RADIO(RADIO_DATA), LIMITS_STATUS(LIMITS_STATUS_DATA), WIND(WIND_DATA), DATA16(DATA16_DATA), DATA32(DATA32_DATA), DATA64(DATA64_DATA), DATA96(DATA96_DATA), RANGEFINDER(RANGEFINDER_DATA), AIRSPEED_AUTOCAL(AIRSPEED_AUTOCAL_DATA), RALLY_POINT(RALLY_POINT_DATA), RALLY_FETCH_POINT(RALLY_FETCH_POINT_DATA), COMPASSMOT_STATUS(COMPASSMOT_STATUS_DATA), AHRS2(AHRS2_DATA), CAMERA_STATUS(CAMERA_STATUS_DATA), CAMERA_FEEDBACK(CAMERA_FEEDBACK_DATA), BATTERY2(BATTERY2_DATA), AHRS3(AHRS3_DATA), AUTOPILOT_VERSION_REQUEST(AUTOPILOT_VERSION_REQUEST_DATA), REMOTE_LOG_DATA_BLOCK(REMOTE_LOG_DATA_BLOCK_DATA), REMOTE_LOG_BLOCK_STATUS(REMOTE_LOG_BLOCK_STATUS_DATA), LED_CONTROL(LED_CONTROL_DATA), MAG_CAL_PROGRESS(MAG_CAL_PROGRESS_DATA), MAG_CAL_REPORT(MAG_CAL_REPORT_DATA), EKF_STATUS_REPORT(EKF_STATUS_REPORT_DATA), PID_TUNING(PID_TUNING_DATA), DEEPSTALL(DEEPSTALL_DATA), GIMBAL_REPORT(GIMBAL_REPORT_DATA), GIMBAL_CONTROL(GIMBAL_CONTROL_DATA), GIMBAL_TORQUE_CMD_REPORT(GIMBAL_TORQUE_CMD_REPORT_DATA), GOPRO_HEARTBEAT(GOPRO_HEARTBEAT_DATA), GOPRO_GET_REQUEST(GOPRO_GET_REQUEST_DATA), GOPRO_GET_RESPONSE(GOPRO_GET_RESPONSE_DATA), GOPRO_SET_REQUEST(GOPRO_SET_REQUEST_DATA), GOPRO_SET_RESPONSE(GOPRO_SET_RESPONSE_DATA), EFI_STATUS(EFI_STATUS_DATA), RPM(RPM_DATA), DEVICE_OP_READ(DEVICE_OP_READ_DATA), DEVICE_OP_READ_REPLY(DEVICE_OP_READ_REPLY_DATA), DEVICE_OP_WRITE(DEVICE_OP_WRITE_DATA), DEVICE_OP_WRITE_REPLY(DEVICE_OP_WRITE_REPLY_DATA), ADAP_TUNING(ADAP_TUNING_DATA), VISION_POSITION_DELTA(VISION_POSITION_DELTA_DATA), AOA_SSA(AOA_SSA_DATA), ESC_TELEMETRY_1_TO_4(ESC_TELEMETRY_1_TO_4_DATA), ESC_TELEMETRY_5_TO_8(ESC_TELEMETRY_5_TO_8_DATA), ESC_TELEMETRY_9_TO_12(ESC_TELEMETRY_9_TO_12_DATA), common(MavMessage), uavionix(MavMessage), icarous(MavMessage),
}

Variants§

§

SENSOR_OFFSETS(SENSOR_OFFSETS_DATA)

§

SET_MAG_OFFSETS(SET_MAG_OFFSETS_DATA)

§

MEMINFO(MEMINFO_DATA)

§

AP_ADC(AP_ADC_DATA)

§

DIGICAM_CONFIGURE(DIGICAM_CONFIGURE_DATA)

§

DIGICAM_CONTROL(DIGICAM_CONTROL_DATA)

§

MOUNT_CONFIGURE(MOUNT_CONFIGURE_DATA)

§

MOUNT_CONTROL(MOUNT_CONTROL_DATA)

§

MOUNT_STATUS(MOUNT_STATUS_DATA)

§

FENCE_POINT(FENCE_POINT_DATA)

§

FENCE_FETCH_POINT(FENCE_FETCH_POINT_DATA)

§

AHRS(AHRS_DATA)

§

SIMSTATE(SIMSTATE_DATA)

§

HWSTATUS(HWSTATUS_DATA)

§

RADIO(RADIO_DATA)

§

LIMITS_STATUS(LIMITS_STATUS_DATA)

§

WIND(WIND_DATA)

§

DATA16(DATA16_DATA)

§

DATA32(DATA32_DATA)

§

DATA64(DATA64_DATA)

§

DATA96(DATA96_DATA)

§

RANGEFINDER(RANGEFINDER_DATA)

§

AIRSPEED_AUTOCAL(AIRSPEED_AUTOCAL_DATA)

§

RALLY_POINT(RALLY_POINT_DATA)

§

RALLY_FETCH_POINT(RALLY_FETCH_POINT_DATA)

§

COMPASSMOT_STATUS(COMPASSMOT_STATUS_DATA)

§

AHRS2(AHRS2_DATA)

§

CAMERA_STATUS(CAMERA_STATUS_DATA)

§

CAMERA_FEEDBACK(CAMERA_FEEDBACK_DATA)

§

BATTERY2(BATTERY2_DATA)

§

AHRS3(AHRS3_DATA)

§

AUTOPILOT_VERSION_REQUEST(AUTOPILOT_VERSION_REQUEST_DATA)

§

REMOTE_LOG_DATA_BLOCK(REMOTE_LOG_DATA_BLOCK_DATA)

§

REMOTE_LOG_BLOCK_STATUS(REMOTE_LOG_BLOCK_STATUS_DATA)

§

LED_CONTROL(LED_CONTROL_DATA)

§

MAG_CAL_PROGRESS(MAG_CAL_PROGRESS_DATA)

§

MAG_CAL_REPORT(MAG_CAL_REPORT_DATA)

§

EKF_STATUS_REPORT(EKF_STATUS_REPORT_DATA)

§

PID_TUNING(PID_TUNING_DATA)

§

DEEPSTALL(DEEPSTALL_DATA)

§

GIMBAL_REPORT(GIMBAL_REPORT_DATA)

§

GIMBAL_CONTROL(GIMBAL_CONTROL_DATA)

§

GIMBAL_TORQUE_CMD_REPORT(GIMBAL_TORQUE_CMD_REPORT_DATA)

§

GOPRO_HEARTBEAT(GOPRO_HEARTBEAT_DATA)

§

GOPRO_GET_REQUEST(GOPRO_GET_REQUEST_DATA)

§

GOPRO_GET_RESPONSE(GOPRO_GET_RESPONSE_DATA)

§

GOPRO_SET_REQUEST(GOPRO_SET_REQUEST_DATA)

§

GOPRO_SET_RESPONSE(GOPRO_SET_RESPONSE_DATA)

§

EFI_STATUS(EFI_STATUS_DATA)

§

RPM(RPM_DATA)

§

DEVICE_OP_READ(DEVICE_OP_READ_DATA)

§

DEVICE_OP_READ_REPLY(DEVICE_OP_READ_REPLY_DATA)

§

DEVICE_OP_WRITE(DEVICE_OP_WRITE_DATA)

§

DEVICE_OP_WRITE_REPLY(DEVICE_OP_WRITE_REPLY_DATA)

§

ADAP_TUNING(ADAP_TUNING_DATA)

§

VISION_POSITION_DELTA(VISION_POSITION_DELTA_DATA)

§

AOA_SSA(AOA_SSA_DATA)

§

ESC_TELEMETRY_1_TO_4(ESC_TELEMETRY_1_TO_4_DATA)

§

ESC_TELEMETRY_5_TO_8(ESC_TELEMETRY_5_TO_8_DATA)

§

ESC_TELEMETRY_9_TO_12(ESC_TELEMETRY_9_TO_12_DATA)

§

common(MavMessage)

§

uavionix(MavMessage)

§

icarous(MavMessage)

Trait Implementations§

source§

impl Clone for MavMessage

source§

fn clone(&self) -> MavMessage

Returns a copy of the value. Read more
1.0.0 · source§

fn clone_from(&mut self, source: &Self)

Performs copy-assignment from source. Read more
source§

impl Debug for MavMessage

source§

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

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

impl<'de> Deserialize<'de> for MavMessage

source§

fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>
where __D: Deserializer<'de>,

Deserialize this value from the given Serde deserializer. Read more
source§

impl From<MavMessage> for MavMessage

source§

fn from(message: MavMessage) -> Self

Converts to this type from the input type.
source§

impl From<MavMessage> for MavMessage

source§

fn from(message: MavMessage) -> Self

Converts to this type from the input type.
source§

impl From<MavMessage> for MavMessage

source§

fn from(message: MavMessage) -> Self

Converts to this type from the input type.
source§

impl Message for MavMessage

source§

fn parse( version: MavlinkVersion, id: u32, payload: &[u8] ) -> Result<MavMessage, ParserError>

source§

fn message_name(&self) -> &'static str

source§

fn message_id(&self) -> u32

source§

fn message_id_from_name(name: &str) -> Result<u32, &'static str>

source§

fn default_message_from_id(id: u32) -> Result<MavMessage, &'static str>

source§

fn ser(&self) -> Vec<u8>

source§

fn extra_crc(id: u32) -> u8

source§

impl PartialEq for MavMessage

source§

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

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

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

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

impl Serialize for MavMessage

source§

fn serialize<__S>(&self, __serializer: __S) -> Result<__S::Ok, __S::Error>
where __S: Serializer,

Serialize this value into the given Serde serializer. Read more
source§

impl StructuralPartialEq for MavMessage

Auto Trait Implementations§

Blanket Implementations§

source§

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

source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
source§

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

source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
source§

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

source§

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

Mutably borrows from an owned value. Read more
source§

impl<T> From<T> for T

source§

fn from(t: T) -> T

Returns the argument unchanged.

source§

impl<T, U> Into<U> for T
where U: From<T>,

source§

fn into(self) -> U

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

source§

impl<T> ToOwned for T
where T: Clone,

§

type Owned = T

The resulting type after obtaining ownership.
source§

fn to_owned(&self) -> T

Creates owned data from borrowed data, usually by cloning. Read more
source§

fn clone_into(&self, target: &mut T)

Uses borrowed data to replace owned data, usually by cloning. Read more
source§

impl<T, U> TryFrom<U> for T
where U: Into<T>,

§

type Error = Infallible

The type returned in the event of a conversion error.
source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
source§

impl<T, U> TryInto<U> for T
where U: TryFrom<T>,

§

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.
source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.
source§

impl<T> DeserializeOwned for T
where T: for<'de> Deserialize<'de>,