Enum MavMessage

Source
#[repr(u32)]
pub enum MavMessage {
Show 241 variants SUPPORTED_TUNES(SUPPORTED_TUNES_DATA), CAN_FILTER_MODIFY(CAN_FILTER_MODIFY_DATA), TERRAIN_DATA(TERRAIN_DATA_DATA), CURRENT_EVENT_SEQUENCE(CURRENT_EVENT_SEQUENCE_DATA), TUNNEL(TUNNEL_DATA), CHANGE_OPERATOR_CONTROL_ACK(CHANGE_OPERATOR_CONTROL_ACK_DATA), GPS_RTK(GPS_RTK_DATA), LOG_ERASE(LOG_ERASE_DATA), TIME_ESTIMATE_TO_TARGET(TIME_ESTIMATE_TO_TARGET_DATA), LOG_REQUEST_END(LOG_REQUEST_END_DATA), SET_HOME_POSITION(SET_HOME_POSITION_DATA), MISSION_ITEM_INT(MISSION_ITEM_INT_DATA), FOLLOW_TARGET(FOLLOW_TARGET_DATA), ADSB_VEHICLE(ADSB_VEHICLE_DATA), UTM_GLOBAL_POSITION(UTM_GLOBAL_POSITION_DATA), DATA_TRANSMISSION_HANDSHAKE(DATA_TRANSMISSION_HANDSHAKE_DATA), VISION_POSITION_ESTIMATE(VISION_POSITION_ESTIMATE_DATA), GPS_STATUS(GPS_STATUS_DATA), CAMERA_FOV_STATUS(CAMERA_FOV_STATUS_DATA), GPS_INJECT_DATA(GPS_INJECT_DATA_DATA), LANDING_TARGET(LANDING_TARGET_DATA), ALTITUDE(ALTITUDE_DATA), MISSION_REQUEST_LIST(MISSION_REQUEST_LIST_DATA), BATTERY_INFO(BATTERY_INFO_DATA), LOGGING_DATA(LOGGING_DATA_DATA), SCALED_IMU(SCALED_IMU_DATA), OPEN_DRONE_ID_SYSTEM(OPEN_DRONE_ID_SYSTEM_DATA), BUTTON_CHANGE(BUTTON_CHANGE_DATA), TIMESYNC(TIMESYNC_DATA), SERIAL_CONTROL(SERIAL_CONTROL_DATA), MISSION_ITEM_REACHED(MISSION_ITEM_REACHED_DATA), AUTOPILOT_VERSION(AUTOPILOT_VERSION_DATA), ESTIMATOR_STATUS(ESTIMATOR_STATUS_DATA), GIMBAL_MANAGER_SET_ATTITUDE(GIMBAL_MANAGER_SET_ATTITUDE_DATA), OPEN_DRONE_ID_MESSAGE_PACK(OPEN_DRONE_ID_MESSAGE_PACK_DATA), SMART_BATTERY_INFO(SMART_BATTERY_INFO_DATA), SCALED_PRESSURE(SCALED_PRESSURE_DATA), GIMBAL_MANAGER_SET_PITCHYAW(GIMBAL_MANAGER_SET_PITCHYAW_DATA), NAMED_VALUE_FLOAT(NAMED_VALUE_FLOAT_DATA), SCALED_PRESSURE2(SCALED_PRESSURE2_DATA), CAN_FRAME(CAN_FRAME_DATA), DEBUG_VECT(DEBUG_VECT_DATA), BATTERY_STATUS_V2(BATTERY_STATUS_V2_DATA), ODOMETRY(ODOMETRY_DATA), PARAM_EXT_ACK(PARAM_EXT_ACK_DATA), SCALED_PRESSURE3(SCALED_PRESSURE3_DATA), PLAY_TUNE_V2(PLAY_TUNE_V2_DATA), LINK_NODE_STATUS(LINK_NODE_STATUS_DATA), DEBUG_FLOAT_ARRAY(DEBUG_FLOAT_ARRAY_DATA), HIGH_LATENCY2(HIGH_LATENCY2_DATA), V2_EXTENSION(V2_EXTENSION_DATA), TERRAIN_REQUEST(TERRAIN_REQUEST_DATA), LOCAL_POSITION_NED_COV(LOCAL_POSITION_NED_COV_DATA), CHANGE_OPERATOR_CONTROL(CHANGE_OPERATOR_CONTROL_DATA), GPS_RTCM_DATA(GPS_RTCM_DATA_DATA), NAMED_VALUE_INT(NAMED_VALUE_INT_DATA), HIL_STATE_QUATERNION(HIL_STATE_QUATERNION_DATA), PARAM_EXT_SET(PARAM_EXT_SET_DATA), VISION_SPEED_ESTIMATE(VISION_SPEED_ESTIMATE_DATA), MISSION_REQUEST(MISSION_REQUEST_DATA), MESSAGE_INTERVAL(MESSAGE_INTERVAL_DATA), ATTITUDE_QUATERNION_COV(ATTITUDE_QUATERNION_COV_DATA), AVAILABLE_MODES_MONITOR(AVAILABLE_MODES_MONITOR_DATA), MEMORY_VECT(MEMORY_VECT_DATA), HIL_SENSOR(HIL_SENSOR_DATA), COMPONENT_METADATA(COMPONENT_METADATA_DATA), FUEL_STATUS(FUEL_STATUS_DATA), CAMERA_INFORMATION(CAMERA_INFORMATION_DATA), AVAILABLE_MODES(AVAILABLE_MODES_DATA), MISSION_REQUEST_INT(MISSION_REQUEST_INT_DATA), GROUP_START(GROUP_START_DATA), TARGET_RELATIVE(TARGET_RELATIVE_DATA), GPS_RAW_INT(GPS_RAW_INT_DATA), TERRAIN_CHECK(TERRAIN_CHECK_DATA), TRAJECTORY_REPRESENTATION_BEZIER(TRAJECTORY_REPRESENTATION_BEZIER_DATA), PLAY_TUNE(PLAY_TUNE_DATA), SETUP_SIGNING(SETUP_SIGNING_DATA), MANUAL_CONTROL(MANUAL_CONTROL_DATA), RC_CHANNELS_RAW(RC_CHANNELS_RAW_DATA), GENERATOR_STATUS(GENERATOR_STATUS_DATA), TERRAIN_REPORT(TERRAIN_REPORT_DATA), OPEN_DRONE_ID_SELF_ID(OPEN_DRONE_ID_SELF_ID_DATA), UAVCAN_NODE_STATUS(UAVCAN_NODE_STATUS_DATA), RADIO_RC_CHANNELS(RADIO_RC_CHANNELS_DATA), CAMERA_CAPTURE_STATUS(CAMERA_CAPTURE_STATUS_DATA), MISSION_REQUEST_PARTIAL_LIST(MISSION_REQUEST_PARTIAL_LIST_DATA), FILE_TRANSFER_PROTOCOL(FILE_TRANSFER_PROTOCOL_DATA), AIS_VESSEL(AIS_VESSEL_DATA), MISSION_CLEAR_ALL(MISSION_CLEAR_ALL_DATA), DEBUG(DEBUG_DATA), COMMAND_INT(COMMAND_INT_DATA), GPS2_RAW(GPS2_RAW_DATA), UAVCAN_NODE_INFO(UAVCAN_NODE_INFO_DATA), MANUAL_SETPOINT(MANUAL_SETPOINT_DATA), GIMBAL_DEVICE_INFORMATION(GIMBAL_DEVICE_INFORMATION_DATA), GPS2_RTK(GPS2_RTK_DATA), ESC_STATUS(ESC_STATUS_DATA), PROTOCOL_VERSION(PROTOCOL_VERSION_DATA), TARGET_ABSOLUTE(TARGET_ABSOLUTE_DATA), MISSION_ACK(MISSION_ACK_DATA), RADIO_STATUS(RADIO_STATUS_DATA), CAMERA_SETTINGS(CAMERA_SETTINGS_DATA), HIL_CONTROLS(HIL_CONTROLS_DATA), VELOCITY_LIMITS(VELOCITY_LIMITS_DATA), RC_CHANNELS(RC_CHANNELS_DATA), OPTICAL_FLOW(OPTICAL_FLOW_DATA), RAW_IMU(RAW_IMU_DATA), POSITION_TARGET_GLOBAL_INT(POSITION_TARGET_GLOBAL_INT_DATA), POWER_STATUS(POWER_STATUS_DATA), OPEN_DRONE_ID_BASIC_ID(OPEN_DRONE_ID_BASIC_ID_DATA), GLOBAL_POSITION_INT_COV(GLOBAL_POSITION_INT_COV_DATA), CELLULAR_CONFIG(CELLULAR_CONFIG_DATA), RC_CHANNELS_SCALED(RC_CHANNELS_SCALED_DATA), WIFI_CONFIG_AP(WIFI_CONFIG_AP_DATA), EXTENDED_SYS_STATE(EXTENDED_SYS_STATE_DATA), VIBRATION(VIBRATION_DATA), SCALED_IMU2(SCALED_IMU2_DATA), AUTH_KEY(AUTH_KEY_DATA), ATT_POS_MOCAP(ATT_POS_MOCAP_DATA), EFI_STATUS(EFI_STATUS_DATA), CAMERA_TRACKING_GEO_STATUS(CAMERA_TRACKING_GEO_STATUS_DATA), SCALED_IMU3(SCALED_IMU3_DATA), MAG_CAL_REPORT(MAG_CAL_REPORT_DATA), OPEN_DRONE_ID_LOCATION(OPEN_DRONE_ID_LOCATION_DATA), SET_VELOCITY_LIMITS(SET_VELOCITY_LIMITS_DATA), VFR_HUD(VFR_HUD_DATA), HOME_POSITION(HOME_POSITION_DATA), SIM_STATE(SIM_STATE_DATA), ONBOARD_COMPUTER_STATUS(ONBOARD_COMPUTER_STATUS_DATA), ACTUATOR_CONTROL_TARGET(ACTUATOR_CONTROL_TARGET_DATA), GPS_INPUT(GPS_INPUT_DATA), CONTROL_SYSTEM_STATE(CONTROL_SYSTEM_STATE_DATA), PARAM_EXT_VALUE(PARAM_EXT_VALUE_DATA), RC_CHANNELS_OVERRIDE(RC_CHANNELS_OVERRIDE_DATA), CAMERA_TRACKING_IMAGE_STATUS(CAMERA_TRACKING_IMAGE_STATUS_DATA), FENCE_STATUS(FENCE_STATUS_DATA), OPEN_DRONE_ID_SYSTEM_UPDATE(OPEN_DRONE_ID_SYSTEM_UPDATE_DATA), MISSION_CURRENT(MISSION_CURRENT_DATA), HIL_RC_INPUTS_RAW(HIL_RC_INPUTS_RAW_DATA), DISTANCE_SENSOR(DISTANCE_SENSOR_DATA), PARAM_REQUEST_LIST(PARAM_REQUEST_LIST_DATA), WINCH_STATUS(WINCH_STATUS_DATA), TRAJECTORY_REPRESENTATION_WAYPOINTS(TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA), GROUP_END(GROUP_END_DATA), REQUEST_DATA_STREAM(REQUEST_DATA_STREAM_DATA), SET_MODE(SET_MODE_DATA), CAMERA_TRIGGER(CAMERA_TRIGGER_DATA), RAW_RPM(RAW_RPM_DATA), RESPONSE_EVENT_ERROR(RESPONSE_EVENT_ERROR_DATA), RAW_PRESSURE(RAW_PRESSURE_DATA), COMPONENT_INFORMATION_BASIC(COMPONENT_INFORMATION_BASIC_DATA), VICON_POSITION_ESTIMATE(VICON_POSITION_ESTIMATE_DATA), MISSION_COUNT(MISSION_COUNT_DATA), PARAM_SET(PARAM_SET_DATA), FIGURE_EIGHT_EXECUTION_STATUS(FIGURE_EIGHT_EXECUTION_STATUS_DATA), CONTROL_STATUS(CONTROL_STATUS_DATA), ESC_INFO(ESC_INFO_DATA), CAMERA_IMAGE_CAPTURED(CAMERA_IMAGE_CAPTURED_DATA), PARAM_MAP_RC(PARAM_MAP_RC_DATA), ORBIT_EXECUTION_STATUS(ORBIT_EXECUTION_STATUS_DATA), ENCAPSULATED_DATA(ENCAPSULATED_DATA_DATA), COMMAND_LONG(COMMAND_LONG_DATA), LOGGING_DATA_ACKED(LOGGING_DATA_ACKED_DATA), COMMAND_ACK(COMMAND_ACK_DATA), CANFD_FRAME(CANFD_FRAME_DATA), SET_ATTITUDE_TARGET(SET_ATTITUDE_TARGET_DATA), GNSS_INTEGRITY(GNSS_INTEGRITY_DATA), LOG_DATA(LOG_DATA_DATA), RESOURCE_REQUEST(RESOURCE_REQUEST_DATA), OPEN_DRONE_ID_OPERATOR_ID(OPEN_DRONE_ID_OPERATOR_ID_DATA), HIL_STATE(HIL_STATE_DATA), LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA), HEARTBEAT(HEARTBEAT_DATA), SET_GPS_GLOBAL_ORIGIN(SET_GPS_GLOBAL_ORIGIN_DATA), COMMAND_CANCEL(COMMAND_CANCEL_DATA), LOG_ENTRY(LOG_ENTRY_DATA), EVENT(EVENT_DATA), HIL_ACTUATOR_CONTROLS(HIL_ACTUATOR_CONTROLS_DATA), HIL_OPTICAL_FLOW(HIL_OPTICAL_FLOW_DATA), COMPONENT_INFORMATION(COMPONENT_INFORMATION_DATA), NAV_CONTROLLER_OUTPUT(NAV_CONTROLLER_OUTPUT_DATA), ATTITUDE_TARGET(ATTITUDE_TARGET_DATA), OPEN_DRONE_ID_AUTHENTICATION(OPEN_DRONE_ID_AUTHENTICATION_DATA), HYGROMETER_SENSOR(HYGROMETER_SENSOR_DATA), GIMBAL_DEVICE_ATTITUDE_STATUS(GIMBAL_DEVICE_ATTITUDE_STATUS_DATA), SYSTEM_TIME(SYSTEM_TIME_DATA), AIRSPEED(AIRSPEED_DATA), MISSION_ITEM(MISSION_ITEM_DATA), GIMBAL_MANAGER_INFORMATION(GIMBAL_MANAGER_INFORMATION_DATA), PARAM_EXT_REQUEST_READ(PARAM_EXT_REQUEST_READ_DATA), HIL_GPS(HIL_GPS_DATA), VIDEO_STREAM_STATUS(VIDEO_STREAM_STATUS_DATA), LOGGING_ACK(LOGGING_ACK_DATA), CAMERA_THERMAL_RANGE(CAMERA_THERMAL_RANGE_DATA), ATTITUDE(ATTITUDE_DATA), GIMBAL_MANAGER_STATUS(GIMBAL_MANAGER_STATUS_DATA), SYS_STATUS(SYS_STATUS_DATA), ACTUATOR_OUTPUT_STATUS(ACTUATOR_OUTPUT_STATUS_DATA), OPTICAL_FLOW_RAD(OPTICAL_FLOW_RAD_DATA), GLOBAL_VISION_POSITION_ESTIMATE(GLOBAL_VISION_POSITION_ESTIMATE_DATA), WHEEL_DISTANCE(WHEEL_DISTANCE_DATA), HIGHRES_IMU(HIGHRES_IMU_DATA), OBSTACLE_DISTANCE(OBSTACLE_DISTANCE_DATA), SAFETY_SET_ALLOWED_AREA(SAFETY_SET_ALLOWED_AREA_DATA), DATA_STREAM(DATA_STREAM_DATA), OPEN_DRONE_ID_ARM_STATUS(OPEN_DRONE_ID_ARM_STATUS_DATA), CURRENT_MODE(CURRENT_MODE_DATA), SET_POSITION_TARGET_LOCAL_NED(SET_POSITION_TARGET_LOCAL_NED_DATA), GIMBAL_DEVICE_SET_ATTITUDE(GIMBAL_DEVICE_SET_ATTITUDE_DATA), MOUNT_ORIENTATION(MOUNT_ORIENTATION_DATA), STORAGE_INFORMATION(STORAGE_INFORMATION_DATA), SAFETY_ALLOWED_AREA(SAFETY_ALLOWED_AREA_DATA), FLIGHT_INFORMATION(FLIGHT_INFORMATION_DATA), GIMBAL_MANAGER_SET_MANUAL_CONTROL(GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA), WIND_COV(WIND_COV_DATA), LOG_REQUEST_LIST(LOG_REQUEST_LIST_DATA), PARAM_VALUE(PARAM_VALUE_DATA), PARAM_REQUEST_READ(PARAM_REQUEST_READ_DATA), LOCAL_POSITION_NED(LOCAL_POSITION_NED_DATA), HIGH_LATENCY(HIGH_LATENCY_DATA), PING(PING_DATA), POSITION_TARGET_LOCAL_NED(POSITION_TARGET_LOCAL_NED_DATA), ATTITUDE_QUATERNION(ATTITUDE_QUATERNION_DATA), STATUSTEXT(STATUSTEXT_DATA), ILLUMINATOR_STATUS(ILLUMINATOR_STATUS_DATA), GLOBAL_POSITION_INT(GLOBAL_POSITION_INT_DATA), VIDEO_STREAM_INFORMATION(VIDEO_STREAM_INFORMATION_DATA), MISSION_WRITE_PARTIAL_LIST(MISSION_WRITE_PARTIAL_LIST_DATA), MISSION_SET_CURRENT(MISSION_SET_CURRENT_DATA), PARAM_EXT_REQUEST_LIST(PARAM_EXT_REQUEST_LIST_DATA), CELLULAR_STATUS(CELLULAR_STATUS_DATA), COLLISION(COLLISION_DATA), SERVO_OUTPUT_RAW(SERVO_OUTPUT_RAW_DATA), LOG_REQUEST_DATA(LOG_REQUEST_DATA_DATA), AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA), SET_ACTUATOR_CONTROL_TARGET(SET_ACTUATOR_CONTROL_TARGET_DATA), BATTERY_STATUS(BATTERY_STATUS_DATA), REQUEST_EVENT(REQUEST_EVENT_DATA), ISBD_LINK_STATUS(ISBD_LINK_STATUS_DATA), SET_POSITION_TARGET_GLOBAL_INT(SET_POSITION_TARGET_GLOBAL_INT_DATA), GPS_GLOBAL_ORIGIN(GPS_GLOBAL_ORIGIN_DATA),
}
Available on crate feature development only.

Variantsยง

ยง

SUPPORTED_TUNES(SUPPORTED_TUNES_DATA)

ยง

CAN_FILTER_MODIFY(CAN_FILTER_MODIFY_DATA)

ยง

TERRAIN_DATA(TERRAIN_DATA_DATA)

ยง

CURRENT_EVENT_SEQUENCE(CURRENT_EVENT_SEQUENCE_DATA)

ยง

TUNNEL(TUNNEL_DATA)

ยง

CHANGE_OPERATOR_CONTROL_ACK(CHANGE_OPERATOR_CONTROL_ACK_DATA)

ยง

GPS_RTK(GPS_RTK_DATA)

ยง

LOG_ERASE(LOG_ERASE_DATA)

ยง

TIME_ESTIMATE_TO_TARGET(TIME_ESTIMATE_TO_TARGET_DATA)

ยง

LOG_REQUEST_END(LOG_REQUEST_END_DATA)

ยง

SET_HOME_POSITION(SET_HOME_POSITION_DATA)

ยง

MISSION_ITEM_INT(MISSION_ITEM_INT_DATA)

ยง

FOLLOW_TARGET(FOLLOW_TARGET_DATA)

ยง

ADSB_VEHICLE(ADSB_VEHICLE_DATA)

ยง

UTM_GLOBAL_POSITION(UTM_GLOBAL_POSITION_DATA)

ยง

DATA_TRANSMISSION_HANDSHAKE(DATA_TRANSMISSION_HANDSHAKE_DATA)

ยง

VISION_POSITION_ESTIMATE(VISION_POSITION_ESTIMATE_DATA)

ยง

GPS_STATUS(GPS_STATUS_DATA)

ยง

CAMERA_FOV_STATUS(CAMERA_FOV_STATUS_DATA)

ยง

GPS_INJECT_DATA(GPS_INJECT_DATA_DATA)

ยง

LANDING_TARGET(LANDING_TARGET_DATA)

ยง

ALTITUDE(ALTITUDE_DATA)

ยง

MISSION_REQUEST_LIST(MISSION_REQUEST_LIST_DATA)

ยง

BATTERY_INFO(BATTERY_INFO_DATA)

ยง

LOGGING_DATA(LOGGING_DATA_DATA)

ยง

SCALED_IMU(SCALED_IMU_DATA)

ยง

OPEN_DRONE_ID_SYSTEM(OPEN_DRONE_ID_SYSTEM_DATA)

ยง

BUTTON_CHANGE(BUTTON_CHANGE_DATA)

ยง

TIMESYNC(TIMESYNC_DATA)

ยง

SERIAL_CONTROL(SERIAL_CONTROL_DATA)

ยง

MISSION_ITEM_REACHED(MISSION_ITEM_REACHED_DATA)

ยง

AUTOPILOT_VERSION(AUTOPILOT_VERSION_DATA)

ยง

ESTIMATOR_STATUS(ESTIMATOR_STATUS_DATA)

ยง

GIMBAL_MANAGER_SET_ATTITUDE(GIMBAL_MANAGER_SET_ATTITUDE_DATA)

ยง

OPEN_DRONE_ID_MESSAGE_PACK(OPEN_DRONE_ID_MESSAGE_PACK_DATA)

ยง

SMART_BATTERY_INFO(SMART_BATTERY_INFO_DATA)

ยง

SCALED_PRESSURE(SCALED_PRESSURE_DATA)

ยง

GIMBAL_MANAGER_SET_PITCHYAW(GIMBAL_MANAGER_SET_PITCHYAW_DATA)

ยง

NAMED_VALUE_FLOAT(NAMED_VALUE_FLOAT_DATA)

ยง

SCALED_PRESSURE2(SCALED_PRESSURE2_DATA)

ยง

CAN_FRAME(CAN_FRAME_DATA)

ยง

DEBUG_VECT(DEBUG_VECT_DATA)

ยง

BATTERY_STATUS_V2(BATTERY_STATUS_V2_DATA)

ยง

ODOMETRY(ODOMETRY_DATA)

ยง

PARAM_EXT_ACK(PARAM_EXT_ACK_DATA)

ยง

SCALED_PRESSURE3(SCALED_PRESSURE3_DATA)

ยง

PLAY_TUNE_V2(PLAY_TUNE_V2_DATA)

ยง

DEBUG_FLOAT_ARRAY(DEBUG_FLOAT_ARRAY_DATA)

ยง

HIGH_LATENCY2(HIGH_LATENCY2_DATA)

ยง

V2_EXTENSION(V2_EXTENSION_DATA)

ยง

TERRAIN_REQUEST(TERRAIN_REQUEST_DATA)

ยง

LOCAL_POSITION_NED_COV(LOCAL_POSITION_NED_COV_DATA)

ยง

CHANGE_OPERATOR_CONTROL(CHANGE_OPERATOR_CONTROL_DATA)

ยง

GPS_RTCM_DATA(GPS_RTCM_DATA_DATA)

ยง

NAMED_VALUE_INT(NAMED_VALUE_INT_DATA)

ยง

HIL_STATE_QUATERNION(HIL_STATE_QUATERNION_DATA)

ยง

PARAM_EXT_SET(PARAM_EXT_SET_DATA)

ยง

VISION_SPEED_ESTIMATE(VISION_SPEED_ESTIMATE_DATA)

ยง

MISSION_REQUEST(MISSION_REQUEST_DATA)

ยง

MESSAGE_INTERVAL(MESSAGE_INTERVAL_DATA)

ยง

ATTITUDE_QUATERNION_COV(ATTITUDE_QUATERNION_COV_DATA)

ยง

AVAILABLE_MODES_MONITOR(AVAILABLE_MODES_MONITOR_DATA)

ยง

MEMORY_VECT(MEMORY_VECT_DATA)

ยง

HIL_SENSOR(HIL_SENSOR_DATA)

ยง

COMPONENT_METADATA(COMPONENT_METADATA_DATA)

ยง

FUEL_STATUS(FUEL_STATUS_DATA)

ยง

CAMERA_INFORMATION(CAMERA_INFORMATION_DATA)

ยง

AVAILABLE_MODES(AVAILABLE_MODES_DATA)

ยง

MISSION_REQUEST_INT(MISSION_REQUEST_INT_DATA)

ยง

GROUP_START(GROUP_START_DATA)

ยง

TARGET_RELATIVE(TARGET_RELATIVE_DATA)

ยง

GPS_RAW_INT(GPS_RAW_INT_DATA)

ยง

TERRAIN_CHECK(TERRAIN_CHECK_DATA)

ยง

TRAJECTORY_REPRESENTATION_BEZIER(TRAJECTORY_REPRESENTATION_BEZIER_DATA)

ยง

PLAY_TUNE(PLAY_TUNE_DATA)

ยง

SETUP_SIGNING(SETUP_SIGNING_DATA)

ยง

MANUAL_CONTROL(MANUAL_CONTROL_DATA)

ยง

RC_CHANNELS_RAW(RC_CHANNELS_RAW_DATA)

ยง

GENERATOR_STATUS(GENERATOR_STATUS_DATA)

ยง

TERRAIN_REPORT(TERRAIN_REPORT_DATA)

ยง

OPEN_DRONE_ID_SELF_ID(OPEN_DRONE_ID_SELF_ID_DATA)

ยง

UAVCAN_NODE_STATUS(UAVCAN_NODE_STATUS_DATA)

ยง

RADIO_RC_CHANNELS(RADIO_RC_CHANNELS_DATA)

ยง

CAMERA_CAPTURE_STATUS(CAMERA_CAPTURE_STATUS_DATA)

ยง

MISSION_REQUEST_PARTIAL_LIST(MISSION_REQUEST_PARTIAL_LIST_DATA)

ยง

FILE_TRANSFER_PROTOCOL(FILE_TRANSFER_PROTOCOL_DATA)

ยง

AIS_VESSEL(AIS_VESSEL_DATA)

ยง

MISSION_CLEAR_ALL(MISSION_CLEAR_ALL_DATA)

ยง

DEBUG(DEBUG_DATA)

ยง

COMMAND_INT(COMMAND_INT_DATA)

ยง

GPS2_RAW(GPS2_RAW_DATA)

ยง

UAVCAN_NODE_INFO(UAVCAN_NODE_INFO_DATA)

ยง

MANUAL_SETPOINT(MANUAL_SETPOINT_DATA)

ยง

GIMBAL_DEVICE_INFORMATION(GIMBAL_DEVICE_INFORMATION_DATA)

ยง

GPS2_RTK(GPS2_RTK_DATA)

ยง

ESC_STATUS(ESC_STATUS_DATA)

ยง

PROTOCOL_VERSION(PROTOCOL_VERSION_DATA)

ยง

TARGET_ABSOLUTE(TARGET_ABSOLUTE_DATA)

ยง

MISSION_ACK(MISSION_ACK_DATA)

ยง

RADIO_STATUS(RADIO_STATUS_DATA)

ยง

CAMERA_SETTINGS(CAMERA_SETTINGS_DATA)

ยง

HIL_CONTROLS(HIL_CONTROLS_DATA)

ยง

VELOCITY_LIMITS(VELOCITY_LIMITS_DATA)

ยง

RC_CHANNELS(RC_CHANNELS_DATA)

ยง

OPTICAL_FLOW(OPTICAL_FLOW_DATA)

ยง

RAW_IMU(RAW_IMU_DATA)

ยง

POSITION_TARGET_GLOBAL_INT(POSITION_TARGET_GLOBAL_INT_DATA)

ยง

POWER_STATUS(POWER_STATUS_DATA)

ยง

OPEN_DRONE_ID_BASIC_ID(OPEN_DRONE_ID_BASIC_ID_DATA)

ยง

GLOBAL_POSITION_INT_COV(GLOBAL_POSITION_INT_COV_DATA)

ยง

CELLULAR_CONFIG(CELLULAR_CONFIG_DATA)

ยง

RC_CHANNELS_SCALED(RC_CHANNELS_SCALED_DATA)

ยง

WIFI_CONFIG_AP(WIFI_CONFIG_AP_DATA)

ยง

EXTENDED_SYS_STATE(EXTENDED_SYS_STATE_DATA)

ยง

VIBRATION(VIBRATION_DATA)

ยง

SCALED_IMU2(SCALED_IMU2_DATA)

ยง

AUTH_KEY(AUTH_KEY_DATA)

ยง

ATT_POS_MOCAP(ATT_POS_MOCAP_DATA)

ยง

EFI_STATUS(EFI_STATUS_DATA)

ยง

CAMERA_TRACKING_GEO_STATUS(CAMERA_TRACKING_GEO_STATUS_DATA)

ยง

SCALED_IMU3(SCALED_IMU3_DATA)

ยง

MAG_CAL_REPORT(MAG_CAL_REPORT_DATA)

ยง

OPEN_DRONE_ID_LOCATION(OPEN_DRONE_ID_LOCATION_DATA)

ยง

SET_VELOCITY_LIMITS(SET_VELOCITY_LIMITS_DATA)

ยง

VFR_HUD(VFR_HUD_DATA)

ยง

HOME_POSITION(HOME_POSITION_DATA)

ยง

SIM_STATE(SIM_STATE_DATA)

ยง

ONBOARD_COMPUTER_STATUS(ONBOARD_COMPUTER_STATUS_DATA)

ยง

ACTUATOR_CONTROL_TARGET(ACTUATOR_CONTROL_TARGET_DATA)

ยง

GPS_INPUT(GPS_INPUT_DATA)

ยง

CONTROL_SYSTEM_STATE(CONTROL_SYSTEM_STATE_DATA)

ยง

PARAM_EXT_VALUE(PARAM_EXT_VALUE_DATA)

ยง

RC_CHANNELS_OVERRIDE(RC_CHANNELS_OVERRIDE_DATA)

ยง

CAMERA_TRACKING_IMAGE_STATUS(CAMERA_TRACKING_IMAGE_STATUS_DATA)

ยง

FENCE_STATUS(FENCE_STATUS_DATA)

ยง

OPEN_DRONE_ID_SYSTEM_UPDATE(OPEN_DRONE_ID_SYSTEM_UPDATE_DATA)

ยง

MISSION_CURRENT(MISSION_CURRENT_DATA)

ยง

HIL_RC_INPUTS_RAW(HIL_RC_INPUTS_RAW_DATA)

ยง

DISTANCE_SENSOR(DISTANCE_SENSOR_DATA)

ยง

PARAM_REQUEST_LIST(PARAM_REQUEST_LIST_DATA)

ยง

WINCH_STATUS(WINCH_STATUS_DATA)

ยง

TRAJECTORY_REPRESENTATION_WAYPOINTS(TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA)

ยง

GROUP_END(GROUP_END_DATA)

ยง

REQUEST_DATA_STREAM(REQUEST_DATA_STREAM_DATA)

ยง

SET_MODE(SET_MODE_DATA)

ยง

CAMERA_TRIGGER(CAMERA_TRIGGER_DATA)

ยง

RAW_RPM(RAW_RPM_DATA)

ยง

RESPONSE_EVENT_ERROR(RESPONSE_EVENT_ERROR_DATA)

ยง

RAW_PRESSURE(RAW_PRESSURE_DATA)

ยง

COMPONENT_INFORMATION_BASIC(COMPONENT_INFORMATION_BASIC_DATA)

ยง

VICON_POSITION_ESTIMATE(VICON_POSITION_ESTIMATE_DATA)

ยง

MISSION_COUNT(MISSION_COUNT_DATA)

ยง

PARAM_SET(PARAM_SET_DATA)

ยง

FIGURE_EIGHT_EXECUTION_STATUS(FIGURE_EIGHT_EXECUTION_STATUS_DATA)

ยง

CONTROL_STATUS(CONTROL_STATUS_DATA)

ยง

ESC_INFO(ESC_INFO_DATA)

ยง

CAMERA_IMAGE_CAPTURED(CAMERA_IMAGE_CAPTURED_DATA)

ยง

PARAM_MAP_RC(PARAM_MAP_RC_DATA)

ยง

ORBIT_EXECUTION_STATUS(ORBIT_EXECUTION_STATUS_DATA)

ยง

ENCAPSULATED_DATA(ENCAPSULATED_DATA_DATA)

ยง

COMMAND_LONG(COMMAND_LONG_DATA)

ยง

LOGGING_DATA_ACKED(LOGGING_DATA_ACKED_DATA)

ยง

COMMAND_ACK(COMMAND_ACK_DATA)

ยง

CANFD_FRAME(CANFD_FRAME_DATA)

ยง

SET_ATTITUDE_TARGET(SET_ATTITUDE_TARGET_DATA)

ยง

GNSS_INTEGRITY(GNSS_INTEGRITY_DATA)

ยง

LOG_DATA(LOG_DATA_DATA)

ยง

RESOURCE_REQUEST(RESOURCE_REQUEST_DATA)

ยง

OPEN_DRONE_ID_OPERATOR_ID(OPEN_DRONE_ID_OPERATOR_ID_DATA)

ยง

HIL_STATE(HIL_STATE_DATA)

ยง

LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA)

ยง

HEARTBEAT(HEARTBEAT_DATA)

ยง

SET_GPS_GLOBAL_ORIGIN(SET_GPS_GLOBAL_ORIGIN_DATA)

ยง

COMMAND_CANCEL(COMMAND_CANCEL_DATA)

ยง

LOG_ENTRY(LOG_ENTRY_DATA)

ยง

EVENT(EVENT_DATA)

ยง

HIL_ACTUATOR_CONTROLS(HIL_ACTUATOR_CONTROLS_DATA)

ยง

HIL_OPTICAL_FLOW(HIL_OPTICAL_FLOW_DATA)

ยง

COMPONENT_INFORMATION(COMPONENT_INFORMATION_DATA)

ยง

NAV_CONTROLLER_OUTPUT(NAV_CONTROLLER_OUTPUT_DATA)

ยง

ATTITUDE_TARGET(ATTITUDE_TARGET_DATA)

ยง

OPEN_DRONE_ID_AUTHENTICATION(OPEN_DRONE_ID_AUTHENTICATION_DATA)

ยง

HYGROMETER_SENSOR(HYGROMETER_SENSOR_DATA)

ยง

GIMBAL_DEVICE_ATTITUDE_STATUS(GIMBAL_DEVICE_ATTITUDE_STATUS_DATA)

ยง

SYSTEM_TIME(SYSTEM_TIME_DATA)

ยง

AIRSPEED(AIRSPEED_DATA)

ยง

MISSION_ITEM(MISSION_ITEM_DATA)

ยง

GIMBAL_MANAGER_INFORMATION(GIMBAL_MANAGER_INFORMATION_DATA)

ยง

PARAM_EXT_REQUEST_READ(PARAM_EXT_REQUEST_READ_DATA)

ยง

HIL_GPS(HIL_GPS_DATA)

ยง

VIDEO_STREAM_STATUS(VIDEO_STREAM_STATUS_DATA)

ยง

LOGGING_ACK(LOGGING_ACK_DATA)

ยง

CAMERA_THERMAL_RANGE(CAMERA_THERMAL_RANGE_DATA)

ยง

ATTITUDE(ATTITUDE_DATA)

ยง

GIMBAL_MANAGER_STATUS(GIMBAL_MANAGER_STATUS_DATA)

ยง

SYS_STATUS(SYS_STATUS_DATA)

ยง

ACTUATOR_OUTPUT_STATUS(ACTUATOR_OUTPUT_STATUS_DATA)

ยง

OPTICAL_FLOW_RAD(OPTICAL_FLOW_RAD_DATA)

ยง

GLOBAL_VISION_POSITION_ESTIMATE(GLOBAL_VISION_POSITION_ESTIMATE_DATA)

ยง

WHEEL_DISTANCE(WHEEL_DISTANCE_DATA)

ยง

HIGHRES_IMU(HIGHRES_IMU_DATA)

ยง

OBSTACLE_DISTANCE(OBSTACLE_DISTANCE_DATA)

ยง

SAFETY_SET_ALLOWED_AREA(SAFETY_SET_ALLOWED_AREA_DATA)

ยง

DATA_STREAM(DATA_STREAM_DATA)

ยง

OPEN_DRONE_ID_ARM_STATUS(OPEN_DRONE_ID_ARM_STATUS_DATA)

ยง

CURRENT_MODE(CURRENT_MODE_DATA)

ยง

SET_POSITION_TARGET_LOCAL_NED(SET_POSITION_TARGET_LOCAL_NED_DATA)

ยง

GIMBAL_DEVICE_SET_ATTITUDE(GIMBAL_DEVICE_SET_ATTITUDE_DATA)

ยง

MOUNT_ORIENTATION(MOUNT_ORIENTATION_DATA)

ยง

STORAGE_INFORMATION(STORAGE_INFORMATION_DATA)

ยง

SAFETY_ALLOWED_AREA(SAFETY_ALLOWED_AREA_DATA)

ยง

FLIGHT_INFORMATION(FLIGHT_INFORMATION_DATA)

ยง

GIMBAL_MANAGER_SET_MANUAL_CONTROL(GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA)

ยง

WIND_COV(WIND_COV_DATA)

ยง

LOG_REQUEST_LIST(LOG_REQUEST_LIST_DATA)

ยง

PARAM_VALUE(PARAM_VALUE_DATA)

ยง

PARAM_REQUEST_READ(PARAM_REQUEST_READ_DATA)

ยง

LOCAL_POSITION_NED(LOCAL_POSITION_NED_DATA)

ยง

HIGH_LATENCY(HIGH_LATENCY_DATA)

ยง

PING(PING_DATA)

ยง

POSITION_TARGET_LOCAL_NED(POSITION_TARGET_LOCAL_NED_DATA)

ยง

ATTITUDE_QUATERNION(ATTITUDE_QUATERNION_DATA)

ยง

STATUSTEXT(STATUSTEXT_DATA)

ยง

ILLUMINATOR_STATUS(ILLUMINATOR_STATUS_DATA)

ยง

GLOBAL_POSITION_INT(GLOBAL_POSITION_INT_DATA)

ยง

VIDEO_STREAM_INFORMATION(VIDEO_STREAM_INFORMATION_DATA)

ยง

MISSION_WRITE_PARTIAL_LIST(MISSION_WRITE_PARTIAL_LIST_DATA)

ยง

MISSION_SET_CURRENT(MISSION_SET_CURRENT_DATA)

ยง

PARAM_EXT_REQUEST_LIST(PARAM_EXT_REQUEST_LIST_DATA)

ยง

CELLULAR_STATUS(CELLULAR_STATUS_DATA)

ยง

COLLISION(COLLISION_DATA)

ยง

SERVO_OUTPUT_RAW(SERVO_OUTPUT_RAW_DATA)

ยง

LOG_REQUEST_DATA(LOG_REQUEST_DATA_DATA)

ยง

AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA)

ยง

SET_ACTUATOR_CONTROL_TARGET(SET_ACTUATOR_CONTROL_TARGET_DATA)

ยง

BATTERY_STATUS(BATTERY_STATUS_DATA)

ยง

REQUEST_EVENT(REQUEST_EVENT_DATA)

ยง

SET_POSITION_TARGET_GLOBAL_INT(SET_POSITION_TARGET_GLOBAL_INT_DATA)

ยง

GPS_GLOBAL_ORIGIN(GPS_GLOBAL_ORIGIN_DATA)

Trait Implementationsยง

Sourceยง

impl Clone for MavMessage

Sourceยง

fn clone(&self) -> MavMessage

Returns a duplicate 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>

Parse a Message from its message id and payload bytes
Sourceยง

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

MAVLink message name
Sourceยง

fn message_id(&self) -> u32

MAVLink message ID
Sourceยง

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

Return message id of specific message name
Sourceยง

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

Return a default message of the speicfied message id
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

Return a message types CRC_EXTRA byte
Sourceยง

impl PartialEq for MavMessage

Sourceยง

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

Tests for self and other values to be equal, and is used by ==.
1.0.0 ยท Sourceยง

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

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> CloneToUninit for T
where T: Clone,

Sourceยง

unsafe fn clone_to_uninit(&self, dest: *mut u8)

๐Ÿ”ฌThis is a nightly-only experimental API. (clone_to_uninit)
Performs copy-assignment from self to dest. 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> Same for T

Sourceยง

type Output = T

Should always be Self
Sourceยง

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

Sourceยง

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>,

Sourceยง

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>,

Sourceยง

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>,