├── .github └── workflows │ └── update.yml ├── LICENSE.txt ├── MAVLink.h ├── MAVLink_ASLUAV.h ├── MAVLink_AVSSUAS.h ├── MAVLink_all.h ├── MAVLink_ardupilotmega.h ├── MAVLink_common.h ├── MAVLink_csAirLink.h ├── MAVLink_cubepilot.h ├── MAVLink_development.h ├── MAVLink_icarous.h ├── MAVLink_matrixpilot.h ├── MAVLink_minimal.h ├── MAVLink_paparazzi.h ├── MAVLink_standard.h ├── MAVLink_storm32.h ├── MAVLink_test.h ├── MAVLink_uAvionix.h ├── MAVLink_ualberta.h ├── README.md ├── examples ├── HeartbeatSender │ └── HeartbeatSender.ino └── WiFiMAVLink │ └── WiFiMAVLink.ino ├── library.properties ├── mavlink ├── ASLUAV │ ├── ASLUAV.h │ ├── mavlink.h │ ├── mavlink_msg_asl_obctrl.h │ ├── mavlink_msg_aslctrl_data.h │ ├── mavlink_msg_aslctrl_debug.h │ ├── mavlink_msg_asluav_status.h │ ├── mavlink_msg_command_int_stamped.h │ ├── mavlink_msg_command_long_stamped.h │ ├── mavlink_msg_ekf_ext.h │ ├── mavlink_msg_fw_soaring_data.h │ ├── mavlink_msg_gsm_link_status.h │ ├── mavlink_msg_satcom_link_status.h │ ├── mavlink_msg_sens_atmos.h │ ├── mavlink_msg_sens_batmon.h │ ├── mavlink_msg_sens_mppt.h │ ├── mavlink_msg_sens_power.h │ ├── mavlink_msg_sens_power_board.h │ ├── mavlink_msg_sensor_airflow_angles.h │ ├── mavlink_msg_sensorpod_status.h │ ├── testsuite.h │ └── version.h ├── AVSSUAS │ ├── AVSSUAS.h │ ├── mavlink.h │ ├── mavlink_msg_avss_drone_imu.h │ ├── mavlink_msg_avss_drone_operation_mode.h │ ├── mavlink_msg_avss_drone_position.h │ ├── mavlink_msg_avss_prs_sys_status.h │ ├── testsuite.h │ └── version.h ├── all │ ├── all.h │ ├── mavlink.h │ ├── testsuite.h │ └── version.h ├── ardupilotmega │ ├── ardupilotmega.h │ ├── mavlink.h │ ├── mavlink_msg_adap_tuning.h │ ├── mavlink_msg_ahrs.h │ ├── mavlink_msg_ahrs2.h │ ├── mavlink_msg_ahrs3.h │ ├── mavlink_msg_airspeed_autocal.h │ ├── mavlink_msg_aoa_ssa.h │ ├── mavlink_msg_ap_adc.h │ ├── mavlink_msg_autopilot_version_request.h │ ├── mavlink_msg_battery2.h │ ├── mavlink_msg_camera_feedback.h │ ├── mavlink_msg_camera_status.h │ ├── mavlink_msg_compassmot_status.h │ ├── mavlink_msg_data16.h │ ├── mavlink_msg_data32.h │ ├── mavlink_msg_data64.h │ ├── mavlink_msg_data96.h │ ├── mavlink_msg_deepstall.h │ ├── mavlink_msg_device_op_read.h │ ├── mavlink_msg_device_op_read_reply.h │ ├── mavlink_msg_device_op_write.h │ ├── mavlink_msg_device_op_write_reply.h │ ├── mavlink_msg_digicam_configure.h │ ├── mavlink_msg_digicam_control.h │ ├── mavlink_msg_ekf_status_report.h │ ├── mavlink_msg_esc_telemetry_13_to_16.h │ ├── mavlink_msg_esc_telemetry_17_to_20.h │ ├── mavlink_msg_esc_telemetry_1_to_4.h │ ├── mavlink_msg_esc_telemetry_21_to_24.h │ ├── mavlink_msg_esc_telemetry_25_to_28.h │ ├── mavlink_msg_esc_telemetry_29_to_32.h │ ├── mavlink_msg_esc_telemetry_5_to_8.h │ ├── mavlink_msg_esc_telemetry_9_to_12.h │ ├── mavlink_msg_fence_fetch_point.h │ ├── mavlink_msg_fence_point.h │ ├── mavlink_msg_gimbal_control.h │ ├── mavlink_msg_gimbal_report.h │ ├── mavlink_msg_gimbal_torque_cmd_report.h │ ├── mavlink_msg_gopro_get_request.h │ ├── mavlink_msg_gopro_get_response.h │ ├── mavlink_msg_gopro_heartbeat.h │ ├── mavlink_msg_gopro_set_request.h │ ├── mavlink_msg_gopro_set_response.h │ ├── mavlink_msg_hwstatus.h │ ├── mavlink_msg_led_control.h │ ├── mavlink_msg_limits_status.h │ ├── mavlink_msg_mag_cal_progress.h │ ├── mavlink_msg_mcu_status.h │ ├── mavlink_msg_meminfo.h │ ├── mavlink_msg_mount_configure.h │ ├── mavlink_msg_mount_control.h │ ├── mavlink_msg_mount_status.h │ ├── mavlink_msg_obstacle_distance_3d.h │ ├── mavlink_msg_osd_param_config.h │ ├── mavlink_msg_osd_param_config_reply.h │ ├── mavlink_msg_osd_param_show_config.h │ ├── mavlink_msg_osd_param_show_config_reply.h │ ├── mavlink_msg_pid_tuning.h │ ├── mavlink_msg_radio.h │ ├── mavlink_msg_rally_fetch_point.h │ ├── mavlink_msg_rally_point.h │ ├── mavlink_msg_rangefinder.h │ ├── mavlink_msg_remote_log_block_status.h │ ├── mavlink_msg_remote_log_data_block.h │ ├── mavlink_msg_rpm.h │ ├── mavlink_msg_secure_command.h │ ├── mavlink_msg_secure_command_reply.h │ ├── mavlink_msg_sensor_offsets.h │ ├── mavlink_msg_set_mag_offsets.h │ ├── mavlink_msg_simstate.h │ ├── mavlink_msg_vision_position_delta.h │ ├── mavlink_msg_water_depth.h │ ├── mavlink_msg_wind.h │ ├── testsuite.h │ └── version.h ├── checksum.h ├── common │ ├── common.h │ ├── mavlink.h │ ├── mavlink_msg_actuator_control_target.h │ ├── mavlink_msg_actuator_output_status.h │ ├── mavlink_msg_adsb_vehicle.h │ ├── mavlink_msg_ais_vessel.h │ ├── mavlink_msg_altitude.h │ ├── mavlink_msg_att_pos_mocap.h │ ├── mavlink_msg_attitude.h │ ├── mavlink_msg_attitude_quaternion.h │ ├── mavlink_msg_attitude_quaternion_cov.h │ ├── mavlink_msg_attitude_target.h │ ├── mavlink_msg_auth_key.h │ ├── mavlink_msg_autopilot_state_for_gimbal_device.h │ ├── mavlink_msg_autopilot_version.h │ ├── mavlink_msg_available_modes.h │ ├── mavlink_msg_available_modes_monitor.h │ ├── mavlink_msg_battery_info.h │ ├── mavlink_msg_battery_status.h │ ├── mavlink_msg_button_change.h │ ├── mavlink_msg_camera_capture_status.h │ ├── mavlink_msg_camera_fov_status.h │ ├── mavlink_msg_camera_image_captured.h │ ├── mavlink_msg_camera_information.h │ ├── mavlink_msg_camera_settings.h │ ├── mavlink_msg_camera_thermal_range.h │ ├── mavlink_msg_camera_tracking_geo_status.h │ ├── mavlink_msg_camera_tracking_image_status.h │ ├── mavlink_msg_camera_trigger.h │ ├── mavlink_msg_can_filter_modify.h │ ├── mavlink_msg_can_frame.h │ ├── mavlink_msg_canfd_frame.h │ ├── mavlink_msg_cellular_config.h │ ├── mavlink_msg_cellular_status.h │ ├── mavlink_msg_change_operator_control.h │ ├── mavlink_msg_change_operator_control_ack.h │ ├── mavlink_msg_collision.h │ ├── mavlink_msg_command_ack.h │ ├── mavlink_msg_command_cancel.h │ ├── mavlink_msg_command_int.h │ ├── mavlink_msg_command_long.h │ ├── mavlink_msg_component_information.h │ ├── mavlink_msg_component_information_basic.h │ ├── mavlink_msg_component_metadata.h │ ├── mavlink_msg_control_system_state.h │ ├── mavlink_msg_current_event_sequence.h │ ├── mavlink_msg_current_mode.h │ ├── mavlink_msg_data_stream.h │ ├── mavlink_msg_data_transmission_handshake.h │ ├── mavlink_msg_debug.h │ ├── mavlink_msg_debug_float_array.h │ ├── mavlink_msg_debug_vect.h │ ├── mavlink_msg_distance_sensor.h │ ├── mavlink_msg_efi_status.h │ ├── mavlink_msg_encapsulated_data.h │ ├── mavlink_msg_esc_info.h │ ├── mavlink_msg_esc_status.h │ ├── mavlink_msg_estimator_status.h │ ├── mavlink_msg_event.h │ ├── mavlink_msg_extended_sys_state.h │ ├── mavlink_msg_fence_status.h │ ├── mavlink_msg_file_transfer_protocol.h │ ├── mavlink_msg_flight_information.h │ ├── mavlink_msg_follow_target.h │ ├── mavlink_msg_fuel_status.h │ ├── mavlink_msg_generator_status.h │ ├── mavlink_msg_gimbal_device_attitude_status.h │ ├── mavlink_msg_gimbal_device_information.h │ ├── mavlink_msg_gimbal_device_set_attitude.h │ ├── mavlink_msg_gimbal_manager_information.h │ ├── mavlink_msg_gimbal_manager_set_attitude.h │ ├── mavlink_msg_gimbal_manager_set_manual_control.h │ ├── mavlink_msg_gimbal_manager_set_pitchyaw.h │ ├── mavlink_msg_gimbal_manager_status.h │ ├── mavlink_msg_global_position_int.h │ ├── mavlink_msg_global_position_int_cov.h │ ├── mavlink_msg_global_vision_position_estimate.h │ ├── mavlink_msg_gps2_raw.h │ ├── mavlink_msg_gps2_rtk.h │ ├── mavlink_msg_gps_global_origin.h │ ├── mavlink_msg_gps_inject_data.h │ ├── mavlink_msg_gps_input.h │ ├── mavlink_msg_gps_raw_int.h │ ├── mavlink_msg_gps_rtcm_data.h │ ├── mavlink_msg_gps_rtk.h │ ├── mavlink_msg_gps_status.h │ ├── mavlink_msg_high_latency.h │ ├── mavlink_msg_high_latency2.h │ ├── mavlink_msg_highres_imu.h │ ├── mavlink_msg_hil_actuator_controls.h │ ├── mavlink_msg_hil_controls.h │ ├── mavlink_msg_hil_gps.h │ ├── mavlink_msg_hil_optical_flow.h │ ├── mavlink_msg_hil_rc_inputs_raw.h │ ├── mavlink_msg_hil_sensor.h │ ├── mavlink_msg_hil_state.h │ ├── mavlink_msg_hil_state_quaternion.h │ ├── mavlink_msg_home_position.h │ ├── mavlink_msg_hygrometer_sensor.h │ ├── mavlink_msg_illuminator_status.h │ ├── mavlink_msg_isbd_link_status.h │ ├── mavlink_msg_landing_target.h │ ├── mavlink_msg_link_node_status.h │ ├── mavlink_msg_local_position_ned.h │ ├── mavlink_msg_local_position_ned_cov.h │ ├── mavlink_msg_local_position_ned_system_global_offset.h │ ├── mavlink_msg_log_data.h │ ├── mavlink_msg_log_entry.h │ ├── mavlink_msg_log_erase.h │ ├── mavlink_msg_log_request_data.h │ ├── mavlink_msg_log_request_end.h │ ├── mavlink_msg_log_request_list.h │ ├── mavlink_msg_logging_ack.h │ ├── mavlink_msg_logging_data.h │ ├── mavlink_msg_logging_data_acked.h │ ├── mavlink_msg_mag_cal_report.h │ ├── mavlink_msg_manual_control.h │ ├── mavlink_msg_manual_setpoint.h │ ├── mavlink_msg_memory_vect.h │ ├── mavlink_msg_message_interval.h │ ├── mavlink_msg_mission_ack.h │ ├── mavlink_msg_mission_clear_all.h │ ├── mavlink_msg_mission_count.h │ ├── mavlink_msg_mission_current.h │ ├── mavlink_msg_mission_item.h │ ├── mavlink_msg_mission_item_int.h │ ├── mavlink_msg_mission_item_reached.h │ ├── mavlink_msg_mission_request.h │ ├── mavlink_msg_mission_request_int.h │ ├── mavlink_msg_mission_request_list.h │ ├── mavlink_msg_mission_request_partial_list.h │ ├── mavlink_msg_mission_set_current.h │ ├── mavlink_msg_mission_write_partial_list.h │ ├── mavlink_msg_mount_orientation.h │ ├── mavlink_msg_named_value_float.h │ ├── mavlink_msg_named_value_int.h │ ├── mavlink_msg_nav_controller_output.h │ ├── mavlink_msg_obstacle_distance.h │ ├── mavlink_msg_odometry.h │ ├── mavlink_msg_onboard_computer_status.h │ ├── mavlink_msg_open_drone_id_arm_status.h │ ├── mavlink_msg_open_drone_id_authentication.h │ ├── mavlink_msg_open_drone_id_basic_id.h │ ├── mavlink_msg_open_drone_id_location.h │ ├── mavlink_msg_open_drone_id_message_pack.h │ ├── mavlink_msg_open_drone_id_operator_id.h │ ├── mavlink_msg_open_drone_id_self_id.h │ ├── mavlink_msg_open_drone_id_system.h │ ├── mavlink_msg_open_drone_id_system_update.h │ ├── mavlink_msg_optical_flow.h │ ├── mavlink_msg_optical_flow_rad.h │ ├── mavlink_msg_orbit_execution_status.h │ ├── mavlink_msg_param_ext_ack.h │ ├── mavlink_msg_param_ext_request_list.h │ ├── mavlink_msg_param_ext_request_read.h │ ├── mavlink_msg_param_ext_set.h │ ├── mavlink_msg_param_ext_value.h │ ├── mavlink_msg_param_map_rc.h │ ├── mavlink_msg_param_request_list.h │ ├── mavlink_msg_param_request_read.h │ ├── mavlink_msg_param_set.h │ ├── mavlink_msg_param_value.h │ ├── mavlink_msg_ping.h │ ├── mavlink_msg_play_tune.h │ ├── mavlink_msg_play_tune_v2.h │ ├── mavlink_msg_position_target_global_int.h │ ├── mavlink_msg_position_target_local_ned.h │ ├── mavlink_msg_power_status.h │ ├── mavlink_msg_radio_status.h │ ├── mavlink_msg_raw_imu.h │ ├── mavlink_msg_raw_pressure.h │ ├── mavlink_msg_raw_rpm.h │ ├── mavlink_msg_rc_channels.h │ ├── mavlink_msg_rc_channels_override.h │ ├── mavlink_msg_rc_channels_raw.h │ ├── mavlink_msg_rc_channels_scaled.h │ ├── mavlink_msg_request_data_stream.h │ ├── mavlink_msg_request_event.h │ ├── mavlink_msg_resource_request.h │ ├── mavlink_msg_response_event_error.h │ ├── mavlink_msg_safety_allowed_area.h │ ├── mavlink_msg_safety_set_allowed_area.h │ ├── mavlink_msg_scaled_imu.h │ ├── mavlink_msg_scaled_imu2.h │ ├── mavlink_msg_scaled_imu3.h │ ├── mavlink_msg_scaled_pressure.h │ ├── mavlink_msg_scaled_pressure2.h │ ├── mavlink_msg_scaled_pressure3.h │ ├── mavlink_msg_serial_control.h │ ├── mavlink_msg_servo_output_raw.h │ ├── mavlink_msg_set_actuator_control_target.h │ ├── mavlink_msg_set_attitude_target.h │ ├── mavlink_msg_set_gps_global_origin.h │ ├── mavlink_msg_set_home_position.h │ ├── mavlink_msg_set_mode.h │ ├── mavlink_msg_set_position_target_global_int.h │ ├── mavlink_msg_set_position_target_local_ned.h │ ├── mavlink_msg_setup_signing.h │ ├── mavlink_msg_sim_state.h │ ├── mavlink_msg_smart_battery_info.h │ ├── mavlink_msg_statustext.h │ ├── mavlink_msg_storage_information.h │ ├── mavlink_msg_supported_tunes.h │ ├── mavlink_msg_sys_status.h │ ├── mavlink_msg_system_time.h │ ├── mavlink_msg_terrain_check.h │ ├── mavlink_msg_terrain_data.h │ ├── mavlink_msg_terrain_report.h │ ├── mavlink_msg_terrain_request.h │ ├── mavlink_msg_time_estimate_to_target.h │ ├── mavlink_msg_timesync.h │ ├── mavlink_msg_trajectory_representation_bezier.h │ ├── mavlink_msg_trajectory_representation_waypoints.h │ ├── mavlink_msg_tunnel.h │ ├── mavlink_msg_uavcan_node_info.h │ ├── mavlink_msg_uavcan_node_status.h │ ├── mavlink_msg_utm_global_position.h │ ├── mavlink_msg_v2_extension.h │ ├── mavlink_msg_vfr_hud.h │ ├── mavlink_msg_vibration.h │ ├── mavlink_msg_vicon_position_estimate.h │ ├── mavlink_msg_video_stream_information.h │ ├── mavlink_msg_video_stream_status.h │ ├── mavlink_msg_vision_position_estimate.h │ ├── mavlink_msg_vision_speed_estimate.h │ ├── mavlink_msg_wheel_distance.h │ ├── mavlink_msg_wifi_config_ap.h │ ├── mavlink_msg_winch_status.h │ ├── mavlink_msg_wind_cov.h │ ├── testsuite.h │ └── version.h ├── csAirLink │ ├── csAirLink.h │ ├── mavlink.h │ ├── mavlink_msg_airlink_auth.h │ ├── mavlink_msg_airlink_auth_response.h │ ├── testsuite.h │ └── version.h ├── cubepilot │ ├── cubepilot.h │ ├── mavlink.h │ ├── mavlink_msg_cubepilot_firmware_update_resp.h │ ├── mavlink_msg_cubepilot_firmware_update_start.h │ ├── mavlink_msg_cubepilot_raw_rc.h │ ├── mavlink_msg_herelink_telem.h │ ├── mavlink_msg_herelink_video_stream_information.h │ ├── testsuite.h │ └── version.h ├── development │ ├── development.h │ ├── mavlink.h │ ├── mavlink_msg_airspeed.h │ ├── mavlink_msg_battery_status_v2.h │ ├── mavlink_msg_control_status.h │ ├── mavlink_msg_figure_eight_execution_status.h │ ├── mavlink_msg_gnss_integrity.h │ ├── mavlink_msg_group_end.h │ ├── mavlink_msg_group_start.h │ ├── mavlink_msg_radio_rc_channels.h │ ├── mavlink_msg_set_velocity_limits.h │ ├── mavlink_msg_target_absolute.h │ ├── mavlink_msg_target_relative.h │ ├── mavlink_msg_velocity_limits.h │ ├── testsuite.h │ └── version.h ├── icarous │ ├── icarous.h │ ├── mavlink.h │ ├── mavlink_msg_icarous_heartbeat.h │ ├── mavlink_msg_icarous_kinematic_bands.h │ ├── testsuite.h │ └── version.h ├── loweheiser │ ├── loweheiser.h │ ├── mavlink.h │ ├── mavlink_msg_loweheiser_gov_efi.h │ ├── testsuite.h │ └── version.h ├── matrixpilot │ ├── matrixpilot.h │ ├── mavlink.h │ ├── mavlink_msg_airspeeds.h │ ├── mavlink_msg_altitudes.h │ ├── mavlink_msg_flexifunction_buffer_function.h │ ├── mavlink_msg_flexifunction_buffer_function_ack.h │ ├── mavlink_msg_flexifunction_command.h │ ├── mavlink_msg_flexifunction_command_ack.h │ ├── mavlink_msg_flexifunction_directory.h │ ├── mavlink_msg_flexifunction_directory_ack.h │ ├── mavlink_msg_flexifunction_read_req.h │ ├── mavlink_msg_flexifunction_set.h │ ├── mavlink_msg_serial_udb_extra_f13.h │ ├── mavlink_msg_serial_udb_extra_f14.h │ ├── mavlink_msg_serial_udb_extra_f15.h │ ├── mavlink_msg_serial_udb_extra_f16.h │ ├── mavlink_msg_serial_udb_extra_f17.h │ ├── mavlink_msg_serial_udb_extra_f18.h │ ├── mavlink_msg_serial_udb_extra_f19.h │ ├── mavlink_msg_serial_udb_extra_f20.h │ ├── mavlink_msg_serial_udb_extra_f21.h │ ├── mavlink_msg_serial_udb_extra_f22.h │ ├── mavlink_msg_serial_udb_extra_f2_a.h │ ├── mavlink_msg_serial_udb_extra_f2_b.h │ ├── mavlink_msg_serial_udb_extra_f4.h │ ├── mavlink_msg_serial_udb_extra_f5.h │ ├── mavlink_msg_serial_udb_extra_f6.h │ ├── mavlink_msg_serial_udb_extra_f7.h │ ├── mavlink_msg_serial_udb_extra_f8.h │ ├── testsuite.h │ └── version.h ├── mavlink_conversions.h ├── mavlink_get_info.h ├── mavlink_helpers.h ├── mavlink_sha256.h ├── mavlink_types.h ├── message_definitions │ ├── ASLUAV.xml │ ├── AVSSUAS.xml │ ├── all.xml │ ├── ardupilotmega.xml │ ├── common.xml │ ├── csAirLink.xml │ ├── cubepilot.xml │ ├── development.xml │ ├── icarous.xml │ ├── loweheiser.xml │ ├── matrixpilot.xml │ ├── minimal.xml │ ├── paparazzi.xml │ ├── python_array_test.xml │ ├── standard.xml │ ├── storm32.xml │ ├── test.xml │ ├── uAvionix.xml │ └── ualberta.xml ├── minimal │ ├── mavlink.h │ ├── mavlink_msg_heartbeat.h │ ├── mavlink_msg_protocol_version.h │ ├── minimal.h │ ├── testsuite.h │ └── version.h ├── paparazzi │ ├── mavlink.h │ ├── mavlink_msg_script_count.h │ ├── mavlink_msg_script_current.h │ ├── mavlink_msg_script_item.h │ ├── mavlink_msg_script_request.h │ ├── mavlink_msg_script_request_list.h │ ├── paparazzi.h │ ├── testsuite.h │ └── version.h ├── protocol.h ├── python_array_test │ ├── mavlink.h │ ├── mavlink_msg_array_test_0.h │ ├── mavlink_msg_array_test_1.h │ ├── mavlink_msg_array_test_3.h │ ├── mavlink_msg_array_test_4.h │ ├── mavlink_msg_array_test_5.h │ ├── mavlink_msg_array_test_6.h │ ├── mavlink_msg_array_test_7.h │ ├── mavlink_msg_array_test_8.h │ ├── python_array_test.h │ ├── testsuite.h │ └── version.h ├── standard │ ├── mavlink.h │ ├── standard.h │ ├── testsuite.h │ └── version.h ├── storm32 │ ├── mavlink.h │ ├── mavlink_msg_autopilot_state_for_gimbal_device_ext.h │ ├── mavlink_msg_frsky_passthrough_array.h │ ├── mavlink_msg_mlrs_radio_link_flow_control.h │ ├── mavlink_msg_mlrs_radio_link_information.h │ ├── mavlink_msg_mlrs_radio_link_stats.h │ ├── mavlink_msg_param_value_array.h │ ├── mavlink_msg_qshot_status.h │ ├── mavlink_msg_storm32_gimbal_manager_control.h │ ├── mavlink_msg_storm32_gimbal_manager_control_pitchyaw.h │ ├── mavlink_msg_storm32_gimbal_manager_correct_roll.h │ ├── mavlink_msg_storm32_gimbal_manager_information.h │ ├── mavlink_msg_storm32_gimbal_manager_status.h │ ├── storm32.h │ ├── testsuite.h │ └── version.h ├── test │ ├── mavlink.h │ ├── mavlink_msg_test_types.h │ ├── test.h │ ├── testsuite.h │ └── version.h ├── uAvionix │ ├── mavlink.h │ ├── mavlink_msg_uavionix_adsb_get.h │ ├── mavlink_msg_uavionix_adsb_out_cfg.h │ ├── mavlink_msg_uavionix_adsb_out_cfg_flightid.h │ ├── mavlink_msg_uavionix_adsb_out_cfg_registration.h │ ├── mavlink_msg_uavionix_adsb_out_control.h │ ├── mavlink_msg_uavionix_adsb_out_dynamic.h │ ├── mavlink_msg_uavionix_adsb_out_status.h │ ├── mavlink_msg_uavionix_adsb_transceiver_health_report.h │ ├── testsuite.h │ ├── uAvionix.h │ └── version.h └── ualberta │ ├── mavlink.h │ ├── mavlink_msg_nav_filter_bias.h │ ├── mavlink_msg_radio_calibration.h │ ├── mavlink_msg_ualberta_sys_status.h │ ├── testsuite.h │ ├── ualberta.h │ └── version.h └── versions.yaml /.github/workflows/update.yml: -------------------------------------------------------------------------------- 1 | # MAVLink-Arduino 2 | # Author: Oleg Kalachev 3 | # Repository: https://github.com/okalachev/mavlink-arduino 4 | # Licence: MIT 5 | 6 | name: Update MAVLink 7 | 8 | on: 9 | schedule: 10 | - cron: '0 0 1 * *' # every month 11 | workflow_dispatch: 12 | 13 | jobs: 14 | update: 15 | runs-on: ubuntu-22.04 16 | steps: 17 | - uses: actions/checkout@v4 18 | - name: Update MAVLink library 19 | run: | 20 | rm -rf mavlink 21 | wget https://codeload.github.com/mavlink/c_library_v2/zip/master -O mavlink.zip 22 | unzip -o mavlink.zip 23 | mv c_library_v2-master mavlink 24 | rm mavlink.zip 25 | - name: Retrieve MAVLink version 26 | id: mavlink_version 27 | run: | 28 | echo MAVLINK_BUILD_DATE=$(sed -n 's/^#define MAVLINK_BUILD_DATE "\(.*\)"/\1/p' mavlink/common/version.h) >> $GITHUB_OUTPUT 29 | echo MAVLINK_CHANGED=$(git diff --quiet || echo "1") >> $GITHUB_OUTPUT 30 | - name: Commit MAVLink update 31 | if: steps.mavlink_version.outputs.MAVLINK_CHANGED == '1' 32 | uses: EndBug/add-and-commit@v9 33 | with: 34 | message: MAVLink version ${{ steps.mavlink_version.outputs.MAVLINK_BUILD_DATE }} 35 | push: false 36 | author_name: github-actions[bot] 37 | author_email: github-actions[bot]@users.noreply.github.com 38 | - name: Bump tag (dry run) 39 | id: bump 40 | uses: anothrNick/github-tag-action@1.64.0 41 | env: 42 | DEFAULT_BUMP: patch 43 | DRY_RUN: true 44 | WITH_V: false 45 | - name: Change version in library.properties 46 | if: steps.mavlink_version.outputs.MAVLINK_CHANGED == '1' 47 | id: version 48 | run: sed -i "s/^version=.*$/version=${{ steps.bump.outputs.new_tag }}/g" library.properties 49 | - name: Dump outputs 50 | run: | 51 | echo MAVLINK_CHANGED=${{ steps.mavlink_version.outputs.MAVLINK_CHANGED }} 52 | echo MAVLINK_BUILD_DATE=${{ steps.mavlink_version.outputs.MAVLINK_BUILD_DATE }} 53 | echo TAG=${{ steps.bump.outputs.tag }} 54 | echo NEW_TAG=${{ steps.bump.outputs.new_tag }} 55 | - name: Update versions list 56 | if: steps.mavlink_version.outputs.MAVLINK_CHANGED == '1' 57 | run: yq -i '."${{ steps.bump.outputs.new_tag }}" = "${{ steps.mavlink_version.outputs.MAVLINK_BUILD_DATE }}"' versions.yaml 58 | - name: Commit version update, push changes 59 | if: steps.mavlink_version.outputs.MAVLINK_CHANGED == '1' 60 | uses: EndBug/add-and-commit@v9 61 | with: 62 | message: MAVLink version ${{ steps.mavlink_version.outputs.MAVLINK_BUILD_DATE }} 63 | push: true 64 | commit: --amend 65 | author_name: github-actions[bot] 66 | author_email: github-actions[bot]@users.noreply.github.com 67 | - name: Bump version and push tag 68 | if: steps.mavlink_version.outputs.MAVLINK_CHANGED == '1' 69 | uses: anothrNick/github-tag-action@1.64.0 70 | env: 71 | GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} 72 | WITH_V: false 73 | DEFAULT_BUMP: patch 74 | -------------------------------------------------------------------------------- /LICENSE.txt: -------------------------------------------------------------------------------- 1 | MIT License 2 | 3 | Copyright (c) 2024 Oleg Kalachev 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in all 13 | copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 21 | SOFTWARE. 22 | -------------------------------------------------------------------------------- /MAVLink.h: -------------------------------------------------------------------------------- 1 | // MAVLink-Arduino 2 | // Author: Oleg Kalachev 3 | // Repository: https://github.com/okalachev/mavlink-arduino 4 | // Licence: MIT 5 | 6 | #include "mavlink/common/mavlink.h" 7 | -------------------------------------------------------------------------------- /MAVLink_ASLUAV.h: -------------------------------------------------------------------------------- 1 | // MAVLink-Arduino 2 | // Author: Oleg Kalachev 3 | // Repository: https://github.com/okalachev/mavlink-arduino 4 | // Licence: MIT 5 | 6 | #include "mavlink/ASLUAV/mavlink.h" 7 | -------------------------------------------------------------------------------- /MAVLink_AVSSUAS.h: -------------------------------------------------------------------------------- 1 | // MAVLink-Arduino 2 | // Author: Oleg Kalachev 3 | // Repository: https://github.com/okalachev/mavlink-arduino 4 | // Licence: MIT 5 | 6 | #include "mavlink/AVSSUAS/mavlink.h" 7 | -------------------------------------------------------------------------------- /MAVLink_all.h: -------------------------------------------------------------------------------- 1 | // MAVLink-Arduino 2 | // Author: Oleg Kalachev 3 | // Repository: https://github.com/okalachev/mavlink-arduino 4 | // Licence: MIT 5 | 6 | #include "mavlink/all/mavlink.h" 7 | -------------------------------------------------------------------------------- /MAVLink_ardupilotmega.h: -------------------------------------------------------------------------------- 1 | // MAVLink-Arduino 2 | // Author: Oleg Kalachev 3 | // Repository: https://github.com/okalachev/mavlink-arduino 4 | // Licence: MIT 5 | 6 | #include "mavlink/ardupilotmega/mavlink.h" 7 | -------------------------------------------------------------------------------- /MAVLink_common.h: -------------------------------------------------------------------------------- 1 | // MAVLink-Arduino 2 | // Author: Oleg Kalachev 3 | // Repository: https://github.com/okalachev/mavlink-arduino 4 | // Licence: MIT 5 | 6 | #include "mavlink/common/mavlink.h" 7 | -------------------------------------------------------------------------------- /MAVLink_csAirLink.h: -------------------------------------------------------------------------------- 1 | // MAVLink-Arduino 2 | // Author: Oleg Kalachev 3 | // Repository: https://github.com/okalachev/mavlink-arduino 4 | // Licence: MIT 5 | 6 | #include "mavlink/csAirLink/mavlink.h" 7 | -------------------------------------------------------------------------------- /MAVLink_cubepilot.h: -------------------------------------------------------------------------------- 1 | // MAVLink-Arduino 2 | // Author: Oleg Kalachev 3 | // Repository: https://github.com/okalachev/mavlink-arduino 4 | // Licence: MIT 5 | 6 | #include "mavlink/cubepilot/mavlink.h" 7 | -------------------------------------------------------------------------------- /MAVLink_development.h: -------------------------------------------------------------------------------- 1 | // MAVLink-Arduino 2 | // Author: Oleg Kalachev 3 | // Repository: https://github.com/okalachev/mavlink-arduino 4 | // Licence: MIT 5 | 6 | #include "mavlink/development/mavlink.h" 7 | -------------------------------------------------------------------------------- /MAVLink_icarous.h: -------------------------------------------------------------------------------- 1 | // MAVLink-Arduino 2 | // Author: Oleg Kalachev 3 | // Repository: https://github.com/okalachev/mavlink-arduino 4 | // Licence: MIT 5 | 6 | #include "mavlink/icarous/mavlink.h" 7 | -------------------------------------------------------------------------------- /MAVLink_matrixpilot.h: -------------------------------------------------------------------------------- 1 | // MAVLink-Arduino 2 | // Author: Oleg Kalachev 3 | // Repository: https://github.com/okalachev/mavlink-arduino 4 | // Licence: MIT 5 | 6 | #include "mavlink/matrixpilot/mavlink.h" 7 | -------------------------------------------------------------------------------- /MAVLink_minimal.h: -------------------------------------------------------------------------------- 1 | // MAVLink-Arduino 2 | // Author: Oleg Kalachev 3 | // Repository: https://github.com/okalachev/mavlink-arduino 4 | // Licence: MIT 5 | 6 | #include "mavlink/minimal/mavlink.h" 7 | -------------------------------------------------------------------------------- /MAVLink_paparazzi.h: -------------------------------------------------------------------------------- 1 | // MAVLink-Arduino 2 | // Author: Oleg Kalachev 3 | // Repository: https://github.com/okalachev/mavlink-arduino 4 | // Licence: MIT 5 | 6 | #include "mavlink/paparazzi/mavlink.h" 7 | -------------------------------------------------------------------------------- /MAVLink_standard.h: -------------------------------------------------------------------------------- 1 | // MAVLink-Arduino 2 | // Author: Oleg Kalachev 3 | // Repository: https://github.com/okalachev/mavlink-arduino 4 | // Licence: MIT 5 | 6 | #include "mavlink/standard/mavlink.h" 7 | -------------------------------------------------------------------------------- /MAVLink_storm32.h: -------------------------------------------------------------------------------- 1 | // MAVLink-Arduino 2 | // Author: Oleg Kalachev 3 | // Repository: https://github.com/okalachev/mavlink-arduino 4 | // Licence: MIT 5 | 6 | #include "mavlink/storm32/mavlink.h" 7 | -------------------------------------------------------------------------------- /MAVLink_test.h: -------------------------------------------------------------------------------- 1 | // MAVLink-Arduino 2 | // Author: Oleg Kalachev 3 | // Repository: https://github.com/okalachev/mavlink-arduino 4 | // Licence: MIT 5 | 6 | #include "mavlink/test/mavlink.h" 7 | -------------------------------------------------------------------------------- /MAVLink_uAvionix.h: -------------------------------------------------------------------------------- 1 | // MAVLink-Arduino 2 | // Author: Oleg Kalachev 3 | // Repository: https://github.com/okalachev/mavlink-arduino 4 | // Licence: MIT 5 | 6 | #include "mavlink/uAvionix/mavlink.h" 7 | -------------------------------------------------------------------------------- /MAVLink_ualberta.h: -------------------------------------------------------------------------------- 1 | // MAVLink-Arduino 2 | // Author: Oleg Kalachev 3 | // Repository: https://github.com/okalachev/mavlink-arduino 4 | // Licence: MIT 5 | 6 | #include "mavlink/ualberta/mavlink.h" 7 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # MAVLink v2 library for Arduino 2 | 3 | MAVLink is a lightweight communication protocol for communication between drones (and/or ground systems) and their components. 4 | 5 | The underlying MAVLink protocol library automatically gets updated once a month. Correspondence between the library release and MAVLink release can be seen in the [`versions.yaml`](versions.yaml) file. 6 | 7 | Official MAVLink documentation: https://mavlink.io/en/. 8 | 9 | ## Installation 10 | 11 | ### Arduino IDE 12 | 13 | Search for "MAVLink" in the Arduino IDE [library manager](https://docs.arduino.cc/software/ide-v2/tutorials/ide-v2-installing-a-library) and install the library. 14 | 15 | ### arduino-cli 16 | 17 | ```bash 18 | arduino-cli lib update-index 19 | arduino-cli lib install MAVLink 20 | ``` 21 | 22 | ## Usage 23 | 24 | ```cpp 25 | #include 26 | 27 | void setup() { 28 | Serial.begin(57600); 29 | } 30 | 31 | void loop() { 32 | // Send HEARTBEAT message to Serial once a second 33 | mavlink_message_t msg; 34 | uint8_t buf[MAVLINK_MAX_PACKET_LEN]; 35 | 36 | mavlink_msg_heartbeat_pack(1, MAV_COMP_ID_AUTOPILOT1, &msg, MAV_TYPE_QUADROTOR, MAV_AUTOPILOT_GENERIC, MAV_MODE_FLAG_MANUAL_INPUT_ENABLED, 0, MAV_STATE_STANDBY); 37 | uint16_t len = mavlink_msg_to_send_buffer(buf, &msg); 38 | 39 | Serial.write(buf, len); 40 | delay(1000); 41 | } 42 | ``` 43 | 44 | The default used [MAVLink dialect](https://mavlink.io/en/messages/#dialects) is `common`. You can use another standard MAVLink dialect like this: 45 | 46 | ```cpp 47 | #include 48 | ``` 49 | 50 | ```cpp 51 | #include 52 | ``` 53 | 54 | See examples in the [`examples`](examples) directory. 55 | 56 | ## Copyright 57 | 58 | Copyright for the Arduino library © Oleg Kalachev, 2024. License: [MIT](LICENSE.txt). 59 | -------------------------------------------------------------------------------- /examples/HeartbeatSender/HeartbeatSender.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | void setup() { 4 | Serial.begin(57600); 5 | } 6 | 7 | void loop() { 8 | // Send HEARTBEAT message to Serial once a second 9 | mavlink_message_t msg; 10 | uint8_t buf[MAVLINK_MAX_PACKET_LEN]; 11 | 12 | mavlink_msg_heartbeat_pack(1, MAV_COMP_ID_AUTOPILOT1, &msg, MAV_TYPE_QUADROTOR, MAV_AUTOPILOT_GENERIC, MAV_MODE_FLAG_MANUAL_INPUT_ENABLED, 0, MAV_STATE_STANDBY); 13 | uint16_t len = mavlink_msg_to_send_buffer(buf, &msg); 14 | 15 | Serial.write(buf, len); 16 | delay(1000); 17 | } 18 | -------------------------------------------------------------------------------- /examples/WiFiMAVLink/WiFiMAVLink.ino: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include 5 | 6 | // Usage: connect to Wi-Fi network and use QGroundControl to open MAVLink connection 7 | 8 | WiFiUDP udp; 9 | 10 | void setup() { 11 | Serial.begin(115200); 12 | WiFi.softAP("MAVLink", "12345678"); 13 | udp.begin(14550); 14 | } 15 | 16 | void loop() { 17 | sendMAVLink(); 18 | receiveMAVLink(); 19 | } 20 | 21 | void sendMAVLink() { 22 | static uint32_t lastSent = 0; 23 | if (millis() - lastSent < 1000) return; // Send every second 24 | 25 | // Generate HEARTBEAT message buffer 26 | mavlink_message_t msg; 27 | uint8_t buf[MAVLINK_MAX_PACKET_LEN]; 28 | 29 | mavlink_msg_heartbeat_pack(1, MAV_COMP_ID_AUTOPILOT1, &msg, MAV_TYPE_QUADROTOR, MAV_AUTOPILOT_GENERIC, MAV_MODE_FLAG_MANUAL_INPUT_ENABLED, 0, MAV_STATE_STANDBY); 30 | uint16_t len = mavlink_msg_to_send_buffer(buf, &msg); 31 | 32 | // Send buffer over UDP 33 | udp.beginPacket("255.255.255.255", 14550); 34 | udp.write(buf, len); 35 | udp.endPacket(); 36 | 37 | lastSent = millis(); 38 | } 39 | 40 | void receiveMAVLink() { 41 | int packetSize = udp.parsePacket(); 42 | if (!packetSize) return; 43 | 44 | // Read UDP packet 45 | uint8_t buf[MAVLINK_MAX_PACKET_LEN]; 46 | udp.read(buf, MAVLINK_MAX_PACKET_LEN); 47 | 48 | // Parse MAVLink message 49 | mavlink_message_t msg; 50 | mavlink_status_t status; 51 | for (int i = 0; i < packetSize; i++) { 52 | if (mavlink_parse_char(MAVLINK_COMM_0, buf[i], &msg, &status)) { 53 | switch (msg.msgid) { 54 | case MAVLINK_MSG_ID_HEARTBEAT: 55 | Serial.println("Received HEARTBEAT"); 56 | break; 57 | case MAVLINK_MSG_ID_MANUAL_CONTROL: 58 | // Can be used to control the vehicle 59 | mavlink_manual_control_t manualControl; 60 | mavlink_msg_manual_control_decode(&msg, &manualControl); 61 | Serial.print("Received MANUAL_CONTROL:"); 62 | Serial.print(" x="); 63 | Serial.print(manualControl.x); 64 | Serial.print(" y="); 65 | Serial.print(manualControl.y); 66 | Serial.print(" z="); 67 | Serial.print(manualControl.z); 68 | Serial.print(" r="); 69 | Serial.println(manualControl.r); 70 | break; 71 | default: 72 | Serial.print("Received message with ID "); 73 | Serial.println(msg.msgid); 74 | break; 75 | } 76 | } 77 | } 78 | } 79 | -------------------------------------------------------------------------------- /library.properties: -------------------------------------------------------------------------------- 1 | name=MAVLink 2 | version=2.0.18 3 | author=Oleg Kalachev 5 | sentence=MAVLink v2 for Arduino. 6 | paragraph=MAVLink is a lightweight communication protocol for communication between drones (and/or ground systems) and their components. 7 | category=Communication 8 | url=https://github.com/okalachev/mavlink-arduino 9 | architectures=* 10 | includes=MAVLink.h 11 | -------------------------------------------------------------------------------- /mavlink/ASLUAV/mavlink.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol built from ASLUAV.xml 3 | * @see http://mavlink.org 4 | */ 5 | #pragma once 6 | #ifndef MAVLINK_H 7 | #define MAVLINK_H 8 | 9 | #define MAVLINK_PRIMARY_XML_HASH 6292167314514737233 10 | 11 | #ifndef MAVLINK_STX 12 | #define MAVLINK_STX 253 13 | #endif 14 | 15 | #ifndef MAVLINK_ENDIAN 16 | #define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN 17 | #endif 18 | 19 | #ifndef MAVLINK_ALIGNED_FIELDS 20 | #define MAVLINK_ALIGNED_FIELDS 1 21 | #endif 22 | 23 | #ifndef MAVLINK_CRC_EXTRA 24 | #define MAVLINK_CRC_EXTRA 1 25 | #endif 26 | 27 | #ifndef MAVLINK_COMMAND_24BIT 28 | #define MAVLINK_COMMAND_24BIT 1 29 | #endif 30 | 31 | #include "version.h" 32 | #include "ASLUAV.h" 33 | 34 | #endif // MAVLINK_H 35 | -------------------------------------------------------------------------------- /mavlink/ASLUAV/version.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol built from ASLUAV.xml 3 | * @see http://mavlink.org 4 | */ 5 | #pragma once 6 | 7 | #ifndef MAVLINK_VERSION_H 8 | #define MAVLINK_VERSION_H 9 | 10 | #define MAVLINK_BUILD_DATE "Thu May 29 2025" 11 | #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0" 12 | #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 13 | 14 | #endif // MAVLINK_VERSION_H 15 | -------------------------------------------------------------------------------- /mavlink/AVSSUAS/mavlink.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol built from AVSSUAS.xml 3 | * @see http://mavlink.org 4 | */ 5 | #pragma once 6 | #ifndef MAVLINK_H 7 | #define MAVLINK_H 8 | 9 | #define MAVLINK_PRIMARY_XML_HASH -4254438026318362368 10 | 11 | #ifndef MAVLINK_STX 12 | #define MAVLINK_STX 253 13 | #endif 14 | 15 | #ifndef MAVLINK_ENDIAN 16 | #define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN 17 | #endif 18 | 19 | #ifndef MAVLINK_ALIGNED_FIELDS 20 | #define MAVLINK_ALIGNED_FIELDS 1 21 | #endif 22 | 23 | #ifndef MAVLINK_CRC_EXTRA 24 | #define MAVLINK_CRC_EXTRA 1 25 | #endif 26 | 27 | #ifndef MAVLINK_COMMAND_24BIT 28 | #define MAVLINK_COMMAND_24BIT 1 29 | #endif 30 | 31 | #include "version.h" 32 | #include "AVSSUAS.h" 33 | 34 | #endif // MAVLINK_H 35 | -------------------------------------------------------------------------------- /mavlink/AVSSUAS/version.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol built from AVSSUAS.xml 3 | * @see http://mavlink.org 4 | */ 5 | #pragma once 6 | 7 | #ifndef MAVLINK_VERSION_H 8 | #define MAVLINK_VERSION_H 9 | 10 | #define MAVLINK_BUILD_DATE "Thu May 29 2025" 11 | #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0" 12 | #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 13 | 14 | #endif // MAVLINK_VERSION_H 15 | -------------------------------------------------------------------------------- /mavlink/all/mavlink.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol built from all.xml 3 | * @see http://mavlink.org 4 | */ 5 | #pragma once 6 | #ifndef MAVLINK_H 7 | #define MAVLINK_H 8 | 9 | #define MAVLINK_PRIMARY_XML_HASH 5908461096974235969 10 | 11 | #ifndef MAVLINK_STX 12 | #define MAVLINK_STX 253 13 | #endif 14 | 15 | #ifndef MAVLINK_ENDIAN 16 | #define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN 17 | #endif 18 | 19 | #ifndef MAVLINK_ALIGNED_FIELDS 20 | #define MAVLINK_ALIGNED_FIELDS 1 21 | #endif 22 | 23 | #ifndef MAVLINK_CRC_EXTRA 24 | #define MAVLINK_CRC_EXTRA 1 25 | #endif 26 | 27 | #ifndef MAVLINK_COMMAND_24BIT 28 | #define MAVLINK_COMMAND_24BIT 1 29 | #endif 30 | 31 | #include "version.h" 32 | #include "all.h" 33 | 34 | #endif // MAVLINK_H 35 | -------------------------------------------------------------------------------- /mavlink/all/testsuite.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol testsuite generated from all.xml 3 | * @see https://mavlink.io/en/ 4 | */ 5 | #pragma once 6 | #ifndef ALL_TESTSUITE_H 7 | #define ALL_TESTSUITE_H 8 | 9 | #ifdef __cplusplus 10 | extern "C" { 11 | #endif 12 | 13 | #ifndef MAVLINK_TEST_ALL 14 | #define MAVLINK_TEST_ALL 15 | static void mavlink_test_ardupilotmega(uint8_t, uint8_t, mavlink_message_t *last_msg); 16 | static void mavlink_test_ASLUAV(uint8_t, uint8_t, mavlink_message_t *last_msg); 17 | static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg); 18 | static void mavlink_test_development(uint8_t, uint8_t, mavlink_message_t *last_msg); 19 | static void mavlink_test_icarous(uint8_t, uint8_t, mavlink_message_t *last_msg); 20 | static void mavlink_test_minimal(uint8_t, uint8_t, mavlink_message_t *last_msg); 21 | static void mavlink_test_python_array_test(uint8_t, uint8_t, mavlink_message_t *last_msg); 22 | static void mavlink_test_standard(uint8_t, uint8_t, mavlink_message_t *last_msg); 23 | static void mavlink_test_test(uint8_t, uint8_t, mavlink_message_t *last_msg); 24 | static void mavlink_test_ualberta(uint8_t, uint8_t, mavlink_message_t *last_msg); 25 | static void mavlink_test_uAvionix(uint8_t, uint8_t, mavlink_message_t *last_msg); 26 | static void mavlink_test_storm32(uint8_t, uint8_t, mavlink_message_t *last_msg); 27 | static void mavlink_test_AVSSUAS(uint8_t, uint8_t, mavlink_message_t *last_msg); 28 | static void mavlink_test_cubepilot(uint8_t, uint8_t, mavlink_message_t *last_msg); 29 | static void mavlink_test_csAirLink(uint8_t, uint8_t, mavlink_message_t *last_msg); 30 | static void mavlink_test_all(uint8_t, uint8_t, mavlink_message_t *last_msg); 31 | 32 | static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) 33 | { 34 | mavlink_test_ardupilotmega(system_id, component_id, last_msg); 35 | mavlink_test_ASLUAV(system_id, component_id, last_msg); 36 | mavlink_test_common(system_id, component_id, last_msg); 37 | mavlink_test_development(system_id, component_id, last_msg); 38 | mavlink_test_icarous(system_id, component_id, last_msg); 39 | mavlink_test_minimal(system_id, component_id, last_msg); 40 | mavlink_test_python_array_test(system_id, component_id, last_msg); 41 | mavlink_test_standard(system_id, component_id, last_msg); 42 | mavlink_test_test(system_id, component_id, last_msg); 43 | mavlink_test_ualberta(system_id, component_id, last_msg); 44 | mavlink_test_uAvionix(system_id, component_id, last_msg); 45 | mavlink_test_storm32(system_id, component_id, last_msg); 46 | mavlink_test_AVSSUAS(system_id, component_id, last_msg); 47 | mavlink_test_cubepilot(system_id, component_id, last_msg); 48 | mavlink_test_csAirLink(system_id, component_id, last_msg); 49 | mavlink_test_all(system_id, component_id, last_msg); 50 | } 51 | #endif 52 | 53 | #include "../ardupilotmega/testsuite.h" 54 | #include "../ASLUAV/testsuite.h" 55 | #include "../common/testsuite.h" 56 | #include "../development/testsuite.h" 57 | #include "../icarous/testsuite.h" 58 | #include "../minimal/testsuite.h" 59 | #include "../python_array_test/testsuite.h" 60 | #include "../standard/testsuite.h" 61 | #include "../test/testsuite.h" 62 | #include "../ualberta/testsuite.h" 63 | #include "../uAvionix/testsuite.h" 64 | #include "../storm32/testsuite.h" 65 | #include "../AVSSUAS/testsuite.h" 66 | #include "../cubepilot/testsuite.h" 67 | #include "../csAirLink/testsuite.h" 68 | 69 | 70 | 71 | static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) 72 | { 73 | 74 | } 75 | 76 | #ifdef __cplusplus 77 | } 78 | #endif // __cplusplus 79 | #endif // ALL_TESTSUITE_H 80 | -------------------------------------------------------------------------------- /mavlink/all/version.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol built from all.xml 3 | * @see http://mavlink.org 4 | */ 5 | #pragma once 6 | 7 | #ifndef MAVLINK_VERSION_H 8 | #define MAVLINK_VERSION_H 9 | 10 | #define MAVLINK_BUILD_DATE "Thu May 29 2025" 11 | #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0" 12 | #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 13 | 14 | #endif // MAVLINK_VERSION_H 15 | -------------------------------------------------------------------------------- /mavlink/ardupilotmega/mavlink.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol built from ardupilotmega.xml 3 | * @see http://mavlink.org 4 | */ 5 | #pragma once 6 | #ifndef MAVLINK_H 7 | #define MAVLINK_H 8 | 9 | #define MAVLINK_PRIMARY_XML_HASH -6471175882599280949 10 | 11 | #ifndef MAVLINK_STX 12 | #define MAVLINK_STX 253 13 | #endif 14 | 15 | #ifndef MAVLINK_ENDIAN 16 | #define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN 17 | #endif 18 | 19 | #ifndef MAVLINK_ALIGNED_FIELDS 20 | #define MAVLINK_ALIGNED_FIELDS 1 21 | #endif 22 | 23 | #ifndef MAVLINK_CRC_EXTRA 24 | #define MAVLINK_CRC_EXTRA 1 25 | #endif 26 | 27 | #ifndef MAVLINK_COMMAND_24BIT 28 | #define MAVLINK_COMMAND_24BIT 1 29 | #endif 30 | 31 | #include "version.h" 32 | #include "ardupilotmega.h" 33 | 34 | #endif // MAVLINK_H 35 | -------------------------------------------------------------------------------- /mavlink/ardupilotmega/mavlink_msg_rpm.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | // MESSAGE RPM PACKING 3 | 4 | #define MAVLINK_MSG_ID_RPM 226 5 | 6 | 7 | typedef struct __mavlink_rpm_t { 8 | float rpm1; /*< RPM Sensor1.*/ 9 | float rpm2; /*< RPM Sensor2.*/ 10 | } mavlink_rpm_t; 11 | 12 | #define MAVLINK_MSG_ID_RPM_LEN 8 13 | #define MAVLINK_MSG_ID_RPM_MIN_LEN 8 14 | #define MAVLINK_MSG_ID_226_LEN 8 15 | #define MAVLINK_MSG_ID_226_MIN_LEN 8 16 | 17 | #define MAVLINK_MSG_ID_RPM_CRC 207 18 | #define MAVLINK_MSG_ID_226_CRC 207 19 | 20 | 21 | 22 | #if MAVLINK_COMMAND_24BIT 23 | #define MAVLINK_MESSAGE_INFO_RPM { \ 24 | 226, \ 25 | "RPM", \ 26 | 2, \ 27 | { { "rpm1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_rpm_t, rpm1) }, \ 28 | { "rpm2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_rpm_t, rpm2) }, \ 29 | } \ 30 | } 31 | #else 32 | #define MAVLINK_MESSAGE_INFO_RPM { \ 33 | "RPM", \ 34 | 2, \ 35 | { { "rpm1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_rpm_t, rpm1) }, \ 36 | { "rpm2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_rpm_t, rpm2) }, \ 37 | } \ 38 | } 39 | #endif 40 | 41 | /** 42 | * @brief Pack a rpm message 43 | * @param system_id ID of this system 44 | * @param component_id ID of this component (e.g. 200 for IMU) 45 | * @param msg The MAVLink message to compress the data into 46 | * 47 | * @param rpm1 RPM Sensor1. 48 | * @param rpm2 RPM Sensor2. 49 | * @return length of the message in bytes (excluding serial stream start sign) 50 | */ 51 | static inline uint16_t mavlink_msg_rpm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, 52 | float rpm1, float rpm2) 53 | { 54 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 55 | char buf[MAVLINK_MSG_ID_RPM_LEN]; 56 | _mav_put_float(buf, 0, rpm1); 57 | _mav_put_float(buf, 4, rpm2); 58 | 59 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RPM_LEN); 60 | #else 61 | mavlink_rpm_t packet; 62 | packet.rpm1 = rpm1; 63 | packet.rpm2 = rpm2; 64 | 65 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RPM_LEN); 66 | #endif 67 | 68 | msg->msgid = MAVLINK_MSG_ID_RPM; 69 | return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RPM_MIN_LEN, MAVLINK_MSG_ID_RPM_LEN, MAVLINK_MSG_ID_RPM_CRC); 70 | } 71 | 72 | /** 73 | * @brief Pack a rpm message 74 | * @param system_id ID of this system 75 | * @param component_id ID of this component (e.g. 200 for IMU) 76 | * @param status MAVLink status structure 77 | * @param msg The MAVLink message to compress the data into 78 | * 79 | * @param rpm1 RPM Sensor1. 80 | * @param rpm2 RPM Sensor2. 81 | * @return length of the message in bytes (excluding serial stream start sign) 82 | */ 83 | static inline uint16_t mavlink_msg_rpm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg, 84 | float rpm1, float rpm2) 85 | { 86 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 87 | char buf[MAVLINK_MSG_ID_RPM_LEN]; 88 | _mav_put_float(buf, 0, rpm1); 89 | _mav_put_float(buf, 4, rpm2); 90 | 91 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RPM_LEN); 92 | #else 93 | mavlink_rpm_t packet; 94 | packet.rpm1 = rpm1; 95 | packet.rpm2 = rpm2; 96 | 97 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RPM_LEN); 98 | #endif 99 | 100 | msg->msgid = MAVLINK_MSG_ID_RPM; 101 | #if MAVLINK_CRC_EXTRA 102 | return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_RPM_MIN_LEN, MAVLINK_MSG_ID_RPM_LEN, MAVLINK_MSG_ID_RPM_CRC); 103 | #else 104 | return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_RPM_MIN_LEN, MAVLINK_MSG_ID_RPM_LEN); 105 | #endif 106 | } 107 | 108 | /** 109 | * @brief Pack a rpm message on a channel 110 | * @param system_id ID of this system 111 | * @param component_id ID of this component (e.g. 200 for IMU) 112 | * @param chan The MAVLink channel this message will be sent over 113 | * @param msg The MAVLink message to compress the data into 114 | * @param rpm1 RPM Sensor1. 115 | * @param rpm2 RPM Sensor2. 116 | * @return length of the message in bytes (excluding serial stream start sign) 117 | */ 118 | static inline uint16_t mavlink_msg_rpm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, 119 | mavlink_message_t* msg, 120 | float rpm1,float rpm2) 121 | { 122 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 123 | char buf[MAVLINK_MSG_ID_RPM_LEN]; 124 | _mav_put_float(buf, 0, rpm1); 125 | _mav_put_float(buf, 4, rpm2); 126 | 127 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RPM_LEN); 128 | #else 129 | mavlink_rpm_t packet; 130 | packet.rpm1 = rpm1; 131 | packet.rpm2 = rpm2; 132 | 133 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RPM_LEN); 134 | #endif 135 | 136 | msg->msgid = MAVLINK_MSG_ID_RPM; 137 | return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RPM_MIN_LEN, MAVLINK_MSG_ID_RPM_LEN, MAVLINK_MSG_ID_RPM_CRC); 138 | } 139 | 140 | /** 141 | * @brief Encode a rpm struct 142 | * 143 | * @param system_id ID of this system 144 | * @param component_id ID of this component (e.g. 200 for IMU) 145 | * @param msg The MAVLink message to compress the data into 146 | * @param rpm C-struct to read the message contents from 147 | */ 148 | static inline uint16_t mavlink_msg_rpm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rpm_t* rpm) 149 | { 150 | return mavlink_msg_rpm_pack(system_id, component_id, msg, rpm->rpm1, rpm->rpm2); 151 | } 152 | 153 | /** 154 | * @brief Encode a rpm struct on a channel 155 | * 156 | * @param system_id ID of this system 157 | * @param component_id ID of this component (e.g. 200 for IMU) 158 | * @param chan The MAVLink channel this message will be sent over 159 | * @param msg The MAVLink message to compress the data into 160 | * @param rpm C-struct to read the message contents from 161 | */ 162 | static inline uint16_t mavlink_msg_rpm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rpm_t* rpm) 163 | { 164 | return mavlink_msg_rpm_pack_chan(system_id, component_id, chan, msg, rpm->rpm1, rpm->rpm2); 165 | } 166 | 167 | /** 168 | * @brief Encode a rpm struct with provided status structure 169 | * 170 | * @param system_id ID of this system 171 | * @param component_id ID of this component (e.g. 200 for IMU) 172 | * @param status MAVLink status structure 173 | * @param msg The MAVLink message to compress the data into 174 | * @param rpm C-struct to read the message contents from 175 | */ 176 | static inline uint16_t mavlink_msg_rpm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_rpm_t* rpm) 177 | { 178 | return mavlink_msg_rpm_pack_status(system_id, component_id, _status, msg, rpm->rpm1, rpm->rpm2); 179 | } 180 | 181 | /** 182 | * @brief Send a rpm message 183 | * @param chan MAVLink channel to send the message 184 | * 185 | * @param rpm1 RPM Sensor1. 186 | * @param rpm2 RPM Sensor2. 187 | */ 188 | #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 189 | 190 | static inline void mavlink_msg_rpm_send(mavlink_channel_t chan, float rpm1, float rpm2) 191 | { 192 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 193 | char buf[MAVLINK_MSG_ID_RPM_LEN]; 194 | _mav_put_float(buf, 0, rpm1); 195 | _mav_put_float(buf, 4, rpm2); 196 | 197 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RPM, buf, MAVLINK_MSG_ID_RPM_MIN_LEN, MAVLINK_MSG_ID_RPM_LEN, MAVLINK_MSG_ID_RPM_CRC); 198 | #else 199 | mavlink_rpm_t packet; 200 | packet.rpm1 = rpm1; 201 | packet.rpm2 = rpm2; 202 | 203 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RPM, (const char *)&packet, MAVLINK_MSG_ID_RPM_MIN_LEN, MAVLINK_MSG_ID_RPM_LEN, MAVLINK_MSG_ID_RPM_CRC); 204 | #endif 205 | } 206 | 207 | /** 208 | * @brief Send a rpm message 209 | * @param chan MAVLink channel to send the message 210 | * @param struct The MAVLink struct to serialize 211 | */ 212 | static inline void mavlink_msg_rpm_send_struct(mavlink_channel_t chan, const mavlink_rpm_t* rpm) 213 | { 214 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 215 | mavlink_msg_rpm_send(chan, rpm->rpm1, rpm->rpm2); 216 | #else 217 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RPM, (const char *)rpm, MAVLINK_MSG_ID_RPM_MIN_LEN, MAVLINK_MSG_ID_RPM_LEN, MAVLINK_MSG_ID_RPM_CRC); 218 | #endif 219 | } 220 | 221 | #if MAVLINK_MSG_ID_RPM_LEN <= MAVLINK_MAX_PAYLOAD_LEN 222 | /* 223 | This variant of _send() can be used to save stack space by re-using 224 | memory from the receive buffer. The caller provides a 225 | mavlink_message_t which is the size of a full mavlink message. This 226 | is usually the receive buffer for the channel, and allows a reply to an 227 | incoming message with minimum stack space usage. 228 | */ 229 | static inline void mavlink_msg_rpm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float rpm1, float rpm2) 230 | { 231 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 232 | char *buf = (char *)msgbuf; 233 | _mav_put_float(buf, 0, rpm1); 234 | _mav_put_float(buf, 4, rpm2); 235 | 236 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RPM, buf, MAVLINK_MSG_ID_RPM_MIN_LEN, MAVLINK_MSG_ID_RPM_LEN, MAVLINK_MSG_ID_RPM_CRC); 237 | #else 238 | mavlink_rpm_t *packet = (mavlink_rpm_t *)msgbuf; 239 | packet->rpm1 = rpm1; 240 | packet->rpm2 = rpm2; 241 | 242 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RPM, (const char *)packet, MAVLINK_MSG_ID_RPM_MIN_LEN, MAVLINK_MSG_ID_RPM_LEN, MAVLINK_MSG_ID_RPM_CRC); 243 | #endif 244 | } 245 | #endif 246 | 247 | #endif 248 | 249 | // MESSAGE RPM UNPACKING 250 | 251 | 252 | /** 253 | * @brief Get field rpm1 from rpm message 254 | * 255 | * @return RPM Sensor1. 256 | */ 257 | static inline float mavlink_msg_rpm_get_rpm1(const mavlink_message_t* msg) 258 | { 259 | return _MAV_RETURN_float(msg, 0); 260 | } 261 | 262 | /** 263 | * @brief Get field rpm2 from rpm message 264 | * 265 | * @return RPM Sensor2. 266 | */ 267 | static inline float mavlink_msg_rpm_get_rpm2(const mavlink_message_t* msg) 268 | { 269 | return _MAV_RETURN_float(msg, 4); 270 | } 271 | 272 | /** 273 | * @brief Decode a rpm message into a struct 274 | * 275 | * @param msg The message to decode 276 | * @param rpm C-struct to decode the message contents into 277 | */ 278 | static inline void mavlink_msg_rpm_decode(const mavlink_message_t* msg, mavlink_rpm_t* rpm) 279 | { 280 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 281 | rpm->rpm1 = mavlink_msg_rpm_get_rpm1(msg); 282 | rpm->rpm2 = mavlink_msg_rpm_get_rpm2(msg); 283 | #else 284 | uint8_t len = msg->len < MAVLINK_MSG_ID_RPM_LEN? msg->len : MAVLINK_MSG_ID_RPM_LEN; 285 | memset(rpm, 0, MAVLINK_MSG_ID_RPM_LEN); 286 | memcpy(rpm, _MAV_PAYLOAD(msg), len); 287 | #endif 288 | } 289 | -------------------------------------------------------------------------------- /mavlink/ardupilotmega/version.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol built from ardupilotmega.xml 3 | * @see http://mavlink.org 4 | */ 5 | #pragma once 6 | 7 | #ifndef MAVLINK_VERSION_H 8 | #define MAVLINK_VERSION_H 9 | 10 | #define MAVLINK_BUILD_DATE "Thu May 29 2025" 11 | #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0" 12 | #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 13 | 14 | #endif // MAVLINK_VERSION_H 15 | -------------------------------------------------------------------------------- /mavlink/checksum.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #if defined(MAVLINK_USE_CXX_NAMESPACE) 4 | namespace mavlink { 5 | #elif defined(__cplusplus) 6 | extern "C" { 7 | #endif 8 | 9 | // Visual Studio versions before 2010 don't have stdint.h, so we just error out. 10 | #if (defined _MSC_VER) && (_MSC_VER < 1600) 11 | #error "The C-MAVLink implementation requires Visual Studio 2010 or greater" 12 | #endif 13 | 14 | #include 15 | 16 | /** 17 | * 18 | * CALCULATE THE CHECKSUM 19 | * 20 | */ 21 | 22 | #define X25_INIT_CRC 0xffff 23 | #define X25_VALIDATE_CRC 0xf0b8 24 | 25 | #ifndef HAVE_CRC_ACCUMULATE 26 | /** 27 | * @brief Accumulate the CRC16_MCRF4XX checksum by adding one char at a time. 28 | * 29 | * The checksum function adds the hash of one char at a time to the 30 | * 16 bit checksum (uint16_t). 31 | * 32 | * @param data new char to hash 33 | * @param crcAccum the already accumulated checksum 34 | **/ 35 | static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum) 36 | { 37 | /*Accumulate one byte of data into the CRC*/ 38 | uint8_t tmp; 39 | 40 | tmp = data ^ (uint8_t)(*crcAccum &0xff); 41 | tmp ^= (tmp<<4); 42 | *crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4); 43 | } 44 | #endif 45 | 46 | 47 | /** 48 | * @brief Initialize the buffer for the MCRF4XX CRC16 49 | * 50 | * @param crcAccum the 16 bit MCRF4XX CRC16 51 | */ 52 | static inline void crc_init(uint16_t* crcAccum) 53 | { 54 | *crcAccum = X25_INIT_CRC; 55 | } 56 | 57 | 58 | /** 59 | * @brief Calculates the CRC16_MCRF4XX checksum on a byte buffer 60 | * 61 | * @param pBuffer buffer containing the byte array to hash 62 | * @param length length of the byte array 63 | * @return the checksum over the buffer bytes 64 | **/ 65 | static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length) 66 | { 67 | uint16_t crcTmp; 68 | crc_init(&crcTmp); 69 | while (length--) { 70 | crc_accumulate(*pBuffer++, &crcTmp); 71 | } 72 | return crcTmp; 73 | } 74 | 75 | 76 | /** 77 | * @brief Accumulate the MCRF4XX CRC16 by adding an array of bytes 78 | * 79 | * The checksum function adds the hash of one char at a time to the 80 | * 16 bit checksum (uint16_t). 81 | * 82 | * @param data new bytes to hash 83 | * @param crcAccum the already accumulated checksum 84 | **/ 85 | static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint16_t length) 86 | { 87 | const uint8_t *p = (const uint8_t *)pBuffer; 88 | while (length--) { 89 | crc_accumulate(*p++, crcAccum); 90 | } 91 | } 92 | 93 | #if defined(MAVLINK_USE_CXX_NAMESPACE) || defined(__cplusplus) 94 | } 95 | #endif 96 | -------------------------------------------------------------------------------- /mavlink/common/mavlink.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol built from common.xml 3 | * @see http://mavlink.org 4 | */ 5 | #pragma once 6 | #ifndef MAVLINK_H 7 | #define MAVLINK_H 8 | 9 | #define MAVLINK_PRIMARY_XML_HASH -1562228861632841957 10 | 11 | #ifndef MAVLINK_STX 12 | #define MAVLINK_STX 253 13 | #endif 14 | 15 | #ifndef MAVLINK_ENDIAN 16 | #define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN 17 | #endif 18 | 19 | #ifndef MAVLINK_ALIGNED_FIELDS 20 | #define MAVLINK_ALIGNED_FIELDS 1 21 | #endif 22 | 23 | #ifndef MAVLINK_CRC_EXTRA 24 | #define MAVLINK_CRC_EXTRA 1 25 | #endif 26 | 27 | #ifndef MAVLINK_COMMAND_24BIT 28 | #define MAVLINK_COMMAND_24BIT 1 29 | #endif 30 | 31 | #include "version.h" 32 | #include "common.h" 33 | 34 | #endif // MAVLINK_H 35 | -------------------------------------------------------------------------------- /mavlink/common/mavlink_msg_auth_key.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | // MESSAGE AUTH_KEY PACKING 3 | 4 | #define MAVLINK_MSG_ID_AUTH_KEY 7 5 | 6 | 7 | typedef struct __mavlink_auth_key_t { 8 | char key[32]; /*< key*/ 9 | } mavlink_auth_key_t; 10 | 11 | #define MAVLINK_MSG_ID_AUTH_KEY_LEN 32 12 | #define MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN 32 13 | #define MAVLINK_MSG_ID_7_LEN 32 14 | #define MAVLINK_MSG_ID_7_MIN_LEN 32 15 | 16 | #define MAVLINK_MSG_ID_AUTH_KEY_CRC 119 17 | #define MAVLINK_MSG_ID_7_CRC 119 18 | 19 | #define MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN 32 20 | 21 | #if MAVLINK_COMMAND_24BIT 22 | #define MAVLINK_MESSAGE_INFO_AUTH_KEY { \ 23 | 7, \ 24 | "AUTH_KEY", \ 25 | 1, \ 26 | { { "key", NULL, MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_auth_key_t, key) }, \ 27 | } \ 28 | } 29 | #else 30 | #define MAVLINK_MESSAGE_INFO_AUTH_KEY { \ 31 | "AUTH_KEY", \ 32 | 1, \ 33 | { { "key", NULL, MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_auth_key_t, key) }, \ 34 | } \ 35 | } 36 | #endif 37 | 38 | /** 39 | * @brief Pack a auth_key message 40 | * @param system_id ID of this system 41 | * @param component_id ID of this component (e.g. 200 for IMU) 42 | * @param msg The MAVLink message to compress the data into 43 | * 44 | * @param key key 45 | * @return length of the message in bytes (excluding serial stream start sign) 46 | */ 47 | static inline uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, 48 | const char *key) 49 | { 50 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 51 | char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN]; 52 | 53 | _mav_put_char_array(buf, 0, key, 32); 54 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTH_KEY_LEN); 55 | #else 56 | mavlink_auth_key_t packet; 57 | 58 | mav_array_memcpy(packet.key, key, sizeof(char)*32); 59 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTH_KEY_LEN); 60 | #endif 61 | 62 | msg->msgid = MAVLINK_MSG_ID_AUTH_KEY; 63 | return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); 64 | } 65 | 66 | /** 67 | * @brief Pack a auth_key message 68 | * @param system_id ID of this system 69 | * @param component_id ID of this component (e.g. 200 for IMU) 70 | * @param status MAVLink status structure 71 | * @param msg The MAVLink message to compress the data into 72 | * 73 | * @param key key 74 | * @return length of the message in bytes (excluding serial stream start sign) 75 | */ 76 | static inline uint16_t mavlink_msg_auth_key_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg, 77 | const char *key) 78 | { 79 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 80 | char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN]; 81 | 82 | _mav_put_char_array(buf, 0, key, 32); 83 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTH_KEY_LEN); 84 | #else 85 | mavlink_auth_key_t packet; 86 | 87 | mav_array_memcpy(packet.key, key, sizeof(char)*32); 88 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTH_KEY_LEN); 89 | #endif 90 | 91 | msg->msgid = MAVLINK_MSG_ID_AUTH_KEY; 92 | #if MAVLINK_CRC_EXTRA 93 | return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); 94 | #else 95 | return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN); 96 | #endif 97 | } 98 | 99 | /** 100 | * @brief Pack a auth_key message on a channel 101 | * @param system_id ID of this system 102 | * @param component_id ID of this component (e.g. 200 for IMU) 103 | * @param chan The MAVLink channel this message will be sent over 104 | * @param msg The MAVLink message to compress the data into 105 | * @param key key 106 | * @return length of the message in bytes (excluding serial stream start sign) 107 | */ 108 | static inline uint16_t mavlink_msg_auth_key_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, 109 | mavlink_message_t* msg, 110 | const char *key) 111 | { 112 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 113 | char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN]; 114 | 115 | _mav_put_char_array(buf, 0, key, 32); 116 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTH_KEY_LEN); 117 | #else 118 | mavlink_auth_key_t packet; 119 | 120 | mav_array_memcpy(packet.key, key, sizeof(char)*32); 121 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTH_KEY_LEN); 122 | #endif 123 | 124 | msg->msgid = MAVLINK_MSG_ID_AUTH_KEY; 125 | return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); 126 | } 127 | 128 | /** 129 | * @brief Encode a auth_key struct 130 | * 131 | * @param system_id ID of this system 132 | * @param component_id ID of this component (e.g. 200 for IMU) 133 | * @param msg The MAVLink message to compress the data into 134 | * @param auth_key C-struct to read the message contents from 135 | */ 136 | static inline uint16_t mavlink_msg_auth_key_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_auth_key_t* auth_key) 137 | { 138 | return mavlink_msg_auth_key_pack(system_id, component_id, msg, auth_key->key); 139 | } 140 | 141 | /** 142 | * @brief Encode a auth_key struct on a channel 143 | * 144 | * @param system_id ID of this system 145 | * @param component_id ID of this component (e.g. 200 for IMU) 146 | * @param chan The MAVLink channel this message will be sent over 147 | * @param msg The MAVLink message to compress the data into 148 | * @param auth_key C-struct to read the message contents from 149 | */ 150 | static inline uint16_t mavlink_msg_auth_key_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_auth_key_t* auth_key) 151 | { 152 | return mavlink_msg_auth_key_pack_chan(system_id, component_id, chan, msg, auth_key->key); 153 | } 154 | 155 | /** 156 | * @brief Encode a auth_key struct with provided status structure 157 | * 158 | * @param system_id ID of this system 159 | * @param component_id ID of this component (e.g. 200 for IMU) 160 | * @param status MAVLink status structure 161 | * @param msg The MAVLink message to compress the data into 162 | * @param auth_key C-struct to read the message contents from 163 | */ 164 | static inline uint16_t mavlink_msg_auth_key_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_auth_key_t* auth_key) 165 | { 166 | return mavlink_msg_auth_key_pack_status(system_id, component_id, _status, msg, auth_key->key); 167 | } 168 | 169 | /** 170 | * @brief Send a auth_key message 171 | * @param chan MAVLink channel to send the message 172 | * 173 | * @param key key 174 | */ 175 | #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 176 | 177 | static inline void mavlink_msg_auth_key_send(mavlink_channel_t chan, const char *key) 178 | { 179 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 180 | char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN]; 181 | 182 | _mav_put_char_array(buf, 0, key, 32); 183 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); 184 | #else 185 | mavlink_auth_key_t packet; 186 | 187 | mav_array_memcpy(packet.key, key, sizeof(char)*32); 188 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)&packet, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); 189 | #endif 190 | } 191 | 192 | /** 193 | * @brief Send a auth_key message 194 | * @param chan MAVLink channel to send the message 195 | * @param struct The MAVLink struct to serialize 196 | */ 197 | static inline void mavlink_msg_auth_key_send_struct(mavlink_channel_t chan, const mavlink_auth_key_t* auth_key) 198 | { 199 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 200 | mavlink_msg_auth_key_send(chan, auth_key->key); 201 | #else 202 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)auth_key, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); 203 | #endif 204 | } 205 | 206 | #if MAVLINK_MSG_ID_AUTH_KEY_LEN <= MAVLINK_MAX_PAYLOAD_LEN 207 | /* 208 | This variant of _send() can be used to save stack space by re-using 209 | memory from the receive buffer. The caller provides a 210 | mavlink_message_t which is the size of a full mavlink message. This 211 | is usually the receive buffer for the channel, and allows a reply to an 212 | incoming message with minimum stack space usage. 213 | */ 214 | static inline void mavlink_msg_auth_key_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *key) 215 | { 216 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 217 | char *buf = (char *)msgbuf; 218 | 219 | _mav_put_char_array(buf, 0, key, 32); 220 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); 221 | #else 222 | mavlink_auth_key_t *packet = (mavlink_auth_key_t *)msgbuf; 223 | 224 | mav_array_memcpy(packet->key, key, sizeof(char)*32); 225 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)packet, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); 226 | #endif 227 | } 228 | #endif 229 | 230 | #endif 231 | 232 | // MESSAGE AUTH_KEY UNPACKING 233 | 234 | 235 | /** 236 | * @brief Get field key from auth_key message 237 | * 238 | * @return key 239 | */ 240 | static inline uint16_t mavlink_msg_auth_key_get_key(const mavlink_message_t* msg, char *key) 241 | { 242 | return _MAV_RETURN_char_array(msg, key, 32, 0); 243 | } 244 | 245 | /** 246 | * @brief Decode a auth_key message into a struct 247 | * 248 | * @param msg The message to decode 249 | * @param auth_key C-struct to decode the message contents into 250 | */ 251 | static inline void mavlink_msg_auth_key_decode(const mavlink_message_t* msg, mavlink_auth_key_t* auth_key) 252 | { 253 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 254 | mavlink_msg_auth_key_get_key(msg, auth_key->key); 255 | #else 256 | uint8_t len = msg->len < MAVLINK_MSG_ID_AUTH_KEY_LEN? msg->len : MAVLINK_MSG_ID_AUTH_KEY_LEN; 257 | memset(auth_key, 0, MAVLINK_MSG_ID_AUTH_KEY_LEN); 258 | memcpy(auth_key, _MAV_PAYLOAD(msg), len); 259 | #endif 260 | } 261 | -------------------------------------------------------------------------------- /mavlink/common/version.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol built from common.xml 3 | * @see http://mavlink.org 4 | */ 5 | #pragma once 6 | 7 | #ifndef MAVLINK_VERSION_H 8 | #define MAVLINK_VERSION_H 9 | 10 | #define MAVLINK_BUILD_DATE "Thu May 29 2025" 11 | #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0" 12 | #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 13 | 14 | #endif // MAVLINK_VERSION_H 15 | -------------------------------------------------------------------------------- /mavlink/csAirLink/csAirLink.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol generated from csAirLink.xml 3 | * @see http://mavlink.org 4 | */ 5 | #pragma once 6 | #ifndef MAVLINK_CSAIRLINK_H 7 | #define MAVLINK_CSAIRLINK_H 8 | 9 | #ifndef MAVLINK_H 10 | #error Wrong include order: MAVLINK_CSAIRLINK.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call. 11 | #endif 12 | 13 | #define MAVLINK_CSAIRLINK_XML_HASH 6436237487046543682 14 | 15 | #ifdef __cplusplus 16 | extern "C" { 17 | #endif 18 | 19 | // MESSAGE LENGTHS AND CRCS 20 | 21 | #ifndef MAVLINK_MESSAGE_LENGTHS 22 | #define MAVLINK_MESSAGE_LENGTHS {} 23 | #endif 24 | 25 | #ifndef MAVLINK_MESSAGE_CRCS 26 | #define MAVLINK_MESSAGE_CRCS {{52000, 13, 100, 100, 0, 0, 0}, {52001, 239, 1, 1, 0, 0, 0}} 27 | #endif 28 | 29 | #include "../protocol.h" 30 | 31 | #define MAVLINK_ENABLED_CSAIRLINK 32 | 33 | // ENUM DEFINITIONS 34 | 35 | 36 | /** @brief */ 37 | #ifndef HAVE_ENUM_AIRLINK_AUTH_RESPONSE_TYPE 38 | #define HAVE_ENUM_AIRLINK_AUTH_RESPONSE_TYPE 39 | typedef enum AIRLINK_AUTH_RESPONSE_TYPE 40 | { 41 | AIRLINK_ERROR_LOGIN_OR_PASS=0, /* Login or password error | */ 42 | AIRLINK_AUTH_OK=1, /* Auth successful | */ 43 | AIRLINK_AUTH_RESPONSE_TYPE_ENUM_END=2, /* | */ 44 | } AIRLINK_AUTH_RESPONSE_TYPE; 45 | #endif 46 | 47 | // MAVLINK VERSION 48 | 49 | #ifndef MAVLINK_VERSION 50 | #define MAVLINK_VERSION 3 51 | #endif 52 | 53 | #if (MAVLINK_VERSION == 0) 54 | #undef MAVLINK_VERSION 55 | #define MAVLINK_VERSION 3 56 | #endif 57 | 58 | // MESSAGE DEFINITIONS 59 | #include "./mavlink_msg_airlink_auth.h" 60 | #include "./mavlink_msg_airlink_auth_response.h" 61 | 62 | // base include 63 | 64 | 65 | 66 | #if MAVLINK_CSAIRLINK_XML_HASH == MAVLINK_PRIMARY_XML_HASH 67 | # define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_AIRLINK_AUTH, MAVLINK_MESSAGE_INFO_AIRLINK_AUTH_RESPONSE} 68 | # define MAVLINK_MESSAGE_NAMES {{ "AIRLINK_AUTH", 52000 }, { "AIRLINK_AUTH_RESPONSE", 52001 }} 69 | # if MAVLINK_COMMAND_24BIT 70 | # include "../mavlink_get_info.h" 71 | # endif 72 | #endif 73 | 74 | #ifdef __cplusplus 75 | } 76 | #endif // __cplusplus 77 | #endif // MAVLINK_CSAIRLINK_H 78 | -------------------------------------------------------------------------------- /mavlink/csAirLink/mavlink.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol built from csAirLink.xml 3 | * @see http://mavlink.org 4 | */ 5 | #pragma once 6 | #ifndef MAVLINK_H 7 | #define MAVLINK_H 8 | 9 | #define MAVLINK_PRIMARY_XML_HASH 6436237487046543682 10 | 11 | #ifndef MAVLINK_STX 12 | #define MAVLINK_STX 253 13 | #endif 14 | 15 | #ifndef MAVLINK_ENDIAN 16 | #define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN 17 | #endif 18 | 19 | #ifndef MAVLINK_ALIGNED_FIELDS 20 | #define MAVLINK_ALIGNED_FIELDS 1 21 | #endif 22 | 23 | #ifndef MAVLINK_CRC_EXTRA 24 | #define MAVLINK_CRC_EXTRA 1 25 | #endif 26 | 27 | #ifndef MAVLINK_COMMAND_24BIT 28 | #define MAVLINK_COMMAND_24BIT 1 29 | #endif 30 | 31 | #include "version.h" 32 | #include "csAirLink.h" 33 | 34 | #endif // MAVLINK_H 35 | -------------------------------------------------------------------------------- /mavlink/csAirLink/testsuite.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol testsuite generated from csAirLink.xml 3 | * @see https://mavlink.io/en/ 4 | */ 5 | #pragma once 6 | #ifndef CSAIRLINK_TESTSUITE_H 7 | #define CSAIRLINK_TESTSUITE_H 8 | 9 | #ifdef __cplusplus 10 | extern "C" { 11 | #endif 12 | 13 | #ifndef MAVLINK_TEST_ALL 14 | #define MAVLINK_TEST_ALL 15 | 16 | static void mavlink_test_csAirLink(uint8_t, uint8_t, mavlink_message_t *last_msg); 17 | 18 | static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) 19 | { 20 | 21 | mavlink_test_csAirLink(system_id, component_id, last_msg); 22 | } 23 | #endif 24 | 25 | 26 | 27 | 28 | static void mavlink_test_airlink_auth(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) 29 | { 30 | #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 31 | mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0); 32 | if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_AIRLINK_AUTH >= 256) { 33 | return; 34 | } 35 | #endif 36 | mavlink_message_t msg; 37 | uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; 38 | uint16_t i; 39 | mavlink_airlink_auth_t packet_in = { 40 | "ABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVW","YZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTU" 41 | }; 42 | mavlink_airlink_auth_t packet1, packet2; 43 | memset(&packet1, 0, sizeof(packet1)); 44 | 45 | mav_array_memcpy(packet1.login, packet_in.login, sizeof(char)*50); 46 | mav_array_memcpy(packet1.password, packet_in.password, sizeof(char)*50); 47 | 48 | #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 49 | if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { 50 | // cope with extensions 51 | memset(MAVLINK_MSG_ID_AIRLINK_AUTH_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_AIRLINK_AUTH_MIN_LEN); 52 | } 53 | #endif 54 | memset(&packet2, 0, sizeof(packet2)); 55 | mavlink_msg_airlink_auth_encode(system_id, component_id, &msg, &packet1); 56 | mavlink_msg_airlink_auth_decode(&msg, &packet2); 57 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 58 | 59 | memset(&packet2, 0, sizeof(packet2)); 60 | mavlink_msg_airlink_auth_pack(system_id, component_id, &msg , packet1.login , packet1.password ); 61 | mavlink_msg_airlink_auth_decode(&msg, &packet2); 62 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 63 | 64 | memset(&packet2, 0, sizeof(packet2)); 65 | mavlink_msg_airlink_auth_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.login , packet1.password ); 66 | mavlink_msg_airlink_auth_decode(&msg, &packet2); 67 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 68 | 69 | memset(&packet2, 0, sizeof(packet2)); 70 | mavlink_msg_to_send_buffer(buffer, &msg); 71 | for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE >= 256) { 93 | return; 94 | } 95 | #endif 96 | mavlink_message_t msg; 97 | uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; 98 | uint16_t i; 99 | mavlink_airlink_auth_response_t packet_in = { 100 | 5 101 | }; 102 | mavlink_airlink_auth_response_t packet1, packet2; 103 | memset(&packet1, 0, sizeof(packet1)); 104 | packet1.resp_type = packet_in.resp_type; 105 | 106 | 107 | #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 108 | if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { 109 | // cope with extensions 110 | memset(MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_MIN_LEN); 111 | } 112 | #endif 113 | memset(&packet2, 0, sizeof(packet2)); 114 | mavlink_msg_airlink_auth_response_encode(system_id, component_id, &msg, &packet1); 115 | mavlink_msg_airlink_auth_response_decode(&msg, &packet2); 116 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 117 | 118 | memset(&packet2, 0, sizeof(packet2)); 119 | mavlink_msg_airlink_auth_response_pack(system_id, component_id, &msg , packet1.resp_type ); 120 | mavlink_msg_airlink_auth_response_decode(&msg, &packet2); 121 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 122 | 123 | memset(&packet2, 0, sizeof(packet2)); 124 | mavlink_msg_airlink_auth_response_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.resp_type ); 125 | mavlink_msg_airlink_auth_response_decode(&msg, &packet2); 126 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 127 | 128 | memset(&packet2, 0, sizeof(packet2)); 129 | mavlink_msg_to_send_buffer(buffer, &msg); 130 | for (i=0; imsgid = MAVLINK_MSG_ID_ICAROUS_HEARTBEAT; 63 | return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_CRC); 64 | } 65 | 66 | /** 67 | * @brief Pack a icarous_heartbeat message 68 | * @param system_id ID of this system 69 | * @param component_id ID of this component (e.g. 200 for IMU) 70 | * @param status MAVLink status structure 71 | * @param msg The MAVLink message to compress the data into 72 | * 73 | * @param status See the FMS_STATE enum. 74 | * @return length of the message in bytes (excluding serial stream start sign) 75 | */ 76 | static inline uint16_t mavlink_msg_icarous_heartbeat_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg, 77 | uint8_t status) 78 | { 79 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 80 | char buf[MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN]; 81 | _mav_put_uint8_t(buf, 0, status); 82 | 83 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN); 84 | #else 85 | mavlink_icarous_heartbeat_t packet; 86 | packet.status = status; 87 | 88 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN); 89 | #endif 90 | 91 | msg->msgid = MAVLINK_MSG_ID_ICAROUS_HEARTBEAT; 92 | #if MAVLINK_CRC_EXTRA 93 | return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_CRC); 94 | #else 95 | return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN); 96 | #endif 97 | } 98 | 99 | /** 100 | * @brief Pack a icarous_heartbeat message on a channel 101 | * @param system_id ID of this system 102 | * @param component_id ID of this component (e.g. 200 for IMU) 103 | * @param chan The MAVLink channel this message will be sent over 104 | * @param msg The MAVLink message to compress the data into 105 | * @param status See the FMS_STATE enum. 106 | * @return length of the message in bytes (excluding serial stream start sign) 107 | */ 108 | static inline uint16_t mavlink_msg_icarous_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, 109 | mavlink_message_t* msg, 110 | uint8_t status) 111 | { 112 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 113 | char buf[MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN]; 114 | _mav_put_uint8_t(buf, 0, status); 115 | 116 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN); 117 | #else 118 | mavlink_icarous_heartbeat_t packet; 119 | packet.status = status; 120 | 121 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN); 122 | #endif 123 | 124 | msg->msgid = MAVLINK_MSG_ID_ICAROUS_HEARTBEAT; 125 | return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_CRC); 126 | } 127 | 128 | /** 129 | * @brief Encode a icarous_heartbeat struct 130 | * 131 | * @param system_id ID of this system 132 | * @param component_id ID of this component (e.g. 200 for IMU) 133 | * @param msg The MAVLink message to compress the data into 134 | * @param icarous_heartbeat C-struct to read the message contents from 135 | */ 136 | static inline uint16_t mavlink_msg_icarous_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_icarous_heartbeat_t* icarous_heartbeat) 137 | { 138 | return mavlink_msg_icarous_heartbeat_pack(system_id, component_id, msg, icarous_heartbeat->status); 139 | } 140 | 141 | /** 142 | * @brief Encode a icarous_heartbeat struct on a channel 143 | * 144 | * @param system_id ID of this system 145 | * @param component_id ID of this component (e.g. 200 for IMU) 146 | * @param chan The MAVLink channel this message will be sent over 147 | * @param msg The MAVLink message to compress the data into 148 | * @param icarous_heartbeat C-struct to read the message contents from 149 | */ 150 | static inline uint16_t mavlink_msg_icarous_heartbeat_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_icarous_heartbeat_t* icarous_heartbeat) 151 | { 152 | return mavlink_msg_icarous_heartbeat_pack_chan(system_id, component_id, chan, msg, icarous_heartbeat->status); 153 | } 154 | 155 | /** 156 | * @brief Encode a icarous_heartbeat struct with provided status structure 157 | * 158 | * @param system_id ID of this system 159 | * @param component_id ID of this component (e.g. 200 for IMU) 160 | * @param status MAVLink status structure 161 | * @param msg The MAVLink message to compress the data into 162 | * @param icarous_heartbeat C-struct to read the message contents from 163 | */ 164 | static inline uint16_t mavlink_msg_icarous_heartbeat_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_icarous_heartbeat_t* icarous_heartbeat) 165 | { 166 | return mavlink_msg_icarous_heartbeat_pack_status(system_id, component_id, _status, msg, icarous_heartbeat->status); 167 | } 168 | 169 | /** 170 | * @brief Send a icarous_heartbeat message 171 | * @param chan MAVLink channel to send the message 172 | * 173 | * @param status See the FMS_STATE enum. 174 | */ 175 | #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 176 | 177 | static inline void mavlink_msg_icarous_heartbeat_send(mavlink_channel_t chan, uint8_t status) 178 | { 179 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 180 | char buf[MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN]; 181 | _mav_put_uint8_t(buf, 0, status); 182 | 183 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT, buf, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_CRC); 184 | #else 185 | mavlink_icarous_heartbeat_t packet; 186 | packet.status = status; 187 | 188 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_CRC); 189 | #endif 190 | } 191 | 192 | /** 193 | * @brief Send a icarous_heartbeat message 194 | * @param chan MAVLink channel to send the message 195 | * @param struct The MAVLink struct to serialize 196 | */ 197 | static inline void mavlink_msg_icarous_heartbeat_send_struct(mavlink_channel_t chan, const mavlink_icarous_heartbeat_t* icarous_heartbeat) 198 | { 199 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 200 | mavlink_msg_icarous_heartbeat_send(chan, icarous_heartbeat->status); 201 | #else 202 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT, (const char *)icarous_heartbeat, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_CRC); 203 | #endif 204 | } 205 | 206 | #if MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN <= MAVLINK_MAX_PAYLOAD_LEN 207 | /* 208 | This variant of _send() can be used to save stack space by re-using 209 | memory from the receive buffer. The caller provides a 210 | mavlink_message_t which is the size of a full mavlink message. This 211 | is usually the receive buffer for the channel, and allows a reply to an 212 | incoming message with minimum stack space usage. 213 | */ 214 | static inline void mavlink_msg_icarous_heartbeat_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t status) 215 | { 216 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 217 | char *buf = (char *)msgbuf; 218 | _mav_put_uint8_t(buf, 0, status); 219 | 220 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT, buf, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_CRC); 221 | #else 222 | mavlink_icarous_heartbeat_t *packet = (mavlink_icarous_heartbeat_t *)msgbuf; 223 | packet->status = status; 224 | 225 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_CRC); 226 | #endif 227 | } 228 | #endif 229 | 230 | #endif 231 | 232 | // MESSAGE ICAROUS_HEARTBEAT UNPACKING 233 | 234 | 235 | /** 236 | * @brief Get field status from icarous_heartbeat message 237 | * 238 | * @return See the FMS_STATE enum. 239 | */ 240 | static inline uint8_t mavlink_msg_icarous_heartbeat_get_status(const mavlink_message_t* msg) 241 | { 242 | return _MAV_RETURN_uint8_t(msg, 0); 243 | } 244 | 245 | /** 246 | * @brief Decode a icarous_heartbeat message into a struct 247 | * 248 | * @param msg The message to decode 249 | * @param icarous_heartbeat C-struct to decode the message contents into 250 | */ 251 | static inline void mavlink_msg_icarous_heartbeat_decode(const mavlink_message_t* msg, mavlink_icarous_heartbeat_t* icarous_heartbeat) 252 | { 253 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 254 | icarous_heartbeat->status = mavlink_msg_icarous_heartbeat_get_status(msg); 255 | #else 256 | uint8_t len = msg->len < MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN? msg->len : MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN; 257 | memset(icarous_heartbeat, 0, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN); 258 | memcpy(icarous_heartbeat, _MAV_PAYLOAD(msg), len); 259 | #endif 260 | } 261 | -------------------------------------------------------------------------------- /mavlink/icarous/testsuite.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol testsuite generated from icarous.xml 3 | * @see https://mavlink.io/en/ 4 | */ 5 | #pragma once 6 | #ifndef ICAROUS_TESTSUITE_H 7 | #define ICAROUS_TESTSUITE_H 8 | 9 | #ifdef __cplusplus 10 | extern "C" { 11 | #endif 12 | 13 | #ifndef MAVLINK_TEST_ALL 14 | #define MAVLINK_TEST_ALL 15 | 16 | static void mavlink_test_icarous(uint8_t, uint8_t, mavlink_message_t *last_msg); 17 | 18 | static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) 19 | { 20 | 21 | mavlink_test_icarous(system_id, component_id, last_msg); 22 | } 23 | #endif 24 | 25 | 26 | 27 | 28 | static void mavlink_test_icarous_heartbeat(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) 29 | { 30 | #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 31 | mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0); 32 | if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ICAROUS_HEARTBEAT >= 256) { 33 | return; 34 | } 35 | #endif 36 | mavlink_message_t msg; 37 | uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; 38 | uint16_t i; 39 | mavlink_icarous_heartbeat_t packet_in = { 40 | 5 41 | }; 42 | mavlink_icarous_heartbeat_t packet1, packet2; 43 | memset(&packet1, 0, sizeof(packet1)); 44 | packet1.status = packet_in.status; 45 | 46 | 47 | #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 48 | if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { 49 | // cope with extensions 50 | memset(MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN); 51 | } 52 | #endif 53 | memset(&packet2, 0, sizeof(packet2)); 54 | mavlink_msg_icarous_heartbeat_encode(system_id, component_id, &msg, &packet1); 55 | mavlink_msg_icarous_heartbeat_decode(&msg, &packet2); 56 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 57 | 58 | memset(&packet2, 0, sizeof(packet2)); 59 | mavlink_msg_icarous_heartbeat_pack(system_id, component_id, &msg , packet1.status ); 60 | mavlink_msg_icarous_heartbeat_decode(&msg, &packet2); 61 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 62 | 63 | memset(&packet2, 0, sizeof(packet2)); 64 | mavlink_msg_icarous_heartbeat_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.status ); 65 | mavlink_msg_icarous_heartbeat_decode(&msg, &packet2); 66 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 67 | 68 | memset(&packet2, 0, sizeof(packet2)); 69 | mavlink_msg_to_send_buffer(buffer, &msg); 70 | for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS >= 256) { 92 | return; 93 | } 94 | #endif 95 | mavlink_message_t msg; 96 | uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; 97 | uint16_t i; 98 | mavlink_icarous_kinematic_bands_t packet_in = { 99 | 17.0,45.0,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,125,192,3,70,137,204 100 | }; 101 | mavlink_icarous_kinematic_bands_t packet1, packet2; 102 | memset(&packet1, 0, sizeof(packet1)); 103 | packet1.min1 = packet_in.min1; 104 | packet1.max1 = packet_in.max1; 105 | packet1.min2 = packet_in.min2; 106 | packet1.max2 = packet_in.max2; 107 | packet1.min3 = packet_in.min3; 108 | packet1.max3 = packet_in.max3; 109 | packet1.min4 = packet_in.min4; 110 | packet1.max4 = packet_in.max4; 111 | packet1.min5 = packet_in.min5; 112 | packet1.max5 = packet_in.max5; 113 | packet1.numBands = packet_in.numBands; 114 | packet1.type1 = packet_in.type1; 115 | packet1.type2 = packet_in.type2; 116 | packet1.type3 = packet_in.type3; 117 | packet1.type4 = packet_in.type4; 118 | packet1.type5 = packet_in.type5; 119 | 120 | 121 | #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 122 | if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { 123 | // cope with extensions 124 | memset(MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_MIN_LEN); 125 | } 126 | #endif 127 | memset(&packet2, 0, sizeof(packet2)); 128 | mavlink_msg_icarous_kinematic_bands_encode(system_id, component_id, &msg, &packet1); 129 | mavlink_msg_icarous_kinematic_bands_decode(&msg, &packet2); 130 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 131 | 132 | memset(&packet2, 0, sizeof(packet2)); 133 | mavlink_msg_icarous_kinematic_bands_pack(system_id, component_id, &msg , packet1.numBands , packet1.type1 , packet1.min1 , packet1.max1 , packet1.type2 , packet1.min2 , packet1.max2 , packet1.type3 , packet1.min3 , packet1.max3 , packet1.type4 , packet1.min4 , packet1.max4 , packet1.type5 , packet1.min5 , packet1.max5 ); 134 | mavlink_msg_icarous_kinematic_bands_decode(&msg, &packet2); 135 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 136 | 137 | memset(&packet2, 0, sizeof(packet2)); 138 | mavlink_msg_icarous_kinematic_bands_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.numBands , packet1.type1 , packet1.min1 , packet1.max1 , packet1.type2 , packet1.min2 , packet1.max2 , packet1.type3 , packet1.min3 , packet1.max3 , packet1.type4 , packet1.min4 , packet1.max4 , packet1.type5 , packet1.min5 , packet1.max5 ); 139 | mavlink_msg_icarous_kinematic_bands_decode(&msg, &packet2); 140 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 141 | 142 | memset(&packet2, 0, sizeof(packet2)); 143 | mavlink_msg_to_send_buffer(buffer, &msg); 144 | for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI >= 256) { 33 | return; 34 | } 35 | #endif 36 | mavlink_message_t msg; 37 | uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; 38 | uint16_t i; 39 | mavlink_loweheiser_gov_efi_t packet_in = { 40 | 17.0,45.0,73.0,101.0,129.0,157.0,963498712,963498920,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,521.0,549.0,21395,21499,1 41 | }; 42 | mavlink_loweheiser_gov_efi_t packet1, packet2; 43 | memset(&packet1, 0, sizeof(packet1)); 44 | packet1.volt_batt = packet_in.volt_batt; 45 | packet1.curr_batt = packet_in.curr_batt; 46 | packet1.curr_gen = packet_in.curr_gen; 47 | packet1.curr_rot = packet_in.curr_rot; 48 | packet1.fuel_level = packet_in.fuel_level; 49 | packet1.throttle = packet_in.throttle; 50 | packet1.runtime = packet_in.runtime; 51 | packet1.until_maintenance = packet_in.until_maintenance; 52 | packet1.rectifier_temp = packet_in.rectifier_temp; 53 | packet1.generator_temp = packet_in.generator_temp; 54 | packet1.efi_batt = packet_in.efi_batt; 55 | packet1.efi_rpm = packet_in.efi_rpm; 56 | packet1.efi_pw = packet_in.efi_pw; 57 | packet1.efi_fuel_flow = packet_in.efi_fuel_flow; 58 | packet1.efi_fuel_consumed = packet_in.efi_fuel_consumed; 59 | packet1.efi_baro = packet_in.efi_baro; 60 | packet1.efi_mat = packet_in.efi_mat; 61 | packet1.efi_clt = packet_in.efi_clt; 62 | packet1.efi_tps = packet_in.efi_tps; 63 | packet1.efi_exhaust_gas_temperature = packet_in.efi_exhaust_gas_temperature; 64 | packet1.generator_status = packet_in.generator_status; 65 | packet1.efi_status = packet_in.efi_status; 66 | packet1.efi_index = packet_in.efi_index; 67 | 68 | 69 | #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 70 | if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { 71 | // cope with extensions 72 | memset(MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_MIN_LEN); 73 | } 74 | #endif 75 | memset(&packet2, 0, sizeof(packet2)); 76 | mavlink_msg_loweheiser_gov_efi_encode(system_id, component_id, &msg, &packet1); 77 | mavlink_msg_loweheiser_gov_efi_decode(&msg, &packet2); 78 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 79 | 80 | memset(&packet2, 0, sizeof(packet2)); 81 | mavlink_msg_loweheiser_gov_efi_pack(system_id, component_id, &msg , packet1.volt_batt , packet1.curr_batt , packet1.curr_gen , packet1.curr_rot , packet1.fuel_level , packet1.throttle , packet1.runtime , packet1.until_maintenance , packet1.rectifier_temp , packet1.generator_temp , packet1.efi_batt , packet1.efi_rpm , packet1.efi_pw , packet1.efi_fuel_flow , packet1.efi_fuel_consumed , packet1.efi_baro , packet1.efi_mat , packet1.efi_clt , packet1.efi_tps , packet1.efi_exhaust_gas_temperature , packet1.efi_index , packet1.generator_status , packet1.efi_status ); 82 | mavlink_msg_loweheiser_gov_efi_decode(&msg, &packet2); 83 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 84 | 85 | memset(&packet2, 0, sizeof(packet2)); 86 | mavlink_msg_loweheiser_gov_efi_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.volt_batt , packet1.curr_batt , packet1.curr_gen , packet1.curr_rot , packet1.fuel_level , packet1.throttle , packet1.runtime , packet1.until_maintenance , packet1.rectifier_temp , packet1.generator_temp , packet1.efi_batt , packet1.efi_rpm , packet1.efi_pw , packet1.efi_fuel_flow , packet1.efi_fuel_consumed , packet1.efi_baro , packet1.efi_mat , packet1.efi_clt , packet1.efi_tps , packet1.efi_exhaust_gas_temperature , packet1.efi_index , packet1.generator_status , packet1.efi_status ); 87 | mavlink_msg_loweheiser_gov_efi_decode(&msg, &packet2); 88 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 89 | 90 | memset(&packet2, 0, sizeof(packet2)); 91 | mavlink_msg_to_send_buffer(buffer, &msg); 92 | for (i=0; i 12 | 13 | #ifndef M_PI_2 14 | #define M_PI_2 ((float)asin(1)) 15 | #endif 16 | 17 | /** 18 | * @file mavlink_conversions.h 19 | * 20 | * These conversion functions follow the NASA rotation standards definition file 21 | * available online. 22 | * 23 | * Their intent is to lower the barrier for MAVLink adopters to use gimbal-lock free 24 | * (both rotation matrices, sometimes called DCM, and quaternions are gimbal-lock free) 25 | * rotation representations. Euler angles (roll, pitch, yaw) will be phased out of the 26 | * protocol as widely as possible. 27 | * 28 | * @author James Goppert 29 | * @author Thomas Gubler 30 | */ 31 | 32 | 33 | /** 34 | * Converts a quaternion to a rotation matrix 35 | * 36 | * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0) 37 | * @param dcm a 3x3 rotation matrix 38 | */ 39 | MAVLINK_HELPER void mavlink_quaternion_to_dcm(const float quaternion[4], float dcm[3][3]) 40 | { 41 | double a = (double)quaternion[0]; 42 | double b = (double)quaternion[1]; 43 | double c = (double)quaternion[2]; 44 | double d = (double)quaternion[3]; 45 | double aSq = a * a; 46 | double bSq = b * b; 47 | double cSq = c * c; 48 | double dSq = d * d; 49 | dcm[0][0] = aSq + bSq - cSq - dSq; 50 | dcm[0][1] = 2 * (b * c - a * d); 51 | dcm[0][2] = 2 * (a * c + b * d); 52 | dcm[1][0] = 2 * (b * c + a * d); 53 | dcm[1][1] = aSq - bSq + cSq - dSq; 54 | dcm[1][2] = 2 * (c * d - a * b); 55 | dcm[2][0] = 2 * (b * d - a * c); 56 | dcm[2][1] = 2 * (a * b + c * d); 57 | dcm[2][2] = aSq - bSq - cSq + dSq; 58 | } 59 | 60 | 61 | /** 62 | * Converts a rotation matrix to euler angles 63 | * 64 | * @param dcm a 3x3 rotation matrix 65 | * @param roll the roll angle in radians 66 | * @param pitch the pitch angle in radians 67 | * @param yaw the yaw angle in radians 68 | */ 69 | MAVLINK_HELPER void mavlink_dcm_to_euler(const float dcm[3][3], float* roll, float* pitch, float* yaw) 70 | { 71 | float phi, theta, psi; 72 | theta = asinf(-dcm[2][0]); 73 | 74 | if (fabsf(theta - (float)M_PI_2) < 1.0e-3f) { 75 | phi = 0.0f; 76 | psi = (atan2f(dcm[1][2] - dcm[0][1], 77 | dcm[0][2] + dcm[1][1]) + phi); 78 | 79 | } else if (fabsf(theta + (float)M_PI_2) < 1.0e-3f) { 80 | phi = 0.0f; 81 | psi = atan2f(dcm[1][2] - dcm[0][1], 82 | dcm[0][2] + dcm[1][1] - phi); 83 | 84 | } else { 85 | phi = atan2f(dcm[2][1], dcm[2][2]); 86 | psi = atan2f(dcm[1][0], dcm[0][0]); 87 | } 88 | 89 | *roll = phi; 90 | *pitch = theta; 91 | *yaw = psi; 92 | } 93 | 94 | 95 | /** 96 | * Converts a quaternion to euler angles 97 | * 98 | * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0) 99 | * @param roll the roll angle in radians 100 | * @param pitch the pitch angle in radians 101 | * @param yaw the yaw angle in radians 102 | */ 103 | MAVLINK_HELPER void mavlink_quaternion_to_euler(const float quaternion[4], float* roll, float* pitch, float* yaw) 104 | { 105 | float dcm[3][3]; 106 | mavlink_quaternion_to_dcm(quaternion, dcm); 107 | mavlink_dcm_to_euler((const float(*)[3])dcm, roll, pitch, yaw); 108 | } 109 | 110 | 111 | /** 112 | * Converts euler angles to a quaternion 113 | * 114 | * @param roll the roll angle in radians 115 | * @param pitch the pitch angle in radians 116 | * @param yaw the yaw angle in radians 117 | * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0) 118 | */ 119 | MAVLINK_HELPER void mavlink_euler_to_quaternion(float roll, float pitch, float yaw, float quaternion[4]) 120 | { 121 | float cosPhi_2 = cosf(roll / 2); 122 | float sinPhi_2 = sinf(roll / 2); 123 | float cosTheta_2 = cosf(pitch / 2); 124 | float sinTheta_2 = sinf(pitch / 2); 125 | float cosPsi_2 = cosf(yaw / 2); 126 | float sinPsi_2 = sinf(yaw / 2); 127 | quaternion[0] = (cosPhi_2 * cosTheta_2 * cosPsi_2 + 128 | sinPhi_2 * sinTheta_2 * sinPsi_2); 129 | quaternion[1] = (sinPhi_2 * cosTheta_2 * cosPsi_2 - 130 | cosPhi_2 * sinTheta_2 * sinPsi_2); 131 | quaternion[2] = (cosPhi_2 * sinTheta_2 * cosPsi_2 + 132 | sinPhi_2 * cosTheta_2 * sinPsi_2); 133 | quaternion[3] = (cosPhi_2 * cosTheta_2 * sinPsi_2 - 134 | sinPhi_2 * sinTheta_2 * cosPsi_2); 135 | } 136 | 137 | 138 | /** 139 | * Converts a rotation matrix to a quaternion 140 | * Reference: 141 | * - Shoemake, Quaternions, 142 | * http://www.cs.ucr.edu/~vbz/resources/quatut.pdf 143 | * 144 | * @param dcm a 3x3 rotation matrix 145 | * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0) 146 | */ 147 | MAVLINK_HELPER void mavlink_dcm_to_quaternion(const float dcm[3][3], float quaternion[4]) 148 | { 149 | float tr = dcm[0][0] + dcm[1][1] + dcm[2][2]; 150 | if (tr > 0.0f) { 151 | float s = sqrtf(tr + 1.0f); 152 | quaternion[0] = s * 0.5f; 153 | s = 0.5f / s; 154 | quaternion[1] = (dcm[2][1] - dcm[1][2]) * s; 155 | quaternion[2] = (dcm[0][2] - dcm[2][0]) * s; 156 | quaternion[3] = (dcm[1][0] - dcm[0][1]) * s; 157 | } else { 158 | /* Find maximum diagonal element in dcm 159 | * store index in dcm_i */ 160 | int dcm_i = 0; 161 | int i; 162 | for (i = 1; i < 3; i++) { 163 | if (dcm[i][i] > dcm[dcm_i][dcm_i]) { 164 | dcm_i = i; 165 | } 166 | } 167 | 168 | int dcm_j = (dcm_i + 1) % 3; 169 | int dcm_k = (dcm_i + 2) % 3; 170 | 171 | float s = sqrtf((dcm[dcm_i][dcm_i] - dcm[dcm_j][dcm_j] - 172 | dcm[dcm_k][dcm_k]) + 1.0f); 173 | quaternion[dcm_i + 1] = s * 0.5f; 174 | s = 0.5f / s; 175 | quaternion[dcm_j + 1] = (dcm[dcm_i][dcm_j] + dcm[dcm_j][dcm_i]) * s; 176 | quaternion[dcm_k + 1] = (dcm[dcm_k][dcm_i] + dcm[dcm_i][dcm_k]) * s; 177 | quaternion[0] = (dcm[dcm_k][dcm_j] - dcm[dcm_j][dcm_k]) * s; 178 | } 179 | } 180 | 181 | 182 | /** 183 | * Converts euler angles to a rotation matrix 184 | * 185 | * @param roll the roll angle in radians 186 | * @param pitch the pitch angle in radians 187 | * @param yaw the yaw angle in radians 188 | * @param dcm a 3x3 rotation matrix 189 | */ 190 | MAVLINK_HELPER void mavlink_euler_to_dcm(float roll, float pitch, float yaw, float dcm[3][3]) 191 | { 192 | float cosPhi = cosf(roll); 193 | float sinPhi = sinf(roll); 194 | float cosThe = cosf(pitch); 195 | float sinThe = sinf(pitch); 196 | float cosPsi = cosf(yaw); 197 | float sinPsi = sinf(yaw); 198 | 199 | dcm[0][0] = cosThe * cosPsi; 200 | dcm[0][1] = -cosPhi * sinPsi + sinPhi * sinThe * cosPsi; 201 | dcm[0][2] = sinPhi * sinPsi + cosPhi * sinThe * cosPsi; 202 | 203 | dcm[1][0] = cosThe * sinPsi; 204 | dcm[1][1] = cosPhi * cosPsi + sinPhi * sinThe * sinPsi; 205 | dcm[1][2] = -sinPhi * cosPsi + cosPhi * sinThe * sinPsi; 206 | 207 | dcm[2][0] = -sinThe; 208 | dcm[2][1] = sinPhi * cosThe; 209 | dcm[2][2] = cosPhi * cosThe; 210 | } 211 | 212 | #endif // MAVLINK_NO_CONVERSION_HELPERS 213 | -------------------------------------------------------------------------------- /mavlink/mavlink_get_info.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #ifdef MAVLINK_USE_MESSAGE_INFO 4 | #define MAVLINK_HAVE_GET_MESSAGE_INFO 5 | 6 | /* 7 | return the message_info struct for a message 8 | */ 9 | MAVLINK_HELPER const mavlink_message_info_t *mavlink_get_message_info_by_id(uint32_t msgid) 10 | { 11 | static const mavlink_message_info_t mavlink_message_info[] = MAVLINK_MESSAGE_INFO; 12 | /* 13 | use a bisection search to find the right entry. A perfect hash may be better 14 | Note that this assumes the table is sorted with primary key msgid 15 | */ 16 | const uint32_t count = sizeof(mavlink_message_info)/sizeof(mavlink_message_info[0]); 17 | if (count == 0) { 18 | return NULL; 19 | } 20 | uint32_t low=0, high=count-1; 21 | while (low < high) { 22 | uint32_t mid = (low+high)/2; 23 | if (msgid < mavlink_message_info[mid].msgid) { 24 | high = mid; 25 | continue; 26 | } 27 | if (msgid > mavlink_message_info[mid].msgid) { 28 | low = mid+1; 29 | continue; 30 | } 31 | return &mavlink_message_info[mid]; 32 | } 33 | if (mavlink_message_info[low].msgid == msgid) { 34 | return &mavlink_message_info[low]; 35 | } 36 | return NULL; 37 | } 38 | 39 | /* 40 | return the message_info struct for a message 41 | */ 42 | MAVLINK_HELPER const mavlink_message_info_t *mavlink_get_message_info(const mavlink_message_t *msg) 43 | { 44 | return mavlink_get_message_info_by_id(msg->msgid); 45 | } 46 | 47 | /* 48 | return the message_info struct for a message 49 | */ 50 | MAVLINK_HELPER const mavlink_message_info_t *mavlink_get_message_info_by_name(const char *name) 51 | { 52 | static const struct { const char *name; uint32_t msgid; } mavlink_message_names[] = MAVLINK_MESSAGE_NAMES; 53 | /* 54 | use a bisection search to find the right entry. A perfect hash may be better 55 | Note that this assumes the table is sorted with primary key name 56 | */ 57 | const uint32_t count = sizeof(mavlink_message_names)/sizeof(mavlink_message_names[0]); 58 | if (count == 0) { 59 | return NULL; 60 | } 61 | uint32_t low=0, high=count-1; 62 | while (low < high) { 63 | uint32_t mid = (low+high)/2; 64 | int cmp = strcmp(mavlink_message_names[mid].name, name); 65 | if (cmp > 0) { 66 | high = mid; 67 | continue; 68 | } 69 | if (cmp < 0) { 70 | low = mid+1; 71 | continue; 72 | } 73 | low = mid; 74 | break; 75 | } 76 | if (strcmp(mavlink_message_names[low].name, name) == 0) { 77 | return mavlink_get_message_info_by_id(mavlink_message_names[low].msgid); 78 | } 79 | return NULL; 80 | } 81 | #endif // MAVLINK_USE_MESSAGE_INFO 82 | 83 | 84 | -------------------------------------------------------------------------------- /mavlink/mavlink_sha256.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | /* 4 | sha-256 implementation for MAVLink based on Heimdal sources, with 5 | modifications to suit mavlink headers 6 | */ 7 | /* 8 | * Copyright (c) 1995 - 2001 Kungliga Tekniska Högskolan 9 | * (Royal Institute of Technology, Stockholm, Sweden). 10 | * All rights reserved. 11 | * 12 | * Redistribution and use in source and binary forms, with or without 13 | * modification, are permitted provided that the following conditions 14 | * are met: 15 | * 16 | * 1. Redistributions of source code must retain the above copyright 17 | * notice, this list of conditions and the following disclaimer. 18 | * 19 | * 2. Redistributions in binary form must reproduce the above copyright 20 | * notice, this list of conditions and the following disclaimer in the 21 | * documentation and/or other materials provided with the distribution. 22 | * 23 | * 3. Neither the name of the Institute nor the names of its contributors 24 | * may be used to endorse or promote products derived from this software 25 | * without specific prior written permission. 26 | * 27 | * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND 28 | * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 29 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 30 | * ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE 31 | * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 32 | * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS 33 | * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) 34 | * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 35 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY 36 | * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF 37 | * SUCH DAMAGE. 38 | */ 39 | 40 | /* 41 | allow implementation to provide their own sha256 with the same API 42 | */ 43 | #ifndef HAVE_MAVLINK_SHA256 44 | 45 | #ifdef MAVLINK_USE_CXX_NAMESPACE 46 | namespace mavlink { 47 | #endif 48 | 49 | #ifndef MAVLINK_HELPER 50 | #define MAVLINK_HELPER 51 | #endif 52 | 53 | typedef struct { 54 | uint32_t sz[2]; 55 | uint32_t counter[8]; 56 | union { 57 | unsigned char save_bytes[64]; 58 | uint32_t save_u32[16]; 59 | } u; 60 | } mavlink_sha256_ctx; 61 | 62 | #define Ch(x,y,z) (((x) & (y)) ^ ((~(x)) & (z))) 63 | #define Maj(x,y,z) (((x) & (y)) ^ ((x) & (z)) ^ ((y) & (z))) 64 | 65 | #define ROTR(x,n) (((x)>>(n)) | ((x) << (32 - (n)))) 66 | 67 | #define Sigma0(x) (ROTR(x,2) ^ ROTR(x,13) ^ ROTR(x,22)) 68 | #define Sigma1(x) (ROTR(x,6) ^ ROTR(x,11) ^ ROTR(x,25)) 69 | #define sigma0(x) (ROTR(x,7) ^ ROTR(x,18) ^ ((x)>>3)) 70 | #define sigma1(x) (ROTR(x,17) ^ ROTR(x,19) ^ ((x)>>10)) 71 | 72 | static const uint32_t mavlink_sha256_constant_256[64] = { 73 | 0x428a2f98, 0x71374491, 0xb5c0fbcf, 0xe9b5dba5, 74 | 0x3956c25b, 0x59f111f1, 0x923f82a4, 0xab1c5ed5, 75 | 0xd807aa98, 0x12835b01, 0x243185be, 0x550c7dc3, 76 | 0x72be5d74, 0x80deb1fe, 0x9bdc06a7, 0xc19bf174, 77 | 0xe49b69c1, 0xefbe4786, 0x0fc19dc6, 0x240ca1cc, 78 | 0x2de92c6f, 0x4a7484aa, 0x5cb0a9dc, 0x76f988da, 79 | 0x983e5152, 0xa831c66d, 0xb00327c8, 0xbf597fc7, 80 | 0xc6e00bf3, 0xd5a79147, 0x06ca6351, 0x14292967, 81 | 0x27b70a85, 0x2e1b2138, 0x4d2c6dfc, 0x53380d13, 82 | 0x650a7354, 0x766a0abb, 0x81c2c92e, 0x92722c85, 83 | 0xa2bfe8a1, 0xa81a664b, 0xc24b8b70, 0xc76c51a3, 84 | 0xd192e819, 0xd6990624, 0xf40e3585, 0x106aa070, 85 | 0x19a4c116, 0x1e376c08, 0x2748774c, 0x34b0bcb5, 86 | 0x391c0cb3, 0x4ed8aa4a, 0x5b9cca4f, 0x682e6ff3, 87 | 0x748f82ee, 0x78a5636f, 0x84c87814, 0x8cc70208, 88 | 0x90befffa, 0xa4506ceb, 0xbef9a3f7, 0xc67178f2 89 | }; 90 | 91 | MAVLINK_HELPER void mavlink_sha256_init(mavlink_sha256_ctx *m) 92 | { 93 | m->sz[0] = 0; 94 | m->sz[1] = 0; 95 | m->counter[0] = 0x6a09e667; 96 | m->counter[1] = 0xbb67ae85; 97 | m->counter[2] = 0x3c6ef372; 98 | m->counter[3] = 0xa54ff53a; 99 | m->counter[4] = 0x510e527f; 100 | m->counter[5] = 0x9b05688c; 101 | m->counter[6] = 0x1f83d9ab; 102 | m->counter[7] = 0x5be0cd19; 103 | } 104 | 105 | static inline void mavlink_sha256_calc(mavlink_sha256_ctx *m, uint32_t *in) 106 | { 107 | uint32_t AA, BB, CC, DD, EE, FF, GG, HH; 108 | uint32_t data[64]; 109 | int i; 110 | 111 | AA = m->counter[0]; 112 | BB = m->counter[1]; 113 | CC = m->counter[2]; 114 | DD = m->counter[3]; 115 | EE = m->counter[4]; 116 | FF = m->counter[5]; 117 | GG = m->counter[6]; 118 | HH = m->counter[7]; 119 | 120 | for (i = 0; i < 16; ++i) 121 | data[i] = in[i]; 122 | for (i = 16; i < 64; ++i) 123 | data[i] = sigma1(data[i-2]) + data[i-7] + 124 | sigma0(data[i-15]) + data[i - 16]; 125 | 126 | for (i = 0; i < 64; i++) { 127 | uint32_t T1, T2; 128 | 129 | T1 = HH + Sigma1(EE) + Ch(EE, FF, GG) + mavlink_sha256_constant_256[i] + data[i]; 130 | T2 = Sigma0(AA) + Maj(AA,BB,CC); 131 | 132 | HH = GG; 133 | GG = FF; 134 | FF = EE; 135 | EE = DD + T1; 136 | DD = CC; 137 | CC = BB; 138 | BB = AA; 139 | AA = T1 + T2; 140 | } 141 | 142 | m->counter[0] += AA; 143 | m->counter[1] += BB; 144 | m->counter[2] += CC; 145 | m->counter[3] += DD; 146 | m->counter[4] += EE; 147 | m->counter[5] += FF; 148 | m->counter[6] += GG; 149 | m->counter[7] += HH; 150 | } 151 | 152 | MAVLINK_HELPER void mavlink_sha256_update(mavlink_sha256_ctx *m, const void *v, uint32_t len) 153 | { 154 | const unsigned char *p = (const unsigned char *)v; 155 | uint32_t old_sz = m->sz[0]; 156 | uint32_t offset; 157 | 158 | m->sz[0] += len * 8; 159 | if (m->sz[0] < old_sz) 160 | ++m->sz[1]; 161 | offset = (old_sz / 8) % 64; 162 | while(len > 0){ 163 | uint32_t l = 64 - offset; 164 | if (len < l) { 165 | l = len; 166 | } 167 | memcpy(m->u.save_bytes + offset, p, l); 168 | offset += l; 169 | p += l; 170 | len -= l; 171 | if(offset == 64){ 172 | int i; 173 | uint32_t current[16]; 174 | const uint32_t *u = m->u.save_u32; 175 | for (i = 0; i < 16; i++){ 176 | const uint8_t *p1 = (const uint8_t *)&u[i]; 177 | uint8_t *p2 = (uint8_t *)¤t[i]; 178 | p2[0] = p1[3]; 179 | p2[1] = p1[2]; 180 | p2[2] = p1[1]; 181 | p2[3] = p1[0]; 182 | } 183 | mavlink_sha256_calc(m, current); 184 | offset = 0; 185 | } 186 | } 187 | } 188 | 189 | /* 190 | get first 48 bits of final sha256 hash 191 | */ 192 | MAVLINK_HELPER void mavlink_sha256_final_48(mavlink_sha256_ctx *m, uint8_t result[6]) 193 | { 194 | unsigned char zeros[72]; 195 | unsigned offset = (m->sz[0] / 8) % 64; 196 | unsigned int dstart = (120 - offset - 1) % 64 + 1; 197 | uint8_t *p = (uint8_t *)&m->counter[0]; 198 | 199 | *zeros = 0x80; 200 | memset (zeros + 1, 0, sizeof(zeros) - 1); 201 | zeros[dstart+7] = (m->sz[0] >> 0) & 0xff; 202 | zeros[dstart+6] = (m->sz[0] >> 8) & 0xff; 203 | zeros[dstart+5] = (m->sz[0] >> 16) & 0xff; 204 | zeros[dstart+4] = (m->sz[0] >> 24) & 0xff; 205 | zeros[dstart+3] = (m->sz[1] >> 0) & 0xff; 206 | zeros[dstart+2] = (m->sz[1] >> 8) & 0xff; 207 | zeros[dstart+1] = (m->sz[1] >> 16) & 0xff; 208 | zeros[dstart+0] = (m->sz[1] >> 24) & 0xff; 209 | 210 | mavlink_sha256_update(m, zeros, dstart + 8); 211 | 212 | // this ordering makes the result consistent with taking the first 213 | // 6 bytes of more conventional sha256 functions. It assumes 214 | // little-endian ordering of m->counter 215 | result[0] = p[3]; 216 | result[1] = p[2]; 217 | result[2] = p[1]; 218 | result[3] = p[0]; 219 | result[4] = p[7]; 220 | result[5] = p[6]; 221 | } 222 | 223 | // prevent conflicts with users of the header 224 | #undef Ch 225 | #undef ROTR 226 | #undef Sigma0 227 | #undef Sigma1 228 | #undef sigma0 229 | #undef sigma1 230 | 231 | #ifdef MAVLINK_USE_CXX_NAMESPACE 232 | } // namespace mavlink 233 | #endif 234 | 235 | #endif // HAVE_MAVLINK_SHA256 236 | -------------------------------------------------------------------------------- /mavlink/message_definitions/AVSSUAS.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | common.xml 10 | 2 11 | 1 12 | 13 | 14 | 15 | 16 | AVSS defined command. Set PRS arm statuses. 17 | PRS arm statuses 18 | User defined 19 | User defined 20 | User defined 21 | User defined 22 | User defined 23 | User defined 24 | 25 | 26 | AVSS defined command. Gets PRS arm statuses 27 | User defined 28 | User defined 29 | User defined 30 | User defined 31 | User defined 32 | User defined 33 | User defined 34 | 35 | 36 | AVSS defined command. Get the PRS battery voltage in millivolts 37 | User defined 38 | User defined 39 | User defined 40 | User defined 41 | User defined 42 | User defined 43 | User defined 44 | 45 | 46 | AVSS defined command. Get the PRS error statuses. 47 | User defined 48 | User defined 49 | User defined 50 | User defined 51 | User defined 52 | User defined 53 | User defined 54 | 55 | 56 | AVSS defined command. Set the ATS arming altitude in meters. 57 | ATS arming altitude 58 | User defined 59 | User defined 60 | User defined 61 | User defined 62 | User defined 63 | User defined 64 | 65 | 66 | AVSS defined command. Get the ATS arming altitude in meters. 67 | User defined 68 | User defined 69 | User defined 70 | User defined 71 | User defined 72 | User defined 73 | User defined 74 | 75 | 76 | AVSS defined command. Shuts down the PRS system. 77 | User defined 78 | User defined 79 | User defined 80 | User defined 81 | User defined 82 | User defined 83 | User defined 84 | 85 | 86 | 87 | 88 | AVSS defined command failure reason. PRS not steady. 89 | 90 | 91 | AVSS defined command failure reason. PRS DTM not armed. 92 | 93 | 94 | AVSS defined command failure reason. PRS OTM not armed. 95 | 96 | 97 | 98 | 99 | In manual control mode 100 | 101 | 102 | In attitude mode 103 | 104 | 105 | In GPS mode 106 | 107 | 108 | In hotpoint mode 109 | 110 | 111 | In assisted takeoff mode 112 | 113 | 114 | In auto takeoff mode 115 | 116 | 117 | In auto landing mode 118 | 119 | 120 | In go home mode 121 | 122 | 123 | In sdk control mode 124 | 125 | 126 | In sport mode 127 | 128 | 129 | In force auto landing mode 130 | 131 | 132 | In tripod mode 133 | 134 | 135 | In search mode 136 | 137 | 138 | In engine mode 139 | 140 | 141 | 142 | 143 | In manual control mode 144 | 145 | 146 | In auto takeoff mode 147 | 148 | 149 | In auto landing mode 150 | 151 | 152 | In go home mode 153 | 154 | 155 | In drop mode 156 | 157 | 158 | 159 | 160 | 161 | AVSS PRS system status. 162 | Timestamp (time since PRS boot). 163 | PRS error statuses 164 | Estimated battery run-time without a remote connection and PRS battery voltage 165 | PRS arm statuses 166 | PRS battery charge statuses 167 | 168 | 169 | Drone position. 170 | Timestamp (time since FC boot). 171 | Latitude, expressed 172 | Longitude, expressed 173 | Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL. 174 | Altitude above ground, This altitude is measured by a ultrasound, Laser rangefinder or millimeter-wave radar 175 | This altitude is measured by a barometer 176 | 177 | 178 | Drone IMU data. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0). 179 | Timestamp (time since FC boot). 180 | Quaternion component 1, w (1 in null-rotation) 181 | Quaternion component 2, x (0 in null-rotation) 182 | Quaternion component 3, y (0 in null-rotation) 183 | Quaternion component 4, z (0 in null-rotation) 184 | X acceleration 185 | Y acceleration 186 | Z acceleration 187 | Angular speed around X axis 188 | Angular speed around Y axis 189 | Angular speed around Z axis 190 | 191 | 192 | Drone operation mode. 193 | Timestamp (time since FC boot). 194 | DJI M300 operation mode 195 | horsefly operation mode 196 | 197 | 198 | 199 | -------------------------------------------------------------------------------- /mavlink/message_definitions/all.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 7 | ardupilotmega.xml 8 | 12 | ASLUAV.xml 13 | 18 | common.xml 19 | development.xml 20 | 24 | icarous.xml 25 | 26 | 27 | minimal.xml 28 | 29 | 30 | python_array_test.xml 31 | standard.xml 32 | test.xml 33 | ualberta.xml 34 | 38 | uAvionix.xml 39 | 43 | storm32.xml 44 | 48 | AVSSUAS.xml 49 | 53 | cubepilot.xml 54 | 59 | csAirLink.xml 60 | 64 | 68 | 72 | 73 | 74 | 75 | 76 | 77 | 78 | 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 79 | 80 | 81 | Dummy/temporary MAV_CMD that causes all.xml to correctly import all commands from both ardupilotmega.xml and development.xml (otherwise only one is imported, for the reasons given in https://github.com/ArduPilot/pymavlink/pull/544#discussion_r2069976980). 82 | It not be used, and will be removed when the toolchain is fixed. 83 | 84 | 85 | 86 | 87 | 88 | -------------------------------------------------------------------------------- /mavlink/message_definitions/csAirLink.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 3 8 | 9 | 10 | 11 | Login or password error 12 | 13 | 14 | Auth successful 15 | 16 | 17 | 18 | 19 | 20 | Authorization package 21 | Login 22 | Password 23 | 24 | 25 | Response to the authorization request 26 | Response type 27 | 28 | 29 | 30 | -------------------------------------------------------------------------------- /mavlink/message_definitions/cubepilot.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | common.xml 8 | 9 | 10 | Raw RC Data 11 | 12 | 13 | 14 | Information about video stream 15 | Video Stream ID (1 for first, 2 for second, etc.) 16 | Number of streams available. 17 | Frame rate. 18 | Horizontal resolution. 19 | Vertical resolution. 20 | Bit rate. 21 | Video image rotation clockwise. 22 | Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to). 23 | 24 | 25 | Herelink Telemetry 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | Start firmware update with encapsulated data. 36 | System ID. 37 | Component ID. 38 | FW Size. 39 | FW CRC. 40 | 41 | 42 | offset response to encapsulated data. 43 | System ID. 44 | Component ID. 45 | FW Offset. 46 | 47 | 48 | 49 | -------------------------------------------------------------------------------- /mavlink/message_definitions/icarous.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | ICAROUS heartbeat 26 | See the FMS_STATE enum. 27 | 28 | 29 | Kinematic multi bands (track) output from Daidalus 30 | Number of track bands 31 | See the TRACK_BAND_TYPES enum. 32 | min angle (degrees) 33 | max angle (degrees) 34 | See the TRACK_BAND_TYPES enum. 35 | min angle (degrees) 36 | max angle (degrees) 37 | See the TRACK_BAND_TYPES enum. 38 | min angle (degrees) 39 | max angle (degrees) 40 | See the TRACK_BAND_TYPES enum. 41 | min angle (degrees) 42 | max angle (degrees) 43 | See the TRACK_BAND_TYPES enum. 44 | min angle (degrees) 45 | max angle (degrees) 46 | 47 | 48 | 49 | -------------------------------------------------------------------------------- /mavlink/message_definitions/loweheiser.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | minimal.xml 9 | 10 | 11 | 12 | 13 | Set Loweheiser desired states 14 | EFI Index 15 | Desired Engine/EFI State (0: Power Off, 1:Running) 16 | Desired Governor State (0:manual throttle, 1:Governed throttle) 17 | Manual throttle level, 0% - 100% 18 | Electronic Start up (0:Off, 1:On) 19 | Empty 20 | Empty 21 | 22 | 23 | 24 | 25 | 26 | Composite EFI and Governor data from Loweheiser equipment. This message is created by the EFI unit based on its own data and data received from a governor attached to that EFI unit. 27 | 28 | Generator Battery voltage. 29 | Generator Battery current. 30 | Current being produced by generator. 31 | Load current being consumed by the UAV (sum of curr_gen and curr_batt) 32 | Generator fuel remaining in litres. 33 | Throttle Output. 34 | Seconds this generator has run since it was rebooted. 35 | Seconds until this generator requires maintenance. A negative value indicates maintenance is past due. 36 | The Temperature of the rectifier. 37 | The temperature of the mechanical motor, fuel cell core or generator. 38 | 39 | EFI Supply Voltage. 40 | Motor RPM. 41 | Injector pulse-width in miliseconds. 42 | Fuel flow rate in litres/hour. 43 | Fuel consumed. 44 | Atmospheric pressure. 45 | Manifold Air Temperature. 46 | Cylinder Head Temperature. 47 | Throttle Position. 48 | Exhaust gas temperature. 49 | 50 | EFI index. 51 | Generator status. 52 | EFI status. 53 | 54 | 55 | 56 | -------------------------------------------------------------------------------- /mavlink/message_definitions/paparazzi.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | common.xml 4 | 3 5 | 6 | 7 | 8 | 9 | 10 | Message encoding a mission script item. This message is emitted upon a request for the next script item. 11 | System ID 12 | Component ID 13 | Sequence 14 | The name of the mission script, NULL terminated. 15 | 16 | 17 | Request script item with the sequence number seq. The response of the system to this message should be a SCRIPT_ITEM message. 18 | System ID 19 | Component ID 20 | Sequence 21 | 22 | 23 | Request the overall list of mission items from the system/component. 24 | System ID 25 | Component ID 26 | 27 | 28 | This message is emitted as response to SCRIPT_REQUEST_LIST by the MAV to get the number of mission scripts. 29 | System ID 30 | Component ID 31 | Number of script items in the sequence 32 | 33 | 34 | This message informs about the currently active SCRIPT. 35 | Active Sequence 36 | 37 | 38 | 39 | -------------------------------------------------------------------------------- /mavlink/message_definitions/python_array_test.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | common.xml 5 | 6 | 7 | Array test #0. 8 | Stub field 9 | Value array 10 | Value array 11 | Value array 12 | Value array 13 | 14 | 15 | Array test #1. 16 | Value array 17 | 18 | 19 | Array test #3. 20 | Stub field 21 | Value array 22 | 23 | 24 | Array test #4. 25 | Value array 26 | Stub field 27 | 28 | 29 | Array test #5. 30 | Value array 31 | Value array 32 | 33 | 34 | Array test #6. 35 | Stub field 36 | Stub field 37 | Stub field 38 | Value array 39 | Value array 40 | Value array 41 | Value array 42 | Value array 43 | Value array 44 | Value array 45 | Value array 46 | Value array 47 | 48 | 49 | Array test #7. 50 | Value array 51 | Value array 52 | Value array 53 | Value array 54 | Value array 55 | Value array 56 | Value array 57 | Value array 58 | Value array 59 | 60 | 61 | Array test #8. 62 | Stub field 63 | Value array 64 | Value array 65 | 66 | 67 | 68 | -------------------------------------------------------------------------------- /mavlink/message_definitions/standard.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | minimal.xml 5 | 0 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /mavlink/message_definitions/test.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 3 4 | 5 | 6 | Test all field types 7 | char 8 | string 9 | uint8_t 10 | uint16_t 11 | uint32_t 12 | uint64_t 13 | int8_t 14 | int16_t 15 | int32_t 16 | int64_t 17 | float 18 | double 19 | uint8_t_array 20 | uint16_t_array 21 | uint32_t_array 22 | uint64_t_array 23 | int8_t_array 24 | int16_t_array 25 | int32_t_array 26 | int64_t_array 27 | float_array 28 | double_array 29 | 30 | 31 | 32 | -------------------------------------------------------------------------------- /mavlink/message_definitions/ualberta.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | common.xml 4 | 5 | 6 | Available autopilot modes for ualberta uav 7 | 8 | Raw input pulse widts sent to output 9 | 10 | 11 | Inputs are normalized using calibration, the converted back to raw pulse widths for output 12 | 13 | 14 | 15 | 16 | 17 | 18 | Navigation filter mode 19 | 20 | 21 | AHRS mode 22 | 23 | 24 | INS/GPS initialization mode 25 | 26 | 27 | INS/GPS mode 28 | 29 | 30 | 31 | Mode currently commanded by pilot 32 | 33 | 34 | 35 | Rotomotion mode 36 | 37 | 38 | 39 | 40 | 41 | Accelerometer and Gyro biases from the navigation filter 42 | Timestamp (microseconds) 43 | b_f[0] 44 | b_f[1] 45 | b_f[2] 46 | b_f[0] 47 | b_f[1] 48 | b_f[2] 49 | 50 | 51 | Complete set of calibration parameters for the radio 52 | Aileron setpoints: left, center, right 53 | Elevator setpoints: nose down, center, nose up 54 | Rudder setpoints: nose left, center, nose right 55 | Tail gyro mode/gain setpoints: heading hold, rate mode 56 | Pitch curve setpoints (every 25%) 57 | Throttle curve setpoints (every 25%) 58 | 59 | 60 | System status specific to ualberta uav 61 | System mode, see UALBERTA_AUTOPILOT_MODE ENUM 62 | Navigation mode, see UALBERTA_NAV_MODE ENUM 63 | Pilot mode, see UALBERTA_PILOT_MODE 64 | 65 | 66 | 67 | -------------------------------------------------------------------------------- /mavlink/minimal/mavlink.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol built from minimal.xml 3 | * @see http://mavlink.org 4 | */ 5 | #pragma once 6 | #ifndef MAVLINK_H 7 | #define MAVLINK_H 8 | 9 | #define MAVLINK_PRIMARY_XML_HASH 7567541546791713914 10 | 11 | #ifndef MAVLINK_STX 12 | #define MAVLINK_STX 253 13 | #endif 14 | 15 | #ifndef MAVLINK_ENDIAN 16 | #define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN 17 | #endif 18 | 19 | #ifndef MAVLINK_ALIGNED_FIELDS 20 | #define MAVLINK_ALIGNED_FIELDS 1 21 | #endif 22 | 23 | #ifndef MAVLINK_CRC_EXTRA 24 | #define MAVLINK_CRC_EXTRA 1 25 | #endif 26 | 27 | #ifndef MAVLINK_COMMAND_24BIT 28 | #define MAVLINK_COMMAND_24BIT 1 29 | #endif 30 | 31 | #include "version.h" 32 | #include "minimal.h" 33 | 34 | #endif // MAVLINK_H 35 | -------------------------------------------------------------------------------- /mavlink/minimal/testsuite.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol testsuite generated from minimal.xml 3 | * @see https://mavlink.io/en/ 4 | */ 5 | #pragma once 6 | #ifndef MINIMAL_TESTSUITE_H 7 | #define MINIMAL_TESTSUITE_H 8 | 9 | #ifdef __cplusplus 10 | extern "C" { 11 | #endif 12 | 13 | #ifndef MAVLINK_TEST_ALL 14 | #define MAVLINK_TEST_ALL 15 | 16 | static void mavlink_test_minimal(uint8_t, uint8_t, mavlink_message_t *last_msg); 17 | 18 | static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) 19 | { 20 | 21 | mavlink_test_minimal(system_id, component_id, last_msg); 22 | } 23 | #endif 24 | 25 | 26 | 27 | 28 | static void mavlink_test_heartbeat(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) 29 | { 30 | #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 31 | mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0); 32 | if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HEARTBEAT >= 256) { 33 | return; 34 | } 35 | #endif 36 | mavlink_message_t msg; 37 | uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; 38 | uint16_t i; 39 | mavlink_heartbeat_t packet_in = { 40 | 963497464,17,84,151,218,3 41 | }; 42 | mavlink_heartbeat_t packet1, packet2; 43 | memset(&packet1, 0, sizeof(packet1)); 44 | packet1.custom_mode = packet_in.custom_mode; 45 | packet1.type = packet_in.type; 46 | packet1.autopilot = packet_in.autopilot; 47 | packet1.base_mode = packet_in.base_mode; 48 | packet1.system_status = packet_in.system_status; 49 | packet1.mavlink_version = packet_in.mavlink_version; 50 | 51 | 52 | #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 53 | if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { 54 | // cope with extensions 55 | memset(MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN); 56 | } 57 | #endif 58 | memset(&packet2, 0, sizeof(packet2)); 59 | mavlink_msg_heartbeat_encode(system_id, component_id, &msg, &packet1); 60 | mavlink_msg_heartbeat_decode(&msg, &packet2); 61 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 62 | 63 | memset(&packet2, 0, sizeof(packet2)); 64 | mavlink_msg_heartbeat_pack(system_id, component_id, &msg , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status ); 65 | mavlink_msg_heartbeat_decode(&msg, &packet2); 66 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 67 | 68 | memset(&packet2, 0, sizeof(packet2)); 69 | mavlink_msg_heartbeat_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status ); 70 | mavlink_msg_heartbeat_decode(&msg, &packet2); 71 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 72 | 73 | memset(&packet2, 0, sizeof(packet2)); 74 | mavlink_msg_to_send_buffer(buffer, &msg); 75 | for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PROTOCOL_VERSION >= 256) { 97 | return; 98 | } 99 | #endif 100 | mavlink_message_t msg; 101 | uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; 102 | uint16_t i; 103 | mavlink_protocol_version_t packet_in = { 104 | 17235,17339,17443,{ 151, 152, 153, 154, 155, 156, 157, 158 },{ 175, 176, 177, 178, 179, 180, 181, 182 } 105 | }; 106 | mavlink_protocol_version_t packet1, packet2; 107 | memset(&packet1, 0, sizeof(packet1)); 108 | packet1.version = packet_in.version; 109 | packet1.min_version = packet_in.min_version; 110 | packet1.max_version = packet_in.max_version; 111 | 112 | mav_array_memcpy(packet1.spec_version_hash, packet_in.spec_version_hash, sizeof(uint8_t)*8); 113 | mav_array_memcpy(packet1.library_version_hash, packet_in.library_version_hash, sizeof(uint8_t)*8); 114 | 115 | #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 116 | if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { 117 | // cope with extensions 118 | memset(MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN); 119 | } 120 | #endif 121 | memset(&packet2, 0, sizeof(packet2)); 122 | mavlink_msg_protocol_version_encode(system_id, component_id, &msg, &packet1); 123 | mavlink_msg_protocol_version_decode(&msg, &packet2); 124 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 125 | 126 | memset(&packet2, 0, sizeof(packet2)); 127 | mavlink_msg_protocol_version_pack(system_id, component_id, &msg , packet1.version , packet1.min_version , packet1.max_version , packet1.spec_version_hash , packet1.library_version_hash ); 128 | mavlink_msg_protocol_version_decode(&msg, &packet2); 129 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 130 | 131 | memset(&packet2, 0, sizeof(packet2)); 132 | mavlink_msg_protocol_version_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.version , packet1.min_version , packet1.max_version , packet1.spec_version_hash , packet1.library_version_hash ); 133 | mavlink_msg_protocol_version_decode(&msg, &packet2); 134 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 135 | 136 | memset(&packet2, 0, sizeof(packet2)); 137 | mavlink_msg_to_send_buffer(buffer, &msg); 138 | for (i=0; imsgid = MAVLINK_MSG_ID_SCRIPT_CURRENT; 63 | return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCRIPT_CURRENT_MIN_LEN, MAVLINK_MSG_ID_SCRIPT_CURRENT_LEN, MAVLINK_MSG_ID_SCRIPT_CURRENT_CRC); 64 | } 65 | 66 | /** 67 | * @brief Pack a script_current message 68 | * @param system_id ID of this system 69 | * @param component_id ID of this component (e.g. 200 for IMU) 70 | * @param status MAVLink status structure 71 | * @param msg The MAVLink message to compress the data into 72 | * 73 | * @param seq Active Sequence 74 | * @return length of the message in bytes (excluding serial stream start sign) 75 | */ 76 | static inline uint16_t mavlink_msg_script_current_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg, 77 | uint16_t seq) 78 | { 79 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 80 | char buf[MAVLINK_MSG_ID_SCRIPT_CURRENT_LEN]; 81 | _mav_put_uint16_t(buf, 0, seq); 82 | 83 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCRIPT_CURRENT_LEN); 84 | #else 85 | mavlink_script_current_t packet; 86 | packet.seq = seq; 87 | 88 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCRIPT_CURRENT_LEN); 89 | #endif 90 | 91 | msg->msgid = MAVLINK_MSG_ID_SCRIPT_CURRENT; 92 | #if MAVLINK_CRC_EXTRA 93 | return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SCRIPT_CURRENT_MIN_LEN, MAVLINK_MSG_ID_SCRIPT_CURRENT_LEN, MAVLINK_MSG_ID_SCRIPT_CURRENT_CRC); 94 | #else 95 | return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SCRIPT_CURRENT_MIN_LEN, MAVLINK_MSG_ID_SCRIPT_CURRENT_LEN); 96 | #endif 97 | } 98 | 99 | /** 100 | * @brief Pack a script_current message on a channel 101 | * @param system_id ID of this system 102 | * @param component_id ID of this component (e.g. 200 for IMU) 103 | * @param chan The MAVLink channel this message will be sent over 104 | * @param msg The MAVLink message to compress the data into 105 | * @param seq Active Sequence 106 | * @return length of the message in bytes (excluding serial stream start sign) 107 | */ 108 | static inline uint16_t mavlink_msg_script_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, 109 | mavlink_message_t* msg, 110 | uint16_t seq) 111 | { 112 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 113 | char buf[MAVLINK_MSG_ID_SCRIPT_CURRENT_LEN]; 114 | _mav_put_uint16_t(buf, 0, seq); 115 | 116 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCRIPT_CURRENT_LEN); 117 | #else 118 | mavlink_script_current_t packet; 119 | packet.seq = seq; 120 | 121 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCRIPT_CURRENT_LEN); 122 | #endif 123 | 124 | msg->msgid = MAVLINK_MSG_ID_SCRIPT_CURRENT; 125 | return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCRIPT_CURRENT_MIN_LEN, MAVLINK_MSG_ID_SCRIPT_CURRENT_LEN, MAVLINK_MSG_ID_SCRIPT_CURRENT_CRC); 126 | } 127 | 128 | /** 129 | * @brief Encode a script_current struct 130 | * 131 | * @param system_id ID of this system 132 | * @param component_id ID of this component (e.g. 200 for IMU) 133 | * @param msg The MAVLink message to compress the data into 134 | * @param script_current C-struct to read the message contents from 135 | */ 136 | static inline uint16_t mavlink_msg_script_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_script_current_t* script_current) 137 | { 138 | return mavlink_msg_script_current_pack(system_id, component_id, msg, script_current->seq); 139 | } 140 | 141 | /** 142 | * @brief Encode a script_current struct on a channel 143 | * 144 | * @param system_id ID of this system 145 | * @param component_id ID of this component (e.g. 200 for IMU) 146 | * @param chan The MAVLink channel this message will be sent over 147 | * @param msg The MAVLink message to compress the data into 148 | * @param script_current C-struct to read the message contents from 149 | */ 150 | static inline uint16_t mavlink_msg_script_current_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_script_current_t* script_current) 151 | { 152 | return mavlink_msg_script_current_pack_chan(system_id, component_id, chan, msg, script_current->seq); 153 | } 154 | 155 | /** 156 | * @brief Encode a script_current struct with provided status structure 157 | * 158 | * @param system_id ID of this system 159 | * @param component_id ID of this component (e.g. 200 for IMU) 160 | * @param status MAVLink status structure 161 | * @param msg The MAVLink message to compress the data into 162 | * @param script_current C-struct to read the message contents from 163 | */ 164 | static inline uint16_t mavlink_msg_script_current_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_script_current_t* script_current) 165 | { 166 | return mavlink_msg_script_current_pack_status(system_id, component_id, _status, msg, script_current->seq); 167 | } 168 | 169 | /** 170 | * @brief Send a script_current message 171 | * @param chan MAVLink channel to send the message 172 | * 173 | * @param seq Active Sequence 174 | */ 175 | #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 176 | 177 | static inline void mavlink_msg_script_current_send(mavlink_channel_t chan, uint16_t seq) 178 | { 179 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 180 | char buf[MAVLINK_MSG_ID_SCRIPT_CURRENT_LEN]; 181 | _mav_put_uint16_t(buf, 0, seq); 182 | 183 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCRIPT_CURRENT, buf, MAVLINK_MSG_ID_SCRIPT_CURRENT_MIN_LEN, MAVLINK_MSG_ID_SCRIPT_CURRENT_LEN, MAVLINK_MSG_ID_SCRIPT_CURRENT_CRC); 184 | #else 185 | mavlink_script_current_t packet; 186 | packet.seq = seq; 187 | 188 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCRIPT_CURRENT, (const char *)&packet, MAVLINK_MSG_ID_SCRIPT_CURRENT_MIN_LEN, MAVLINK_MSG_ID_SCRIPT_CURRENT_LEN, MAVLINK_MSG_ID_SCRIPT_CURRENT_CRC); 189 | #endif 190 | } 191 | 192 | /** 193 | * @brief Send a script_current message 194 | * @param chan MAVLink channel to send the message 195 | * @param struct The MAVLink struct to serialize 196 | */ 197 | static inline void mavlink_msg_script_current_send_struct(mavlink_channel_t chan, const mavlink_script_current_t* script_current) 198 | { 199 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 200 | mavlink_msg_script_current_send(chan, script_current->seq); 201 | #else 202 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCRIPT_CURRENT, (const char *)script_current, MAVLINK_MSG_ID_SCRIPT_CURRENT_MIN_LEN, MAVLINK_MSG_ID_SCRIPT_CURRENT_LEN, MAVLINK_MSG_ID_SCRIPT_CURRENT_CRC); 203 | #endif 204 | } 205 | 206 | #if MAVLINK_MSG_ID_SCRIPT_CURRENT_LEN <= MAVLINK_MAX_PAYLOAD_LEN 207 | /* 208 | This variant of _send() can be used to save stack space by re-using 209 | memory from the receive buffer. The caller provides a 210 | mavlink_message_t which is the size of a full mavlink message. This 211 | is usually the receive buffer for the channel, and allows a reply to an 212 | incoming message with minimum stack space usage. 213 | */ 214 | static inline void mavlink_msg_script_current_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t seq) 215 | { 216 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 217 | char *buf = (char *)msgbuf; 218 | _mav_put_uint16_t(buf, 0, seq); 219 | 220 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCRIPT_CURRENT, buf, MAVLINK_MSG_ID_SCRIPT_CURRENT_MIN_LEN, MAVLINK_MSG_ID_SCRIPT_CURRENT_LEN, MAVLINK_MSG_ID_SCRIPT_CURRENT_CRC); 221 | #else 222 | mavlink_script_current_t *packet = (mavlink_script_current_t *)msgbuf; 223 | packet->seq = seq; 224 | 225 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCRIPT_CURRENT, (const char *)packet, MAVLINK_MSG_ID_SCRIPT_CURRENT_MIN_LEN, MAVLINK_MSG_ID_SCRIPT_CURRENT_LEN, MAVLINK_MSG_ID_SCRIPT_CURRENT_CRC); 226 | #endif 227 | } 228 | #endif 229 | 230 | #endif 231 | 232 | // MESSAGE SCRIPT_CURRENT UNPACKING 233 | 234 | 235 | /** 236 | * @brief Get field seq from script_current message 237 | * 238 | * @return Active Sequence 239 | */ 240 | static inline uint16_t mavlink_msg_script_current_get_seq(const mavlink_message_t* msg) 241 | { 242 | return _MAV_RETURN_uint16_t(msg, 0); 243 | } 244 | 245 | /** 246 | * @brief Decode a script_current message into a struct 247 | * 248 | * @param msg The message to decode 249 | * @param script_current C-struct to decode the message contents into 250 | */ 251 | static inline void mavlink_msg_script_current_decode(const mavlink_message_t* msg, mavlink_script_current_t* script_current) 252 | { 253 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 254 | script_current->seq = mavlink_msg_script_current_get_seq(msg); 255 | #else 256 | uint8_t len = msg->len < MAVLINK_MSG_ID_SCRIPT_CURRENT_LEN? msg->len : MAVLINK_MSG_ID_SCRIPT_CURRENT_LEN; 257 | memset(script_current, 0, MAVLINK_MSG_ID_SCRIPT_CURRENT_LEN); 258 | memcpy(script_current, _MAV_PAYLOAD(msg), len); 259 | #endif 260 | } 261 | -------------------------------------------------------------------------------- /mavlink/paparazzi/version.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol built from paparazzi.xml 3 | * @see http://mavlink.org 4 | */ 5 | #pragma once 6 | 7 | #ifndef MAVLINK_VERSION_H 8 | #define MAVLINK_VERSION_H 9 | 10 | #define MAVLINK_BUILD_DATE "Thu May 29 2025" 11 | #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0" 12 | #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 13 | 14 | #endif // MAVLINK_VERSION_H 15 | -------------------------------------------------------------------------------- /mavlink/python_array_test/mavlink.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol built from python_array_test.xml 3 | * @see http://mavlink.org 4 | */ 5 | #pragma once 6 | #ifndef MAVLINK_H 7 | #define MAVLINK_H 8 | 9 | #define MAVLINK_PRIMARY_XML_HASH 7697821043526285045 10 | 11 | #ifndef MAVLINK_STX 12 | #define MAVLINK_STX 253 13 | #endif 14 | 15 | #ifndef MAVLINK_ENDIAN 16 | #define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN 17 | #endif 18 | 19 | #ifndef MAVLINK_ALIGNED_FIELDS 20 | #define MAVLINK_ALIGNED_FIELDS 1 21 | #endif 22 | 23 | #ifndef MAVLINK_CRC_EXTRA 24 | #define MAVLINK_CRC_EXTRA 1 25 | #endif 26 | 27 | #ifndef MAVLINK_COMMAND_24BIT 28 | #define MAVLINK_COMMAND_24BIT 1 29 | #endif 30 | 31 | #include "version.h" 32 | #include "python_array_test.h" 33 | 34 | #endif // MAVLINK_H 35 | -------------------------------------------------------------------------------- /mavlink/python_array_test/mavlink_msg_array_test_1.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | // MESSAGE ARRAY_TEST_1 PACKING 3 | 4 | #define MAVLINK_MSG_ID_ARRAY_TEST_1 17151 5 | 6 | 7 | typedef struct __mavlink_array_test_1_t { 8 | uint32_t ar_u32[4]; /*< Value array*/ 9 | } mavlink_array_test_1_t; 10 | 11 | #define MAVLINK_MSG_ID_ARRAY_TEST_1_LEN 16 12 | #define MAVLINK_MSG_ID_ARRAY_TEST_1_MIN_LEN 16 13 | #define MAVLINK_MSG_ID_17151_LEN 16 14 | #define MAVLINK_MSG_ID_17151_MIN_LEN 16 15 | 16 | #define MAVLINK_MSG_ID_ARRAY_TEST_1_CRC 72 17 | #define MAVLINK_MSG_ID_17151_CRC 72 18 | 19 | #define MAVLINK_MSG_ARRAY_TEST_1_FIELD_AR_U32_LEN 4 20 | 21 | #if MAVLINK_COMMAND_24BIT 22 | #define MAVLINK_MESSAGE_INFO_ARRAY_TEST_1 { \ 23 | 17151, \ 24 | "ARRAY_TEST_1", \ 25 | 1, \ 26 | { { "ar_u32", NULL, MAVLINK_TYPE_UINT32_T, 4, 0, offsetof(mavlink_array_test_1_t, ar_u32) }, \ 27 | } \ 28 | } 29 | #else 30 | #define MAVLINK_MESSAGE_INFO_ARRAY_TEST_1 { \ 31 | "ARRAY_TEST_1", \ 32 | 1, \ 33 | { { "ar_u32", NULL, MAVLINK_TYPE_UINT32_T, 4, 0, offsetof(mavlink_array_test_1_t, ar_u32) }, \ 34 | } \ 35 | } 36 | #endif 37 | 38 | /** 39 | * @brief Pack a array_test_1 message 40 | * @param system_id ID of this system 41 | * @param component_id ID of this component (e.g. 200 for IMU) 42 | * @param msg The MAVLink message to compress the data into 43 | * 44 | * @param ar_u32 Value array 45 | * @return length of the message in bytes (excluding serial stream start sign) 46 | */ 47 | static inline uint16_t mavlink_msg_array_test_1_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, 48 | const uint32_t *ar_u32) 49 | { 50 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 51 | char buf[MAVLINK_MSG_ID_ARRAY_TEST_1_LEN]; 52 | 53 | _mav_put_uint32_t_array(buf, 0, ar_u32, 4); 54 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ARRAY_TEST_1_LEN); 55 | #else 56 | mavlink_array_test_1_t packet; 57 | 58 | mav_array_memcpy(packet.ar_u32, ar_u32, sizeof(uint32_t)*4); 59 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ARRAY_TEST_1_LEN); 60 | #endif 61 | 62 | msg->msgid = MAVLINK_MSG_ID_ARRAY_TEST_1; 63 | return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ARRAY_TEST_1_MIN_LEN, MAVLINK_MSG_ID_ARRAY_TEST_1_LEN, MAVLINK_MSG_ID_ARRAY_TEST_1_CRC); 64 | } 65 | 66 | /** 67 | * @brief Pack a array_test_1 message 68 | * @param system_id ID of this system 69 | * @param component_id ID of this component (e.g. 200 for IMU) 70 | * @param status MAVLink status structure 71 | * @param msg The MAVLink message to compress the data into 72 | * 73 | * @param ar_u32 Value array 74 | * @return length of the message in bytes (excluding serial stream start sign) 75 | */ 76 | static inline uint16_t mavlink_msg_array_test_1_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg, 77 | const uint32_t *ar_u32) 78 | { 79 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 80 | char buf[MAVLINK_MSG_ID_ARRAY_TEST_1_LEN]; 81 | 82 | _mav_put_uint32_t_array(buf, 0, ar_u32, 4); 83 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ARRAY_TEST_1_LEN); 84 | #else 85 | mavlink_array_test_1_t packet; 86 | 87 | mav_array_memcpy(packet.ar_u32, ar_u32, sizeof(uint32_t)*4); 88 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ARRAY_TEST_1_LEN); 89 | #endif 90 | 91 | msg->msgid = MAVLINK_MSG_ID_ARRAY_TEST_1; 92 | #if MAVLINK_CRC_EXTRA 93 | return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ARRAY_TEST_1_MIN_LEN, MAVLINK_MSG_ID_ARRAY_TEST_1_LEN, MAVLINK_MSG_ID_ARRAY_TEST_1_CRC); 94 | #else 95 | return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ARRAY_TEST_1_MIN_LEN, MAVLINK_MSG_ID_ARRAY_TEST_1_LEN); 96 | #endif 97 | } 98 | 99 | /** 100 | * @brief Pack a array_test_1 message on a channel 101 | * @param system_id ID of this system 102 | * @param component_id ID of this component (e.g. 200 for IMU) 103 | * @param chan The MAVLink channel this message will be sent over 104 | * @param msg The MAVLink message to compress the data into 105 | * @param ar_u32 Value array 106 | * @return length of the message in bytes (excluding serial stream start sign) 107 | */ 108 | static inline uint16_t mavlink_msg_array_test_1_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, 109 | mavlink_message_t* msg, 110 | const uint32_t *ar_u32) 111 | { 112 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 113 | char buf[MAVLINK_MSG_ID_ARRAY_TEST_1_LEN]; 114 | 115 | _mav_put_uint32_t_array(buf, 0, ar_u32, 4); 116 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ARRAY_TEST_1_LEN); 117 | #else 118 | mavlink_array_test_1_t packet; 119 | 120 | mav_array_memcpy(packet.ar_u32, ar_u32, sizeof(uint32_t)*4); 121 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ARRAY_TEST_1_LEN); 122 | #endif 123 | 124 | msg->msgid = MAVLINK_MSG_ID_ARRAY_TEST_1; 125 | return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ARRAY_TEST_1_MIN_LEN, MAVLINK_MSG_ID_ARRAY_TEST_1_LEN, MAVLINK_MSG_ID_ARRAY_TEST_1_CRC); 126 | } 127 | 128 | /** 129 | * @brief Encode a array_test_1 struct 130 | * 131 | * @param system_id ID of this system 132 | * @param component_id ID of this component (e.g. 200 for IMU) 133 | * @param msg The MAVLink message to compress the data into 134 | * @param array_test_1 C-struct to read the message contents from 135 | */ 136 | static inline uint16_t mavlink_msg_array_test_1_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_array_test_1_t* array_test_1) 137 | { 138 | return mavlink_msg_array_test_1_pack(system_id, component_id, msg, array_test_1->ar_u32); 139 | } 140 | 141 | /** 142 | * @brief Encode a array_test_1 struct on a channel 143 | * 144 | * @param system_id ID of this system 145 | * @param component_id ID of this component (e.g. 200 for IMU) 146 | * @param chan The MAVLink channel this message will be sent over 147 | * @param msg The MAVLink message to compress the data into 148 | * @param array_test_1 C-struct to read the message contents from 149 | */ 150 | static inline uint16_t mavlink_msg_array_test_1_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_array_test_1_t* array_test_1) 151 | { 152 | return mavlink_msg_array_test_1_pack_chan(system_id, component_id, chan, msg, array_test_1->ar_u32); 153 | } 154 | 155 | /** 156 | * @brief Encode a array_test_1 struct with provided status structure 157 | * 158 | * @param system_id ID of this system 159 | * @param component_id ID of this component (e.g. 200 for IMU) 160 | * @param status MAVLink status structure 161 | * @param msg The MAVLink message to compress the data into 162 | * @param array_test_1 C-struct to read the message contents from 163 | */ 164 | static inline uint16_t mavlink_msg_array_test_1_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_array_test_1_t* array_test_1) 165 | { 166 | return mavlink_msg_array_test_1_pack_status(system_id, component_id, _status, msg, array_test_1->ar_u32); 167 | } 168 | 169 | /** 170 | * @brief Send a array_test_1 message 171 | * @param chan MAVLink channel to send the message 172 | * 173 | * @param ar_u32 Value array 174 | */ 175 | #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 176 | 177 | static inline void mavlink_msg_array_test_1_send(mavlink_channel_t chan, const uint32_t *ar_u32) 178 | { 179 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 180 | char buf[MAVLINK_MSG_ID_ARRAY_TEST_1_LEN]; 181 | 182 | _mav_put_uint32_t_array(buf, 0, ar_u32, 4); 183 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARRAY_TEST_1, buf, MAVLINK_MSG_ID_ARRAY_TEST_1_MIN_LEN, MAVLINK_MSG_ID_ARRAY_TEST_1_LEN, MAVLINK_MSG_ID_ARRAY_TEST_1_CRC); 184 | #else 185 | mavlink_array_test_1_t packet; 186 | 187 | mav_array_memcpy(packet.ar_u32, ar_u32, sizeof(uint32_t)*4); 188 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARRAY_TEST_1, (const char *)&packet, MAVLINK_MSG_ID_ARRAY_TEST_1_MIN_LEN, MAVLINK_MSG_ID_ARRAY_TEST_1_LEN, MAVLINK_MSG_ID_ARRAY_TEST_1_CRC); 189 | #endif 190 | } 191 | 192 | /** 193 | * @brief Send a array_test_1 message 194 | * @param chan MAVLink channel to send the message 195 | * @param struct The MAVLink struct to serialize 196 | */ 197 | static inline void mavlink_msg_array_test_1_send_struct(mavlink_channel_t chan, const mavlink_array_test_1_t* array_test_1) 198 | { 199 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 200 | mavlink_msg_array_test_1_send(chan, array_test_1->ar_u32); 201 | #else 202 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARRAY_TEST_1, (const char *)array_test_1, MAVLINK_MSG_ID_ARRAY_TEST_1_MIN_LEN, MAVLINK_MSG_ID_ARRAY_TEST_1_LEN, MAVLINK_MSG_ID_ARRAY_TEST_1_CRC); 203 | #endif 204 | } 205 | 206 | #if MAVLINK_MSG_ID_ARRAY_TEST_1_LEN <= MAVLINK_MAX_PAYLOAD_LEN 207 | /* 208 | This variant of _send() can be used to save stack space by re-using 209 | memory from the receive buffer. The caller provides a 210 | mavlink_message_t which is the size of a full mavlink message. This 211 | is usually the receive buffer for the channel, and allows a reply to an 212 | incoming message with minimum stack space usage. 213 | */ 214 | static inline void mavlink_msg_array_test_1_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const uint32_t *ar_u32) 215 | { 216 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 217 | char *buf = (char *)msgbuf; 218 | 219 | _mav_put_uint32_t_array(buf, 0, ar_u32, 4); 220 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARRAY_TEST_1, buf, MAVLINK_MSG_ID_ARRAY_TEST_1_MIN_LEN, MAVLINK_MSG_ID_ARRAY_TEST_1_LEN, MAVLINK_MSG_ID_ARRAY_TEST_1_CRC); 221 | #else 222 | mavlink_array_test_1_t *packet = (mavlink_array_test_1_t *)msgbuf; 223 | 224 | mav_array_memcpy(packet->ar_u32, ar_u32, sizeof(uint32_t)*4); 225 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARRAY_TEST_1, (const char *)packet, MAVLINK_MSG_ID_ARRAY_TEST_1_MIN_LEN, MAVLINK_MSG_ID_ARRAY_TEST_1_LEN, MAVLINK_MSG_ID_ARRAY_TEST_1_CRC); 226 | #endif 227 | } 228 | #endif 229 | 230 | #endif 231 | 232 | // MESSAGE ARRAY_TEST_1 UNPACKING 233 | 234 | 235 | /** 236 | * @brief Get field ar_u32 from array_test_1 message 237 | * 238 | * @return Value array 239 | */ 240 | static inline uint16_t mavlink_msg_array_test_1_get_ar_u32(const mavlink_message_t* msg, uint32_t *ar_u32) 241 | { 242 | return _MAV_RETURN_uint32_t_array(msg, ar_u32, 4, 0); 243 | } 244 | 245 | /** 246 | * @brief Decode a array_test_1 message into a struct 247 | * 248 | * @param msg The message to decode 249 | * @param array_test_1 C-struct to decode the message contents into 250 | */ 251 | static inline void mavlink_msg_array_test_1_decode(const mavlink_message_t* msg, mavlink_array_test_1_t* array_test_1) 252 | { 253 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 254 | mavlink_msg_array_test_1_get_ar_u32(msg, array_test_1->ar_u32); 255 | #else 256 | uint8_t len = msg->len < MAVLINK_MSG_ID_ARRAY_TEST_1_LEN? msg->len : MAVLINK_MSG_ID_ARRAY_TEST_1_LEN; 257 | memset(array_test_1, 0, MAVLINK_MSG_ID_ARRAY_TEST_1_LEN); 258 | memcpy(array_test_1, _MAV_PAYLOAD(msg), len); 259 | #endif 260 | } 261 | -------------------------------------------------------------------------------- /mavlink/python_array_test/version.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol built from python_array_test.xml 3 | * @see http://mavlink.org 4 | */ 5 | #pragma once 6 | 7 | #ifndef MAVLINK_VERSION_H 8 | #define MAVLINK_VERSION_H 9 | 10 | #define MAVLINK_BUILD_DATE "Thu May 29 2025" 11 | #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0" 12 | #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 13 | 14 | #endif // MAVLINK_VERSION_H 15 | -------------------------------------------------------------------------------- /mavlink/standard/mavlink.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol built from standard.xml 3 | * @see http://mavlink.org 4 | */ 5 | #pragma once 6 | #ifndef MAVLINK_H 7 | #define MAVLINK_H 8 | 9 | #define MAVLINK_PRIMARY_XML_HASH -4169691420381738031 10 | 11 | #ifndef MAVLINK_STX 12 | #define MAVLINK_STX 253 13 | #endif 14 | 15 | #ifndef MAVLINK_ENDIAN 16 | #define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN 17 | #endif 18 | 19 | #ifndef MAVLINK_ALIGNED_FIELDS 20 | #define MAVLINK_ALIGNED_FIELDS 1 21 | #endif 22 | 23 | #ifndef MAVLINK_CRC_EXTRA 24 | #define MAVLINK_CRC_EXTRA 1 25 | #endif 26 | 27 | #ifndef MAVLINK_COMMAND_24BIT 28 | #define MAVLINK_COMMAND_24BIT 1 29 | #endif 30 | 31 | #include "version.h" 32 | #include "standard.h" 33 | 34 | #endif // MAVLINK_H 35 | -------------------------------------------------------------------------------- /mavlink/standard/standard.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol generated from standard.xml 3 | * @see http://mavlink.org 4 | */ 5 | #pragma once 6 | #ifndef MAVLINK_STANDARD_H 7 | #define MAVLINK_STANDARD_H 8 | 9 | #ifndef MAVLINK_H 10 | #error Wrong include order: MAVLINK_STANDARD.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call. 11 | #endif 12 | 13 | #define MAVLINK_STANDARD_XML_HASH -4169691420381738031 14 | 15 | #ifdef __cplusplus 16 | extern "C" { 17 | #endif 18 | 19 | // MESSAGE LENGTHS AND CRCS 20 | 21 | #ifndef MAVLINK_MESSAGE_LENGTHS 22 | #define MAVLINK_MESSAGE_LENGTHS {} 23 | #endif 24 | 25 | #ifndef MAVLINK_MESSAGE_CRCS 26 | #define MAVLINK_MESSAGE_CRCS {{0, 50, 9, 9, 0, 0, 0}, {300, 217, 22, 22, 0, 0, 0}} 27 | #endif 28 | 29 | #include "../protocol.h" 30 | 31 | #define MAVLINK_ENABLED_STANDARD 32 | 33 | // ENUM DEFINITIONS 34 | 35 | 36 | 37 | // MAVLINK VERSION 38 | 39 | #ifndef MAVLINK_VERSION 40 | #define MAVLINK_VERSION 2 41 | #endif 42 | 43 | #if (MAVLINK_VERSION == 0) 44 | #undef MAVLINK_VERSION 45 | #define MAVLINK_VERSION 2 46 | #endif 47 | 48 | // MESSAGE DEFINITIONS 49 | 50 | 51 | // base include 52 | #include "../minimal/minimal.h" 53 | 54 | 55 | #if MAVLINK_STANDARD_XML_HASH == MAVLINK_PRIMARY_XML_HASH 56 | # define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_PROTOCOL_VERSION} 57 | # define MAVLINK_MESSAGE_NAMES {{ "HEARTBEAT", 0 }, { "PROTOCOL_VERSION", 300 }} 58 | # if MAVLINK_COMMAND_24BIT 59 | # include "../mavlink_get_info.h" 60 | # endif 61 | #endif 62 | 63 | #ifdef __cplusplus 64 | } 65 | #endif // __cplusplus 66 | #endif // MAVLINK_STANDARD_H 67 | -------------------------------------------------------------------------------- /mavlink/standard/testsuite.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol testsuite generated from standard.xml 3 | * @see https://mavlink.io/en/ 4 | */ 5 | #pragma once 6 | #ifndef STANDARD_TESTSUITE_H 7 | #define STANDARD_TESTSUITE_H 8 | 9 | #ifdef __cplusplus 10 | extern "C" { 11 | #endif 12 | 13 | #ifndef MAVLINK_TEST_ALL 14 | #define MAVLINK_TEST_ALL 15 | static void mavlink_test_minimal(uint8_t, uint8_t, mavlink_message_t *last_msg); 16 | static void mavlink_test_standard(uint8_t, uint8_t, mavlink_message_t *last_msg); 17 | 18 | static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) 19 | { 20 | mavlink_test_minimal(system_id, component_id, last_msg); 21 | mavlink_test_standard(system_id, component_id, last_msg); 22 | } 23 | #endif 24 | 25 | #include "../minimal/testsuite.h" 26 | 27 | 28 | 29 | static void mavlink_test_standard(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) 30 | { 31 | 32 | } 33 | 34 | #ifdef __cplusplus 35 | } 36 | #endif // __cplusplus 37 | #endif // STANDARD_TESTSUITE_H 38 | -------------------------------------------------------------------------------- /mavlink/standard/version.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol built from standard.xml 3 | * @see http://mavlink.org 4 | */ 5 | #pragma once 6 | 7 | #ifndef MAVLINK_VERSION_H 8 | #define MAVLINK_VERSION_H 9 | 10 | #define MAVLINK_BUILD_DATE "Thu May 29 2025" 11 | #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0" 12 | #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 22 13 | 14 | #endif // MAVLINK_VERSION_H 15 | -------------------------------------------------------------------------------- /mavlink/storm32/mavlink.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol built from storm32.xml 3 | * @see http://mavlink.org 4 | */ 5 | #pragma once 6 | #ifndef MAVLINK_H 7 | #define MAVLINK_H 8 | 9 | #define MAVLINK_PRIMARY_XML_HASH -4061112174935892483 10 | 11 | #ifndef MAVLINK_STX 12 | #define MAVLINK_STX 253 13 | #endif 14 | 15 | #ifndef MAVLINK_ENDIAN 16 | #define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN 17 | #endif 18 | 19 | #ifndef MAVLINK_ALIGNED_FIELDS 20 | #define MAVLINK_ALIGNED_FIELDS 1 21 | #endif 22 | 23 | #ifndef MAVLINK_CRC_EXTRA 24 | #define MAVLINK_CRC_EXTRA 1 25 | #endif 26 | 27 | #ifndef MAVLINK_COMMAND_24BIT 28 | #define MAVLINK_COMMAND_24BIT 1 29 | #endif 30 | 31 | #include "version.h" 32 | #include "storm32.h" 33 | 34 | #endif // MAVLINK_H 35 | -------------------------------------------------------------------------------- /mavlink/storm32/version.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol built from storm32.xml 3 | * @see http://mavlink.org 4 | */ 5 | #pragma once 6 | 7 | #ifndef MAVLINK_VERSION_H 8 | #define MAVLINK_VERSION_H 9 | 10 | #define MAVLINK_BUILD_DATE "Thu May 29 2025" 11 | #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0" 12 | #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 13 | 14 | #endif // MAVLINK_VERSION_H 15 | -------------------------------------------------------------------------------- /mavlink/test/mavlink.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol built from test.xml 3 | * @see http://mavlink.org 4 | */ 5 | #pragma once 6 | #ifndef MAVLINK_H 7 | #define MAVLINK_H 8 | 9 | #define MAVLINK_PRIMARY_XML_HASH 524711514875573561 10 | 11 | #ifndef MAVLINK_STX 12 | #define MAVLINK_STX 253 13 | #endif 14 | 15 | #ifndef MAVLINK_ENDIAN 16 | #define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN 17 | #endif 18 | 19 | #ifndef MAVLINK_ALIGNED_FIELDS 20 | #define MAVLINK_ALIGNED_FIELDS 1 21 | #endif 22 | 23 | #ifndef MAVLINK_CRC_EXTRA 24 | #define MAVLINK_CRC_EXTRA 1 25 | #endif 26 | 27 | #ifndef MAVLINK_COMMAND_24BIT 28 | #define MAVLINK_COMMAND_24BIT 1 29 | #endif 30 | 31 | #include "version.h" 32 | #include "test.h" 33 | 34 | #endif // MAVLINK_H 35 | -------------------------------------------------------------------------------- /mavlink/test/test.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol generated from test.xml 3 | * @see http://mavlink.org 4 | */ 5 | #pragma once 6 | #ifndef MAVLINK_TEST_H 7 | #define MAVLINK_TEST_H 8 | 9 | #ifndef MAVLINK_H 10 | #error Wrong include order: MAVLINK_TEST.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call. 11 | #endif 12 | 13 | #define MAVLINK_TEST_XML_HASH 524711514875573561 14 | 15 | #ifdef __cplusplus 16 | extern "C" { 17 | #endif 18 | 19 | // MESSAGE LENGTHS AND CRCS 20 | 21 | #ifndef MAVLINK_MESSAGE_LENGTHS 22 | #define MAVLINK_MESSAGE_LENGTHS {} 23 | #endif 24 | 25 | #ifndef MAVLINK_MESSAGE_CRCS 26 | #define MAVLINK_MESSAGE_CRCS {{17000, 103, 179, 179, 0, 0, 0}} 27 | #endif 28 | 29 | #include "../protocol.h" 30 | 31 | #define MAVLINK_ENABLED_TEST 32 | 33 | // ENUM DEFINITIONS 34 | 35 | 36 | 37 | // MAVLINK VERSION 38 | 39 | #ifndef MAVLINK_VERSION 40 | #define MAVLINK_VERSION 3 41 | #endif 42 | 43 | #if (MAVLINK_VERSION == 0) 44 | #undef MAVLINK_VERSION 45 | #define MAVLINK_VERSION 3 46 | #endif 47 | 48 | // MESSAGE DEFINITIONS 49 | #include "./mavlink_msg_test_types.h" 50 | 51 | // base include 52 | 53 | 54 | 55 | #if MAVLINK_TEST_XML_HASH == MAVLINK_PRIMARY_XML_HASH 56 | # define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_TEST_TYPES} 57 | # define MAVLINK_MESSAGE_NAMES {{ "TEST_TYPES", 17000 }} 58 | # if MAVLINK_COMMAND_24BIT 59 | # include "../mavlink_get_info.h" 60 | # endif 61 | #endif 62 | 63 | #ifdef __cplusplus 64 | } 65 | #endif // __cplusplus 66 | #endif // MAVLINK_TEST_H 67 | -------------------------------------------------------------------------------- /mavlink/test/testsuite.h: -------------------------------------------------------------------------------- 1 | /** @file 2 | * @brief MAVLink comm protocol testsuite generated from test.xml 3 | * @see https://mavlink.io/en/ 4 | */ 5 | #pragma once 6 | #ifndef TEST_TESTSUITE_H 7 | #define TEST_TESTSUITE_H 8 | 9 | #ifdef __cplusplus 10 | extern "C" { 11 | #endif 12 | 13 | #ifndef MAVLINK_TEST_ALL 14 | #define MAVLINK_TEST_ALL 15 | 16 | static void mavlink_test_test(uint8_t, uint8_t, mavlink_message_t *last_msg); 17 | 18 | static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) 19 | { 20 | 21 | mavlink_test_test(system_id, component_id, last_msg); 22 | } 23 | #endif 24 | 25 | 26 | 27 | 28 | static void mavlink_test_test_types(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) 29 | { 30 | #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 31 | mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0); 32 | if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_TEST_TYPES >= 256) { 33 | return; 34 | } 35 | #endif 36 | mavlink_message_t msg; 37 | uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; 38 | uint16_t i; 39 | mavlink_test_types_t packet_in = { 40 | 93372036854775807ULL,93372036854776311LL,235.0,{ 93372036854777319, 93372036854777320, 93372036854777321 },{ 93372036854778831, 93372036854778832, 93372036854778833 },{ 627.0, 628.0, 629.0 },963502456,963502664,745.0,{ 963503080, 963503081, 963503082 },{ 963503704, 963503705, 963503706 },{ 941.0, 942.0, 943.0 },24723,24827,{ 24931, 24932, 24933 },{ 25243, 25244, 25245 },'E',"FGHIJKLMN",198,9,{ 76, 77, 78 },{ 21, 22, 23 } 41 | }; 42 | mavlink_test_types_t packet1, packet2; 43 | memset(&packet1, 0, sizeof(packet1)); 44 | packet1.u64 = packet_in.u64; 45 | packet1.s64 = packet_in.s64; 46 | packet1.d = packet_in.d; 47 | packet1.u32 = packet_in.u32; 48 | packet1.s32 = packet_in.s32; 49 | packet1.f = packet_in.f; 50 | packet1.u16 = packet_in.u16; 51 | packet1.s16 = packet_in.s16; 52 | packet1.c = packet_in.c; 53 | packet1.u8 = packet_in.u8; 54 | packet1.s8 = packet_in.s8; 55 | 56 | mav_array_memcpy(packet1.u64_array, packet_in.u64_array, sizeof(uint64_t)*3); 57 | mav_array_memcpy(packet1.s64_array, packet_in.s64_array, sizeof(int64_t)*3); 58 | mav_array_memcpy(packet1.d_array, packet_in.d_array, sizeof(double)*3); 59 | mav_array_memcpy(packet1.u32_array, packet_in.u32_array, sizeof(uint32_t)*3); 60 | mav_array_memcpy(packet1.s32_array, packet_in.s32_array, sizeof(int32_t)*3); 61 | mav_array_memcpy(packet1.f_array, packet_in.f_array, sizeof(float)*3); 62 | mav_array_memcpy(packet1.u16_array, packet_in.u16_array, sizeof(uint16_t)*3); 63 | mav_array_memcpy(packet1.s16_array, packet_in.s16_array, sizeof(int16_t)*3); 64 | mav_array_memcpy(packet1.s, packet_in.s, sizeof(char)*10); 65 | mav_array_memcpy(packet1.u8_array, packet_in.u8_array, sizeof(uint8_t)*3); 66 | mav_array_memcpy(packet1.s8_array, packet_in.s8_array, sizeof(int8_t)*3); 67 | 68 | #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 69 | if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { 70 | // cope with extensions 71 | memset(MAVLINK_MSG_ID_TEST_TYPES_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TEST_TYPES_MIN_LEN); 72 | } 73 | #endif 74 | memset(&packet2, 0, sizeof(packet2)); 75 | mavlink_msg_test_types_encode(system_id, component_id, &msg, &packet1); 76 | mavlink_msg_test_types_decode(&msg, &packet2); 77 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 78 | 79 | memset(&packet2, 0, sizeof(packet2)); 80 | mavlink_msg_test_types_pack(system_id, component_id, &msg , packet1.c , packet1.s , packet1.u8 , packet1.u16 , packet1.u32 , packet1.u64 , packet1.s8 , packet1.s16 , packet1.s32 , packet1.s64 , packet1.f , packet1.d , packet1.u8_array , packet1.u16_array , packet1.u32_array , packet1.u64_array , packet1.s8_array , packet1.s16_array , packet1.s32_array , packet1.s64_array , packet1.f_array , packet1.d_array ); 81 | mavlink_msg_test_types_decode(&msg, &packet2); 82 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 83 | 84 | memset(&packet2, 0, sizeof(packet2)); 85 | mavlink_msg_test_types_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.c , packet1.s , packet1.u8 , packet1.u16 , packet1.u32 , packet1.u64 , packet1.s8 , packet1.s16 , packet1.s32 , packet1.s64 , packet1.f , packet1.d , packet1.u8_array , packet1.u16_array , packet1.u32_array , packet1.u64_array , packet1.s8_array , packet1.s16_array , packet1.s32_array , packet1.s64_array , packet1.f_array , packet1.d_array ); 86 | mavlink_msg_test_types_decode(&msg, &packet2); 87 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 88 | 89 | memset(&packet2, 0, sizeof(packet2)); 90 | mavlink_msg_to_send_buffer(buffer, &msg); 91 | for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_NAV_FILTER_BIAS >= 256) { 33 | return; 34 | } 35 | #endif 36 | mavlink_message_t msg; 37 | uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; 38 | uint16_t i; 39 | mavlink_nav_filter_bias_t packet_in = { 40 | 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0 41 | }; 42 | mavlink_nav_filter_bias_t packet1, packet2; 43 | memset(&packet1, 0, sizeof(packet1)); 44 | packet1.usec = packet_in.usec; 45 | packet1.accel_0 = packet_in.accel_0; 46 | packet1.accel_1 = packet_in.accel_1; 47 | packet1.accel_2 = packet_in.accel_2; 48 | packet1.gyro_0 = packet_in.gyro_0; 49 | packet1.gyro_1 = packet_in.gyro_1; 50 | packet1.gyro_2 = packet_in.gyro_2; 51 | 52 | 53 | #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 54 | if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { 55 | // cope with extensions 56 | memset(MAVLINK_MSG_ID_NAV_FILTER_BIAS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_NAV_FILTER_BIAS_MIN_LEN); 57 | } 58 | #endif 59 | memset(&packet2, 0, sizeof(packet2)); 60 | mavlink_msg_nav_filter_bias_encode(system_id, component_id, &msg, &packet1); 61 | mavlink_msg_nav_filter_bias_decode(&msg, &packet2); 62 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 63 | 64 | memset(&packet2, 0, sizeof(packet2)); 65 | mavlink_msg_nav_filter_bias_pack(system_id, component_id, &msg , packet1.usec , packet1.accel_0 , packet1.accel_1 , packet1.accel_2 , packet1.gyro_0 , packet1.gyro_1 , packet1.gyro_2 ); 66 | mavlink_msg_nav_filter_bias_decode(&msg, &packet2); 67 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 68 | 69 | memset(&packet2, 0, sizeof(packet2)); 70 | mavlink_msg_nav_filter_bias_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.accel_0 , packet1.accel_1 , packet1.accel_2 , packet1.gyro_0 , packet1.gyro_1 , packet1.gyro_2 ); 71 | mavlink_msg_nav_filter_bias_decode(&msg, &packet2); 72 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 73 | 74 | memset(&packet2, 0, sizeof(packet2)); 75 | mavlink_msg_to_send_buffer(buffer, &msg); 76 | for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RADIO_CALIBRATION >= 256) { 98 | return; 99 | } 100 | #endif 101 | mavlink_message_t msg; 102 | uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; 103 | uint16_t i; 104 | mavlink_radio_calibration_t packet_in = { 105 | { 17235, 17236, 17237 },{ 17547, 17548, 17549 },{ 17859, 17860, 17861 },{ 18171, 18172 },{ 18379, 18380, 18381, 18382, 18383 },{ 18899, 18900, 18901, 18902, 18903 } 106 | }; 107 | mavlink_radio_calibration_t packet1, packet2; 108 | memset(&packet1, 0, sizeof(packet1)); 109 | 110 | mav_array_memcpy(packet1.aileron, packet_in.aileron, sizeof(uint16_t)*3); 111 | mav_array_memcpy(packet1.elevator, packet_in.elevator, sizeof(uint16_t)*3); 112 | mav_array_memcpy(packet1.rudder, packet_in.rudder, sizeof(uint16_t)*3); 113 | mav_array_memcpy(packet1.gyro, packet_in.gyro, sizeof(uint16_t)*2); 114 | mav_array_memcpy(packet1.pitch, packet_in.pitch, sizeof(uint16_t)*5); 115 | mav_array_memcpy(packet1.throttle, packet_in.throttle, sizeof(uint16_t)*5); 116 | 117 | #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 118 | if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { 119 | // cope with extensions 120 | memset(MAVLINK_MSG_ID_RADIO_CALIBRATION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RADIO_CALIBRATION_MIN_LEN); 121 | } 122 | #endif 123 | memset(&packet2, 0, sizeof(packet2)); 124 | mavlink_msg_radio_calibration_encode(system_id, component_id, &msg, &packet1); 125 | mavlink_msg_radio_calibration_decode(&msg, &packet2); 126 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 127 | 128 | memset(&packet2, 0, sizeof(packet2)); 129 | mavlink_msg_radio_calibration_pack(system_id, component_id, &msg , packet1.aileron , packet1.elevator , packet1.rudder , packet1.gyro , packet1.pitch , packet1.throttle ); 130 | mavlink_msg_radio_calibration_decode(&msg, &packet2); 131 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 132 | 133 | memset(&packet2, 0, sizeof(packet2)); 134 | mavlink_msg_radio_calibration_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.aileron , packet1.elevator , packet1.rudder , packet1.gyro , packet1.pitch , packet1.throttle ); 135 | mavlink_msg_radio_calibration_decode(&msg, &packet2); 136 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 137 | 138 | memset(&packet2, 0, sizeof(packet2)); 139 | mavlink_msg_to_send_buffer(buffer, &msg); 140 | for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_UALBERTA_SYS_STATUS >= 256) { 162 | return; 163 | } 164 | #endif 165 | mavlink_message_t msg; 166 | uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; 167 | uint16_t i; 168 | mavlink_ualberta_sys_status_t packet_in = { 169 | 5,72,139 170 | }; 171 | mavlink_ualberta_sys_status_t packet1, packet2; 172 | memset(&packet1, 0, sizeof(packet1)); 173 | packet1.mode = packet_in.mode; 174 | packet1.nav_mode = packet_in.nav_mode; 175 | packet1.pilot = packet_in.pilot; 176 | 177 | 178 | #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 179 | if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { 180 | // cope with extensions 181 | memset(MAVLINK_MSG_ID_UALBERTA_SYS_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_UALBERTA_SYS_STATUS_MIN_LEN); 182 | } 183 | #endif 184 | memset(&packet2, 0, sizeof(packet2)); 185 | mavlink_msg_ualberta_sys_status_encode(system_id, component_id, &msg, &packet1); 186 | mavlink_msg_ualberta_sys_status_decode(&msg, &packet2); 187 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 188 | 189 | memset(&packet2, 0, sizeof(packet2)); 190 | mavlink_msg_ualberta_sys_status_pack(system_id, component_id, &msg , packet1.mode , packet1.nav_mode , packet1.pilot ); 191 | mavlink_msg_ualberta_sys_status_decode(&msg, &packet2); 192 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 193 | 194 | memset(&packet2, 0, sizeof(packet2)); 195 | mavlink_msg_ualberta_sys_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.mode , packet1.nav_mode , packet1.pilot ); 196 | mavlink_msg_ualberta_sys_status_decode(&msg, &packet2); 197 | MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); 198 | 199 | memset(&packet2, 0, sizeof(packet2)); 200 | mavlink_msg_to_send_buffer(buffer, &msg); 201 | for (i=0; i