pub enum MavMessage {
Show 296 variants RADIO(RADIO_DATA), PARAM_MAP_RC(PARAM_MAP_RC_DATA), COMMAND_INT(COMMAND_INT_DATA), HIGH_LATENCY2(HIGH_LATENCY2_DATA), MISSION_CLEAR_ALL(MISSION_CLEAR_ALL_DATA), MOUNT_CONTROL(MOUNT_CONTROL_DATA), HIL_RC_INPUTS_RAW(HIL_RC_INPUTS_RAW_DATA), LOCAL_POSITION_NED_COV(LOCAL_POSITION_NED_COV_DATA), DATA64(DATA64_DATA), CUBEPILOT_FIRMWARE_UPDATE_RESP(CUBEPILOT_FIRMWARE_UPDATE_RESP_DATA), STATUSTEXT(STATUSTEXT_DATA), MISSION_WRITE_PARTIAL_LIST(MISSION_WRITE_PARTIAL_LIST_DATA), HIL_STATE_QUATERNION(HIL_STATE_QUATERNION_DATA), ESC_INFO(ESC_INFO_DATA), ESC_TELEMETRY_1_TO_4(ESC_TELEMETRY_1_TO_4_DATA), OSD_PARAM_SHOW_CONFIG_REPLY(OSD_PARAM_SHOW_CONFIG_REPLY_DATA), GLOBAL_POSITION_INT(GLOBAL_POSITION_INT_DATA), GOPRO_SET_REQUEST(GOPRO_SET_REQUEST_DATA), GIMBAL_REPORT(GIMBAL_REPORT_DATA), NAMED_VALUE_FLOAT(NAMED_VALUE_FLOAT_DATA), SET_HOME_POSITION(SET_HOME_POSITION_DATA), REMOTE_LOG_DATA_BLOCK(REMOTE_LOG_DATA_BLOCK_DATA), DEEPSTALL(DEEPSTALL_DATA), DEVICE_OP_READ_REPLY(DEVICE_OP_READ_REPLY_DATA), WIND_COV(WIND_COV_DATA), DEBUG(DEBUG_DATA), DATA_STREAM(DATA_STREAM_DATA), LOG_REQUEST_END(LOG_REQUEST_END_DATA), SIM_STATE(SIM_STATE_DATA), ACTUATOR_CONTROL_TARGET(ACTUATOR_CONTROL_TARGET_DATA), DIGICAM_CONTROL(DIGICAM_CONTROL_DATA), SET_MAG_OFFSETS(SET_MAG_OFFSETS_DATA), HIL_ACTUATOR_CONTROLS(HIL_ACTUATOR_CONTROLS_DATA), CAMERA_TRACKING_GEO_STATUS(CAMERA_TRACKING_GEO_STATUS_DATA), GIMBAL_MANAGER_SET_MANUAL_CONTROL(GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA), COMMAND_CANCEL(COMMAND_CANCEL_DATA), VICON_POSITION_ESTIMATE(VICON_POSITION_ESTIMATE_DATA), CAMERA_SETTINGS(CAMERA_SETTINGS_DATA), NAMED_VALUE_INT(NAMED_VALUE_INT_DATA), PLAY_TUNE(PLAY_TUNE_DATA), ESC_TELEMETRY_9_TO_12(ESC_TELEMETRY_9_TO_12_DATA), SCALED_PRESSURE(SCALED_PRESSURE_DATA), GOPRO_GET_REQUEST(GOPRO_GET_REQUEST_DATA), SET_ACTUATOR_CONTROL_TARGET(SET_ACTUATOR_CONTROL_TARGET_DATA), POSITION_TARGET_LOCAL_NED(POSITION_TARGET_LOCAL_NED_DATA), GIMBAL_MANAGER_STATUS(GIMBAL_MANAGER_STATUS_DATA), DEBUG_FLOAT_ARRAY(DEBUG_FLOAT_ARRAY_DATA), MANUAL_CONTROL(MANUAL_CONTROL_DATA), OBSTACLE_DISTANCE_3D(OBSTACLE_DISTANCE_3D_DATA), TIMESYNC(TIMESYNC_DATA), VISION_SPEED_ESTIMATE(VISION_SPEED_ESTIMATE_DATA), CAN_FRAME(CAN_FRAME_DATA), FENCE_STATUS(FENCE_STATUS_DATA), OBSTACLE_DISTANCE(OBSTACLE_DISTANCE_DATA), VFR_HUD(VFR_HUD_DATA), UTM_GLOBAL_POSITION(UTM_GLOBAL_POSITION_DATA), BATTERY_STATUS(BATTERY_STATUS_DATA), VISION_POSITION_DELTA(VISION_POSITION_DELTA_DATA), HIGHRES_IMU(HIGHRES_IMU_DATA), LINK_NODE_STATUS(LINK_NODE_STATUS_DATA), SCALED_PRESSURE2(SCALED_PRESSURE2_DATA), RC_CHANNELS_OVERRIDE(RC_CHANNELS_OVERRIDE_DATA), AUTOPILOT_VERSION(AUTOPILOT_VERSION_DATA), LANDING_TARGET(LANDING_TARGET_DATA), AOA_SSA(AOA_SSA_DATA), DEBUG_VECT(DEBUG_VECT_DATA), UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT(UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA), EKF_STATUS_REPORT(EKF_STATUS_REPORT_DATA), ACTUATOR_OUTPUT_STATUS(ACTUATOR_OUTPUT_STATUS_DATA), GPS_INPUT(GPS_INPUT_DATA), REMOTE_LOG_BLOCK_STATUS(REMOTE_LOG_BLOCK_STATUS_DATA), FENCE_FETCH_POINT(FENCE_FETCH_POINT_DATA), DEVICE_OP_READ(DEVICE_OP_READ_DATA), V2_EXTENSION(V2_EXTENSION_DATA), OSD_PARAM_CONFIG(OSD_PARAM_CONFIG_DATA), VISION_POSITION_ESTIMATE(VISION_POSITION_ESTIMATE_DATA), POSITION_TARGET_GLOBAL_INT(POSITION_TARGET_GLOBAL_INT_DATA), GPS_STATUS(GPS_STATUS_DATA), OPEN_DRONE_ID_SYSTEM(OPEN_DRONE_ID_SYSTEM_DATA), AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA), ENCAPSULATED_DATA(ENCAPSULATED_DATA_DATA), OSD_PARAM_SHOW_CONFIG(OSD_PARAM_SHOW_CONFIG_DATA), CAMERA_INFORMATION(CAMERA_INFORMATION_DATA), COMPONENT_INFORMATION(COMPONENT_INFORMATION_DATA), SET_GPS_GLOBAL_ORIGIN(SET_GPS_GLOBAL_ORIGIN_DATA), MISSION_CURRENT(MISSION_CURRENT_DATA), OPEN_DRONE_ID_LOCATION(OPEN_DRONE_ID_LOCATION_DATA), ESTIMATOR_STATUS(ESTIMATOR_STATUS_DATA), PARAM_VALUE(PARAM_VALUE_DATA), GIMBAL_DEVICE_ATTITUDE_STATUS(GIMBAL_DEVICE_ATTITUDE_STATUS_DATA), AP_ADC(AP_ADC_DATA), HIL_GPS(HIL_GPS_DATA), LOGGING_DATA_ACKED(LOGGING_DATA_ACKED_DATA), GIMBAL_CONTROL(GIMBAL_CONTROL_DATA), TERRAIN_DATA(TERRAIN_DATA_DATA), EFI_STATUS(EFI_STATUS_DATA), ESC_STATUS(ESC_STATUS_DATA), MISSION_ITEM_REACHED(MISSION_ITEM_REACHED_DATA), MISSION_REQUEST_LIST(MISSION_REQUEST_LIST_DATA), UAVIONIX_ADSB_OUT_DYNAMIC(UAVIONIX_ADSB_OUT_DYNAMIC_DATA), SYSTEM_TIME(SYSTEM_TIME_DATA), ICAROUS_HEARTBEAT(ICAROUS_HEARTBEAT_DATA), CAMERA_FEEDBACK(CAMERA_FEEDBACK_DATA), LED_CONTROL(LED_CONTROL_DATA), UAVIONIX_ADSB_OUT_CFG(UAVIONIX_ADSB_OUT_CFG_DATA), OPEN_DRONE_ID_SYSTEM_UPDATE(OPEN_DRONE_ID_SYSTEM_UPDATE_DATA), TUNNEL(TUNNEL_DATA), POWER_STATUS(POWER_STATUS_DATA), RAW_IMU(RAW_IMU_DATA), CUBEPILOT_RAW_RC(CUBEPILOT_RAW_RC_DATA), OPEN_DRONE_ID_MESSAGE_PACK(OPEN_DRONE_ID_MESSAGE_PACK_DATA), PARAM_EXT_REQUEST_READ(PARAM_EXT_REQUEST_READ_DATA), HIL_SENSOR(HIL_SENSOR_DATA), CURRENT_EVENT_SEQUENCE(CURRENT_EVENT_SEQUENCE_DATA), LOG_ENTRY(LOG_ENTRY_DATA), GENERATOR_STATUS(GENERATOR_STATUS_DATA), ADSB_VEHICLE(ADSB_VEHICLE_DATA), FOLLOW_TARGET(FOLLOW_TARGET_DATA), ATTITUDE_QUATERNION(ATTITUDE_QUATERNION_DATA), PARAM_REQUEST_LIST(PARAM_REQUEST_LIST_DATA), HERELINK_TELEM(HERELINK_TELEM_DATA), AIRSPEED_AUTOCAL(AIRSPEED_AUTOCAL_DATA), MISSION_REQUEST(MISSION_REQUEST_DATA), MCU_STATUS(MCU_STATUS_DATA), OPEN_DRONE_ID_ARM_STATUS(OPEN_DRONE_ID_ARM_STATUS_DATA), HERELINK_VIDEO_STREAM_INFORMATION(HERELINK_VIDEO_STREAM_INFORMATION_DATA), PING(PING_DATA), HYGROMETER_SENSOR(HYGROMETER_SENSOR_DATA), SETUP_SIGNING(SETUP_SIGNING_DATA), MEMORY_VECT(MEMORY_VECT_DATA), OPEN_DRONE_ID_OPERATOR_ID(OPEN_DRONE_ID_OPERATOR_ID_DATA), SCALED_IMU(SCALED_IMU_DATA), ALTITUDE(ALTITUDE_DATA), LOGGING_ACK(LOGGING_ACK_DATA), RC_CHANNELS_SCALED(RC_CHANNELS_SCALED_DATA), AHRS(AHRS_DATA), CHANGE_OPERATOR_CONTROL(CHANGE_OPERATOR_CONTROL_DATA), RANGEFINDER(RANGEFINDER_DATA), SMART_BATTERY_INFO(SMART_BATTERY_INFO_DATA), PARAM_EXT_ACK(PARAM_EXT_ACK_DATA), GOPRO_SET_RESPONSE(GOPRO_SET_RESPONSE_DATA), EVENT(EVENT_DATA), GPS_INJECT_DATA(GPS_INJECT_DATA_DATA), ADAP_TUNING(ADAP_TUNING_DATA), GPS_GLOBAL_ORIGIN(GPS_GLOBAL_ORIGIN_DATA), SERVO_OUTPUT_RAW(SERVO_OUTPUT_RAW_DATA), PROTOCOL_VERSION(PROTOCOL_VERSION_DATA), CANFD_FRAME(CANFD_FRAME_DATA), GPS_RTK(GPS_RTK_DATA), ONBOARD_COMPUTER_STATUS(ONBOARD_COMPUTER_STATUS_DATA), TERRAIN_CHECK(TERRAIN_CHECK_DATA), PLAY_TUNE_V2(PLAY_TUNE_V2_DATA), CAN_FILTER_MODIFY(CAN_FILTER_MODIFY_DATA), GPS2_RAW(GPS2_RAW_DATA), UAVCAN_NODE_INFO(UAVCAN_NODE_INFO_DATA), HIGH_LATENCY(HIGH_LATENCY_DATA), TERRAIN_REQUEST(TERRAIN_REQUEST_DATA), SCALED_IMU3(SCALED_IMU3_DATA), RALLY_FETCH_POINT(RALLY_FETCH_POINT_DATA), LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA), RAW_PRESSURE(RAW_PRESSURE_DATA), LOG_REQUEST_DATA(LOG_REQUEST_DATA_DATA), GPS_RAW_INT(GPS_RAW_INT_DATA), RC_CHANNELS_RAW(RC_CHANNELS_RAW_DATA), VIDEO_STREAM_STATUS(VIDEO_STREAM_STATUS_DATA), TRAJECTORY_REPRESENTATION_BEZIER(TRAJECTORY_REPRESENTATION_BEZIER_DATA), LOG_ERASE(LOG_ERASE_DATA), RAW_RPM(RAW_RPM_DATA), ATTITUDE_QUATERNION_COV(ATTITUDE_QUATERNION_COV_DATA), MESSAGE_INTERVAL(MESSAGE_INTERVAL_DATA), MISSION_COUNT(MISSION_COUNT_DATA), ORBIT_EXECUTION_STATUS(ORBIT_EXECUTION_STATUS_DATA), GIMBAL_MANAGER_SET_ATTITUDE(GIMBAL_MANAGER_SET_ATTITUDE_DATA), PID_TUNING(PID_TUNING_DATA), CAMERA_STATUS(CAMERA_STATUS_DATA), LIMITS_STATUS(LIMITS_STATUS_DATA), FLIGHT_INFORMATION(FLIGHT_INFORMATION_DATA), AHRS3(AHRS3_DATA), SCALED_IMU2(SCALED_IMU2_DATA), TRAJECTORY_REPRESENTATION_WAYPOINTS(TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA), MISSION_REQUEST_INT(MISSION_REQUEST_INT_DATA), ESC_TELEMETRY_5_TO_8(ESC_TELEMETRY_5_TO_8_DATA), ISBD_LINK_STATUS(ISBD_LINK_STATUS_DATA), CAMERA_IMAGE_CAPTURED(CAMERA_IMAGE_CAPTURED_DATA), SENSOR_OFFSETS(SENSOR_OFFSETS_DATA), DEVICE_OP_WRITE_REPLY(DEVICE_OP_WRITE_REPLY_DATA), SIMSTATE(SIMSTATE_DATA), FILE_TRANSFER_PROTOCOL(FILE_TRANSFER_PROTOCOL_DATA), WIND(WIND_DATA), AUTOPILOT_VERSION_REQUEST(AUTOPILOT_VERSION_REQUEST_DATA), CUBEPILOT_FIRMWARE_UPDATE_START(CUBEPILOT_FIRMWARE_UPDATE_START_DATA), COMMAND_ACK(COMMAND_ACK_DATA), SET_MODE(SET_MODE_DATA), LOCAL_POSITION_NED(LOCAL_POSITION_NED_DATA), RADIO_STATUS(RADIO_STATUS_DATA), DIGICAM_CONFIGURE(DIGICAM_CONFIGURE_DATA), CONTROL_SYSTEM_STATE(CONTROL_SYSTEM_STATE_DATA), HIL_CONTROLS(HIL_CONTROLS_DATA), STORAGE_INFORMATION(STORAGE_INFORMATION_DATA), DATA32(DATA32_DATA), GIMBAL_TORQUE_CMD_REPORT(GIMBAL_TORQUE_CMD_REPORT_DATA), MISSION_REQUEST_PARTIAL_LIST(MISSION_REQUEST_PARTIAL_LIST_DATA), TIME_ESTIMATE_TO_TARGET(TIME_ESTIMATE_TO_TARGET_DATA), GIMBAL_DEVICE_INFORMATION(GIMBAL_DEVICE_INFORMATION_DATA), EXTENDED_SYS_STATE(EXTENDED_SYS_STATE_DATA), DATA_TRANSMISSION_HANDSHAKE(DATA_TRANSMISSION_HANDSHAKE_DATA), HIL_OPTICAL_FLOW(HIL_OPTICAL_FLOW_DATA), LOG_DATA(LOG_DATA_DATA), MISSION_ITEM(MISSION_ITEM_DATA), DEVICE_OP_WRITE(DEVICE_OP_WRITE_DATA), MOUNT_STATUS(MOUNT_STATUS_DATA), CAMERA_CAPTURE_STATUS(CAMERA_CAPTURE_STATUS_DATA), HOME_POSITION(HOME_POSITION_DATA), CAMERA_FOV_STATUS(CAMERA_FOV_STATUS_DATA), SUPPORTED_TUNES(SUPPORTED_TUNES_DATA), GIMBAL_MANAGER_SET_PITCHYAW(GIMBAL_MANAGER_SET_PITCHYAW_DATA), COMMAND_LONG(COMMAND_LONG_DATA), GPS2_RTK(GPS2_RTK_DATA), PARAM_EXT_SET(PARAM_EXT_SET_DATA), SET_ATTITUDE_TARGET(SET_ATTITUDE_TARGET_DATA), GPS_RTCM_DATA(GPS_RTCM_DATA_DATA), OPTICAL_FLOW(OPTICAL_FLOW_DATA), MISSION_SET_CURRENT(MISSION_SET_CURRENT_DATA), COMPONENT_METADATA(COMPONENT_METADATA_DATA), PARAM_EXT_VALUE(PARAM_EXT_VALUE_DATA), CELLULAR_CONFIG(CELLULAR_CONFIG_DATA), GLOBAL_VISION_POSITION_ESTIMATE(GLOBAL_VISION_POSITION_ESTIMATE_DATA), LOGGING_DATA(LOGGING_DATA_DATA), VIDEO_STREAM_INFORMATION(VIDEO_STREAM_INFORMATION_DATA), WIFI_CONFIG_AP(WIFI_CONFIG_AP_DATA), RALLY_POINT(RALLY_POINT_DATA), RESOURCE_REQUEST(RESOURCE_REQUEST_DATA), MAG_CAL_PROGRESS(MAG_CAL_PROGRESS_DATA), GLOBAL_POSITION_INT_COV(GLOBAL_POSITION_INT_COV_DATA), RPM(RPM_DATA), WHEEL_DISTANCE(WHEEL_DISTANCE_DATA), CELLULAR_STATUS(CELLULAR_STATUS_DATA), REQUEST_EVENT(REQUEST_EVENT_DATA), AUTH_KEY(AUTH_KEY_DATA), REQUEST_DATA_STREAM(REQUEST_DATA_STREAM_DATA), SET_POSITION_TARGET_GLOBAL_INT(SET_POSITION_TARGET_GLOBAL_INT_DATA), WINCH_STATUS(WINCH_STATUS_DATA), WATER_DEPTH(WATER_DEPTH_DATA), COMPASSMOT_STATUS(COMPASSMOT_STATUS_DATA), HIL_STATE(HIL_STATE_DATA), NAV_CONTROLLER_OUTPUT(NAV_CONTROLLER_OUTPUT_DATA), LOG_REQUEST_LIST(LOG_REQUEST_LIST_DATA), MISSION_ITEM_INT(MISSION_ITEM_INT_DATA), HEARTBEAT(HEARTBEAT_DATA), CAMERA_TRIGGER(CAMERA_TRIGGER_DATA), ATT_POS_MOCAP(ATT_POS_MOCAP_DATA), ATTITUDE(ATTITUDE_DATA), ICAROUS_KINEMATIC_BANDS(ICAROUS_KINEMATIC_BANDS_DATA), DATA16(DATA16_DATA), GIMBAL_DEVICE_SET_ATTITUDE(GIMBAL_DEVICE_SET_ATTITUDE_DATA), GOPRO_GET_RESPONSE(GOPRO_GET_RESPONSE_DATA), SAFETY_ALLOWED_AREA(SAFETY_ALLOWED_AREA_DATA), SET_POSITION_TARGET_LOCAL_NED(SET_POSITION_TARGET_LOCAL_NED_DATA), BUTTON_CHANGE(BUTTON_CHANGE_DATA), SERIAL_CONTROL(SERIAL_CONTROL_DATA), MOUNT_CONFIGURE(MOUNT_CONFIGURE_DATA), SCALED_PRESSURE3(SCALED_PRESSURE3_DATA), CAMERA_TRACKING_IMAGE_STATUS(CAMERA_TRACKING_IMAGE_STATUS_DATA), RC_CHANNELS(RC_CHANNELS_DATA), AHRS2(AHRS2_DATA), MAG_CAL_REPORT(MAG_CAL_REPORT_DATA), MOUNT_ORIENTATION(MOUNT_ORIENTATION_DATA), VIBRATION(VIBRATION_DATA), GIMBAL_MANAGER_INFORMATION(GIMBAL_MANAGER_INFORMATION_DATA), GOPRO_HEARTBEAT(GOPRO_HEARTBEAT_DATA), OSD_PARAM_CONFIG_REPLY(OSD_PARAM_CONFIG_REPLY_DATA), PARAM_REQUEST_READ(PARAM_REQUEST_READ_DATA), OPTICAL_FLOW_RAD(OPTICAL_FLOW_RAD_DATA), MISSION_ACK(MISSION_ACK_DATA), RESPONSE_EVENT_ERROR(RESPONSE_EVENT_ERROR_DATA), CHANGE_OPERATOR_CONTROL_ACK(CHANGE_OPERATOR_CONTROL_ACK_DATA), MEMINFO(MEMINFO_DATA), FENCE_POINT(FENCE_POINT_DATA), DATA96(DATA96_DATA), HWSTATUS(HWSTATUS_DATA), PARAM_SET(PARAM_SET_DATA), COLLISION(COLLISION_DATA), BATTERY2(BATTERY2_DATA), DISTANCE_SENSOR(DISTANCE_SENSOR_DATA), ATTITUDE_TARGET(ATTITUDE_TARGET_DATA), AIS_VESSEL(AIS_VESSEL_DATA), SAFETY_SET_ALLOWED_AREA(SAFETY_SET_ALLOWED_AREA_DATA), TERRAIN_REPORT(TERRAIN_REPORT_DATA), ODOMETRY(ODOMETRY_DATA), PARAM_EXT_REQUEST_LIST(PARAM_EXT_REQUEST_LIST_DATA), OPEN_DRONE_ID_AUTHENTICATION(OPEN_DRONE_ID_AUTHENTICATION_DATA), SYS_STATUS(SYS_STATUS_DATA), UAVCAN_NODE_STATUS(UAVCAN_NODE_STATUS_DATA), OPEN_DRONE_ID_SELF_ID(OPEN_DRONE_ID_SELF_ID_DATA), OPEN_DRONE_ID_BASIC_ID(OPEN_DRONE_ID_BASIC_ID_DATA), MANUAL_SETPOINT(MANUAL_SETPOINT_DATA),
}

Variants§

§

RADIO(RADIO_DATA)

§

PARAM_MAP_RC(PARAM_MAP_RC_DATA)

§

COMMAND_INT(COMMAND_INT_DATA)

§

HIGH_LATENCY2(HIGH_LATENCY2_DATA)

§

MISSION_CLEAR_ALL(MISSION_CLEAR_ALL_DATA)

§

MOUNT_CONTROL(MOUNT_CONTROL_DATA)

§

HIL_RC_INPUTS_RAW(HIL_RC_INPUTS_RAW_DATA)

§

LOCAL_POSITION_NED_COV(LOCAL_POSITION_NED_COV_DATA)

§

DATA64(DATA64_DATA)

§

CUBEPILOT_FIRMWARE_UPDATE_RESP(CUBEPILOT_FIRMWARE_UPDATE_RESP_DATA)

§

STATUSTEXT(STATUSTEXT_DATA)

§

MISSION_WRITE_PARTIAL_LIST(MISSION_WRITE_PARTIAL_LIST_DATA)

§

HIL_STATE_QUATERNION(HIL_STATE_QUATERNION_DATA)

§

ESC_INFO(ESC_INFO_DATA)

§

ESC_TELEMETRY_1_TO_4(ESC_TELEMETRY_1_TO_4_DATA)

§

OSD_PARAM_SHOW_CONFIG_REPLY(OSD_PARAM_SHOW_CONFIG_REPLY_DATA)

§

GLOBAL_POSITION_INT(GLOBAL_POSITION_INT_DATA)

§

GOPRO_SET_REQUEST(GOPRO_SET_REQUEST_DATA)

§

GIMBAL_REPORT(GIMBAL_REPORT_DATA)

§

NAMED_VALUE_FLOAT(NAMED_VALUE_FLOAT_DATA)

§

SET_HOME_POSITION(SET_HOME_POSITION_DATA)

§

REMOTE_LOG_DATA_BLOCK(REMOTE_LOG_DATA_BLOCK_DATA)

§

DEEPSTALL(DEEPSTALL_DATA)

§

DEVICE_OP_READ_REPLY(DEVICE_OP_READ_REPLY_DATA)

§

WIND_COV(WIND_COV_DATA)

§

DEBUG(DEBUG_DATA)

§

DATA_STREAM(DATA_STREAM_DATA)

§

LOG_REQUEST_END(LOG_REQUEST_END_DATA)

§

SIM_STATE(SIM_STATE_DATA)

§

ACTUATOR_CONTROL_TARGET(ACTUATOR_CONTROL_TARGET_DATA)

§

DIGICAM_CONTROL(DIGICAM_CONTROL_DATA)

§

SET_MAG_OFFSETS(SET_MAG_OFFSETS_DATA)

§

HIL_ACTUATOR_CONTROLS(HIL_ACTUATOR_CONTROLS_DATA)

§

CAMERA_TRACKING_GEO_STATUS(CAMERA_TRACKING_GEO_STATUS_DATA)

§

GIMBAL_MANAGER_SET_MANUAL_CONTROL(GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA)

§

COMMAND_CANCEL(COMMAND_CANCEL_DATA)

§

VICON_POSITION_ESTIMATE(VICON_POSITION_ESTIMATE_DATA)

§

CAMERA_SETTINGS(CAMERA_SETTINGS_DATA)

§

NAMED_VALUE_INT(NAMED_VALUE_INT_DATA)

§

PLAY_TUNE(PLAY_TUNE_DATA)

§

ESC_TELEMETRY_9_TO_12(ESC_TELEMETRY_9_TO_12_DATA)

§

SCALED_PRESSURE(SCALED_PRESSURE_DATA)

§

GOPRO_GET_REQUEST(GOPRO_GET_REQUEST_DATA)

§

SET_ACTUATOR_CONTROL_TARGET(SET_ACTUATOR_CONTROL_TARGET_DATA)

§

POSITION_TARGET_LOCAL_NED(POSITION_TARGET_LOCAL_NED_DATA)

§

GIMBAL_MANAGER_STATUS(GIMBAL_MANAGER_STATUS_DATA)

§

DEBUG_FLOAT_ARRAY(DEBUG_FLOAT_ARRAY_DATA)

§

MANUAL_CONTROL(MANUAL_CONTROL_DATA)

§

OBSTACLE_DISTANCE_3D(OBSTACLE_DISTANCE_3D_DATA)

§

TIMESYNC(TIMESYNC_DATA)

§

VISION_SPEED_ESTIMATE(VISION_SPEED_ESTIMATE_DATA)

§

CAN_FRAME(CAN_FRAME_DATA)

§

FENCE_STATUS(FENCE_STATUS_DATA)

§

OBSTACLE_DISTANCE(OBSTACLE_DISTANCE_DATA)

§

VFR_HUD(VFR_HUD_DATA)

§

UTM_GLOBAL_POSITION(UTM_GLOBAL_POSITION_DATA)

§

BATTERY_STATUS(BATTERY_STATUS_DATA)

§

VISION_POSITION_DELTA(VISION_POSITION_DELTA_DATA)

§

HIGHRES_IMU(HIGHRES_IMU_DATA)

§

SCALED_PRESSURE2(SCALED_PRESSURE2_DATA)

§

RC_CHANNELS_OVERRIDE(RC_CHANNELS_OVERRIDE_DATA)

§

AUTOPILOT_VERSION(AUTOPILOT_VERSION_DATA)

§

LANDING_TARGET(LANDING_TARGET_DATA)

§

AOA_SSA(AOA_SSA_DATA)

§

DEBUG_VECT(DEBUG_VECT_DATA)

§

UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT(UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA)

§

EKF_STATUS_REPORT(EKF_STATUS_REPORT_DATA)

§

ACTUATOR_OUTPUT_STATUS(ACTUATOR_OUTPUT_STATUS_DATA)

§

GPS_INPUT(GPS_INPUT_DATA)

§

REMOTE_LOG_BLOCK_STATUS(REMOTE_LOG_BLOCK_STATUS_DATA)

§

FENCE_FETCH_POINT(FENCE_FETCH_POINT_DATA)

§

DEVICE_OP_READ(DEVICE_OP_READ_DATA)

§

V2_EXTENSION(V2_EXTENSION_DATA)

§

OSD_PARAM_CONFIG(OSD_PARAM_CONFIG_DATA)

§

VISION_POSITION_ESTIMATE(VISION_POSITION_ESTIMATE_DATA)

§

POSITION_TARGET_GLOBAL_INT(POSITION_TARGET_GLOBAL_INT_DATA)

§

GPS_STATUS(GPS_STATUS_DATA)

§

OPEN_DRONE_ID_SYSTEM(OPEN_DRONE_ID_SYSTEM_DATA)

§

AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA)

§

ENCAPSULATED_DATA(ENCAPSULATED_DATA_DATA)

§

OSD_PARAM_SHOW_CONFIG(OSD_PARAM_SHOW_CONFIG_DATA)

§

CAMERA_INFORMATION(CAMERA_INFORMATION_DATA)

§

COMPONENT_INFORMATION(COMPONENT_INFORMATION_DATA)

§

SET_GPS_GLOBAL_ORIGIN(SET_GPS_GLOBAL_ORIGIN_DATA)

§

MISSION_CURRENT(MISSION_CURRENT_DATA)

§

OPEN_DRONE_ID_LOCATION(OPEN_DRONE_ID_LOCATION_DATA)

§

ESTIMATOR_STATUS(ESTIMATOR_STATUS_DATA)

§

PARAM_VALUE(PARAM_VALUE_DATA)

§

GIMBAL_DEVICE_ATTITUDE_STATUS(GIMBAL_DEVICE_ATTITUDE_STATUS_DATA)

§

AP_ADC(AP_ADC_DATA)

§

HIL_GPS(HIL_GPS_DATA)

§

LOGGING_DATA_ACKED(LOGGING_DATA_ACKED_DATA)

§

GIMBAL_CONTROL(GIMBAL_CONTROL_DATA)

§

TERRAIN_DATA(TERRAIN_DATA_DATA)

§

EFI_STATUS(EFI_STATUS_DATA)

§

ESC_STATUS(ESC_STATUS_DATA)

§

MISSION_ITEM_REACHED(MISSION_ITEM_REACHED_DATA)

§

MISSION_REQUEST_LIST(MISSION_REQUEST_LIST_DATA)

§

UAVIONIX_ADSB_OUT_DYNAMIC(UAVIONIX_ADSB_OUT_DYNAMIC_DATA)

§

SYSTEM_TIME(SYSTEM_TIME_DATA)

§

ICAROUS_HEARTBEAT(ICAROUS_HEARTBEAT_DATA)

§

CAMERA_FEEDBACK(CAMERA_FEEDBACK_DATA)

§

LED_CONTROL(LED_CONTROL_DATA)

§

UAVIONIX_ADSB_OUT_CFG(UAVIONIX_ADSB_OUT_CFG_DATA)

§

OPEN_DRONE_ID_SYSTEM_UPDATE(OPEN_DRONE_ID_SYSTEM_UPDATE_DATA)

§

TUNNEL(TUNNEL_DATA)

§

POWER_STATUS(POWER_STATUS_DATA)

§

RAW_IMU(RAW_IMU_DATA)

§

CUBEPILOT_RAW_RC(CUBEPILOT_RAW_RC_DATA)

§

OPEN_DRONE_ID_MESSAGE_PACK(OPEN_DRONE_ID_MESSAGE_PACK_DATA)

§

PARAM_EXT_REQUEST_READ(PARAM_EXT_REQUEST_READ_DATA)

§

HIL_SENSOR(HIL_SENSOR_DATA)

§

CURRENT_EVENT_SEQUENCE(CURRENT_EVENT_SEQUENCE_DATA)

§

LOG_ENTRY(LOG_ENTRY_DATA)

§

GENERATOR_STATUS(GENERATOR_STATUS_DATA)

§

ADSB_VEHICLE(ADSB_VEHICLE_DATA)

§

FOLLOW_TARGET(FOLLOW_TARGET_DATA)

§

ATTITUDE_QUATERNION(ATTITUDE_QUATERNION_DATA)

§

PARAM_REQUEST_LIST(PARAM_REQUEST_LIST_DATA)

§

AIRSPEED_AUTOCAL(AIRSPEED_AUTOCAL_DATA)

§

MISSION_REQUEST(MISSION_REQUEST_DATA)

§

MCU_STATUS(MCU_STATUS_DATA)

§

OPEN_DRONE_ID_ARM_STATUS(OPEN_DRONE_ID_ARM_STATUS_DATA)

§

PING(PING_DATA)

§

HYGROMETER_SENSOR(HYGROMETER_SENSOR_DATA)

§

SETUP_SIGNING(SETUP_SIGNING_DATA)

§

MEMORY_VECT(MEMORY_VECT_DATA)

§

OPEN_DRONE_ID_OPERATOR_ID(OPEN_DRONE_ID_OPERATOR_ID_DATA)

§

SCALED_IMU(SCALED_IMU_DATA)

§

ALTITUDE(ALTITUDE_DATA)

§

LOGGING_ACK(LOGGING_ACK_DATA)

§

RC_CHANNELS_SCALED(RC_CHANNELS_SCALED_DATA)

§

AHRS(AHRS_DATA)

§

CHANGE_OPERATOR_CONTROL(CHANGE_OPERATOR_CONTROL_DATA)

§

RANGEFINDER(RANGEFINDER_DATA)

§

SMART_BATTERY_INFO(SMART_BATTERY_INFO_DATA)

§

PARAM_EXT_ACK(PARAM_EXT_ACK_DATA)

§

GOPRO_SET_RESPONSE(GOPRO_SET_RESPONSE_DATA)

§

EVENT(EVENT_DATA)

§

GPS_INJECT_DATA(GPS_INJECT_DATA_DATA)

§

ADAP_TUNING(ADAP_TUNING_DATA)

§

GPS_GLOBAL_ORIGIN(GPS_GLOBAL_ORIGIN_DATA)

§

SERVO_OUTPUT_RAW(SERVO_OUTPUT_RAW_DATA)

§

PROTOCOL_VERSION(PROTOCOL_VERSION_DATA)

§

CANFD_FRAME(CANFD_FRAME_DATA)

§

GPS_RTK(GPS_RTK_DATA)

§

ONBOARD_COMPUTER_STATUS(ONBOARD_COMPUTER_STATUS_DATA)

§

TERRAIN_CHECK(TERRAIN_CHECK_DATA)

§

PLAY_TUNE_V2(PLAY_TUNE_V2_DATA)

§

CAN_FILTER_MODIFY(CAN_FILTER_MODIFY_DATA)

§

GPS2_RAW(GPS2_RAW_DATA)

§

UAVCAN_NODE_INFO(UAVCAN_NODE_INFO_DATA)

§

HIGH_LATENCY(HIGH_LATENCY_DATA)

§

TERRAIN_REQUEST(TERRAIN_REQUEST_DATA)

§

SCALED_IMU3(SCALED_IMU3_DATA)

§

RALLY_FETCH_POINT(RALLY_FETCH_POINT_DATA)

§

LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA)

§

RAW_PRESSURE(RAW_PRESSURE_DATA)

§

LOG_REQUEST_DATA(LOG_REQUEST_DATA_DATA)

§

GPS_RAW_INT(GPS_RAW_INT_DATA)

§

RC_CHANNELS_RAW(RC_CHANNELS_RAW_DATA)

§

VIDEO_STREAM_STATUS(VIDEO_STREAM_STATUS_DATA)

§

TRAJECTORY_REPRESENTATION_BEZIER(TRAJECTORY_REPRESENTATION_BEZIER_DATA)

§

LOG_ERASE(LOG_ERASE_DATA)

§

RAW_RPM(RAW_RPM_DATA)

§

ATTITUDE_QUATERNION_COV(ATTITUDE_QUATERNION_COV_DATA)

§

MESSAGE_INTERVAL(MESSAGE_INTERVAL_DATA)

§

MISSION_COUNT(MISSION_COUNT_DATA)

§

ORBIT_EXECUTION_STATUS(ORBIT_EXECUTION_STATUS_DATA)

§

GIMBAL_MANAGER_SET_ATTITUDE(GIMBAL_MANAGER_SET_ATTITUDE_DATA)

§

PID_TUNING(PID_TUNING_DATA)

§

CAMERA_STATUS(CAMERA_STATUS_DATA)

§

LIMITS_STATUS(LIMITS_STATUS_DATA)

§

FLIGHT_INFORMATION(FLIGHT_INFORMATION_DATA)

§

AHRS3(AHRS3_DATA)

§

SCALED_IMU2(SCALED_IMU2_DATA)

§

TRAJECTORY_REPRESENTATION_WAYPOINTS(TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA)

§

MISSION_REQUEST_INT(MISSION_REQUEST_INT_DATA)

§

ESC_TELEMETRY_5_TO_8(ESC_TELEMETRY_5_TO_8_DATA)

§

CAMERA_IMAGE_CAPTURED(CAMERA_IMAGE_CAPTURED_DATA)

§

SENSOR_OFFSETS(SENSOR_OFFSETS_DATA)

§

DEVICE_OP_WRITE_REPLY(DEVICE_OP_WRITE_REPLY_DATA)

§

SIMSTATE(SIMSTATE_DATA)

§

FILE_TRANSFER_PROTOCOL(FILE_TRANSFER_PROTOCOL_DATA)

§

WIND(WIND_DATA)

§

AUTOPILOT_VERSION_REQUEST(AUTOPILOT_VERSION_REQUEST_DATA)

§

CUBEPILOT_FIRMWARE_UPDATE_START(CUBEPILOT_FIRMWARE_UPDATE_START_DATA)

§

COMMAND_ACK(COMMAND_ACK_DATA)

§

SET_MODE(SET_MODE_DATA)

§

LOCAL_POSITION_NED(LOCAL_POSITION_NED_DATA)

§

RADIO_STATUS(RADIO_STATUS_DATA)

§

DIGICAM_CONFIGURE(DIGICAM_CONFIGURE_DATA)

§

CONTROL_SYSTEM_STATE(CONTROL_SYSTEM_STATE_DATA)

§

HIL_CONTROLS(HIL_CONTROLS_DATA)

§

STORAGE_INFORMATION(STORAGE_INFORMATION_DATA)

§

DATA32(DATA32_DATA)

§

GIMBAL_TORQUE_CMD_REPORT(GIMBAL_TORQUE_CMD_REPORT_DATA)

§

MISSION_REQUEST_PARTIAL_LIST(MISSION_REQUEST_PARTIAL_LIST_DATA)

§

TIME_ESTIMATE_TO_TARGET(TIME_ESTIMATE_TO_TARGET_DATA)

§

GIMBAL_DEVICE_INFORMATION(GIMBAL_DEVICE_INFORMATION_DATA)

§

EXTENDED_SYS_STATE(EXTENDED_SYS_STATE_DATA)

§

DATA_TRANSMISSION_HANDSHAKE(DATA_TRANSMISSION_HANDSHAKE_DATA)

§

HIL_OPTICAL_FLOW(HIL_OPTICAL_FLOW_DATA)

§

LOG_DATA(LOG_DATA_DATA)

§

MISSION_ITEM(MISSION_ITEM_DATA)

§

DEVICE_OP_WRITE(DEVICE_OP_WRITE_DATA)

§

MOUNT_STATUS(MOUNT_STATUS_DATA)

§

CAMERA_CAPTURE_STATUS(CAMERA_CAPTURE_STATUS_DATA)

§

HOME_POSITION(HOME_POSITION_DATA)

§

CAMERA_FOV_STATUS(CAMERA_FOV_STATUS_DATA)

§

SUPPORTED_TUNES(SUPPORTED_TUNES_DATA)

§

GIMBAL_MANAGER_SET_PITCHYAW(GIMBAL_MANAGER_SET_PITCHYAW_DATA)

§

COMMAND_LONG(COMMAND_LONG_DATA)

§

GPS2_RTK(GPS2_RTK_DATA)

§

PARAM_EXT_SET(PARAM_EXT_SET_DATA)

§

SET_ATTITUDE_TARGET(SET_ATTITUDE_TARGET_DATA)

§

GPS_RTCM_DATA(GPS_RTCM_DATA_DATA)

§

OPTICAL_FLOW(OPTICAL_FLOW_DATA)

§

MISSION_SET_CURRENT(MISSION_SET_CURRENT_DATA)

§

COMPONENT_METADATA(COMPONENT_METADATA_DATA)

§

PARAM_EXT_VALUE(PARAM_EXT_VALUE_DATA)

§

CELLULAR_CONFIG(CELLULAR_CONFIG_DATA)

§

GLOBAL_VISION_POSITION_ESTIMATE(GLOBAL_VISION_POSITION_ESTIMATE_DATA)

§

LOGGING_DATA(LOGGING_DATA_DATA)

§

VIDEO_STREAM_INFORMATION(VIDEO_STREAM_INFORMATION_DATA)

§

WIFI_CONFIG_AP(WIFI_CONFIG_AP_DATA)

§

RALLY_POINT(RALLY_POINT_DATA)

§

RESOURCE_REQUEST(RESOURCE_REQUEST_DATA)

§

MAG_CAL_PROGRESS(MAG_CAL_PROGRESS_DATA)

§

GLOBAL_POSITION_INT_COV(GLOBAL_POSITION_INT_COV_DATA)

§

RPM(RPM_DATA)

§

WHEEL_DISTANCE(WHEEL_DISTANCE_DATA)

§

CELLULAR_STATUS(CELLULAR_STATUS_DATA)

§

REQUEST_EVENT(REQUEST_EVENT_DATA)

§

AUTH_KEY(AUTH_KEY_DATA)

§

REQUEST_DATA_STREAM(REQUEST_DATA_STREAM_DATA)

§

SET_POSITION_TARGET_GLOBAL_INT(SET_POSITION_TARGET_GLOBAL_INT_DATA)

§

WINCH_STATUS(WINCH_STATUS_DATA)

§

WATER_DEPTH(WATER_DEPTH_DATA)

§

COMPASSMOT_STATUS(COMPASSMOT_STATUS_DATA)

§

HIL_STATE(HIL_STATE_DATA)

§

NAV_CONTROLLER_OUTPUT(NAV_CONTROLLER_OUTPUT_DATA)

§

LOG_REQUEST_LIST(LOG_REQUEST_LIST_DATA)

§

MISSION_ITEM_INT(MISSION_ITEM_INT_DATA)

§

HEARTBEAT(HEARTBEAT_DATA)

§

CAMERA_TRIGGER(CAMERA_TRIGGER_DATA)

§

ATT_POS_MOCAP(ATT_POS_MOCAP_DATA)

§

ATTITUDE(ATTITUDE_DATA)

§

ICAROUS_KINEMATIC_BANDS(ICAROUS_KINEMATIC_BANDS_DATA)

§

DATA16(DATA16_DATA)

§

GIMBAL_DEVICE_SET_ATTITUDE(GIMBAL_DEVICE_SET_ATTITUDE_DATA)

§

GOPRO_GET_RESPONSE(GOPRO_GET_RESPONSE_DATA)

§

SAFETY_ALLOWED_AREA(SAFETY_ALLOWED_AREA_DATA)

§

SET_POSITION_TARGET_LOCAL_NED(SET_POSITION_TARGET_LOCAL_NED_DATA)

§

BUTTON_CHANGE(BUTTON_CHANGE_DATA)

§

SERIAL_CONTROL(SERIAL_CONTROL_DATA)

§

MOUNT_CONFIGURE(MOUNT_CONFIGURE_DATA)

§

SCALED_PRESSURE3(SCALED_PRESSURE3_DATA)

§

CAMERA_TRACKING_IMAGE_STATUS(CAMERA_TRACKING_IMAGE_STATUS_DATA)

§

RC_CHANNELS(RC_CHANNELS_DATA)

§

AHRS2(AHRS2_DATA)

§

MAG_CAL_REPORT(MAG_CAL_REPORT_DATA)

§

MOUNT_ORIENTATION(MOUNT_ORIENTATION_DATA)

§

VIBRATION(VIBRATION_DATA)

§

GIMBAL_MANAGER_INFORMATION(GIMBAL_MANAGER_INFORMATION_DATA)

§

GOPRO_HEARTBEAT(GOPRO_HEARTBEAT_DATA)

§

OSD_PARAM_CONFIG_REPLY(OSD_PARAM_CONFIG_REPLY_DATA)

§

PARAM_REQUEST_READ(PARAM_REQUEST_READ_DATA)

§

OPTICAL_FLOW_RAD(OPTICAL_FLOW_RAD_DATA)

§

MISSION_ACK(MISSION_ACK_DATA)

§

RESPONSE_EVENT_ERROR(RESPONSE_EVENT_ERROR_DATA)

§

CHANGE_OPERATOR_CONTROL_ACK(CHANGE_OPERATOR_CONTROL_ACK_DATA)

§

MEMINFO(MEMINFO_DATA)

§

FENCE_POINT(FENCE_POINT_DATA)

§

DATA96(DATA96_DATA)

§

HWSTATUS(HWSTATUS_DATA)

§

PARAM_SET(PARAM_SET_DATA)

§

COLLISION(COLLISION_DATA)

§

BATTERY2(BATTERY2_DATA)

§

DISTANCE_SENSOR(DISTANCE_SENSOR_DATA)

§

ATTITUDE_TARGET(ATTITUDE_TARGET_DATA)

§

AIS_VESSEL(AIS_VESSEL_DATA)

§

SAFETY_SET_ALLOWED_AREA(SAFETY_SET_ALLOWED_AREA_DATA)

§

TERRAIN_REPORT(TERRAIN_REPORT_DATA)

§

ODOMETRY(ODOMETRY_DATA)

§

PARAM_EXT_REQUEST_LIST(PARAM_EXT_REQUEST_LIST_DATA)

§

OPEN_DRONE_ID_AUTHENTICATION(OPEN_DRONE_ID_AUTHENTICATION_DATA)

§

SYS_STATUS(SYS_STATUS_DATA)

§

UAVCAN_NODE_STATUS(UAVCAN_NODE_STATUS_DATA)

§

OPEN_DRONE_ID_SELF_ID(OPEN_DRONE_ID_SELF_ID_DATA)

§

OPEN_DRONE_ID_BASIC_ID(OPEN_DRONE_ID_BASIC_ID_DATA)

§

MANUAL_SETPOINT(MANUAL_SETPOINT_DATA)

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 Message for MavMessage

source§

fn parse( version: MavlinkVersion, id: u32, payload: &[u8] ) -> Result<Self, 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<Self, &'static str>

source§

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

Serialize Message into byte slice and return count of bytes written
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 Twhere T: 'static + ?Sized,

source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
source§

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

source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
source§

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

source§

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

Mutably borrows from an owned value. Read more
source§

impl<T> From<T> for T

source§

fn from(t: T) -> T

Returns the argument unchanged.

source§

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

source§

fn into(self) -> U

Calls U::from(self).

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

source§

impl<T> ToOwned for Twhere T: Clone,

§

type Owned = T

The resulting type after obtaining ownership.
source§

fn to_owned(&self) -> T

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

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

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

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

§

type Error = Infallible

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

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

Performs the conversion.
source§

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

§

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

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

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

Performs the conversion.
source§

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