mirror of https://github.com/ArduPilot/ardupilot
mavlink: import new version with AP_ADC packet
this adds the AP_ADC packet which gives us raw ADC values
This commit is contained in:
parent
ada409855a
commit
bf7d62e788
|
@ -12,15 +12,15 @@ extern "C" {
|
||||||
// MESSAGE LENGTHS AND CRCS
|
// MESSAGE LENGTHS AND CRCS
|
||||||
|
|
||||||
#ifndef MAVLINK_MESSAGE_LENGTHS
|
#ifndef MAVLINK_MESSAGE_LENGTHS
|
||||||
#define MAVLINK_MESSAGE_LENGTHS {3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 24, 24, 0, 0, 0, 26, 16, 36, 5, 6, 56, 26, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51, 5}
|
#define MAVLINK_MESSAGE_LENGTHS {3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 24, 24, 0, 0, 0, 26, 16, 36, 5, 6, 56, 26, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 12, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51, 5}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef MAVLINK_MESSAGE_CRCS
|
#ifndef MAVLINK_MESSAGE_CRCS
|
||||||
#define MAVLINK_MESSAGE_CRCS {72, 39, 190, 92, 191, 217, 104, 119, 0, 219, 60, 186, 10, 0, 0, 0, 0, 0, 0, 0, 89, 159, 162, 121, 0, 149, 222, 110, 179, 136, 66, 126, 185, 147, 112, 252, 162, 215, 229, 128, 9, 106, 101, 213, 4, 229, 21, 214, 215, 14, 206, 50, 157, 126, 108, 213, 95, 5, 127, 0, 0, 0, 57, 126, 130, 119, 193, 191, 236, 158, 143, 0, 0, 104, 123, 131, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 143, 29, 208, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 178, 224, 60, 106, 7}
|
#define MAVLINK_MESSAGE_CRCS {72, 39, 190, 92, 191, 217, 104, 119, 0, 219, 60, 186, 10, 0, 0, 0, 0, 0, 0, 0, 89, 159, 162, 121, 0, 149, 222, 110, 179, 136, 66, 126, 185, 147, 112, 252, 162, 215, 229, 128, 9, 106, 101, 213, 4, 229, 21, 214, 215, 14, 206, 50, 157, 126, 108, 213, 95, 5, 127, 0, 0, 0, 57, 126, 130, 119, 193, 191, 236, 158, 143, 0, 0, 104, 123, 131, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 143, 29, 208, 188, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 178, 224, 60, 106, 7}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef MAVLINK_MESSAGE_INFO
|
#ifndef MAVLINK_MESSAGE_INFO
|
||||||
#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_BOOT, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_SYSTEM_TIME_UTC, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {NULL}, MAVLINK_MESSAGE_INFO_ACTION_ACK, MAVLINK_MESSAGE_INFO_ACTION, MAVLINK_MESSAGE_INFO_SET_MODE, MAVLINK_MESSAGE_INFO_SET_NAV_MODE, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, {NULL}, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_LOCAL_POSITION, MAVLINK_MESSAGE_INFO_GPS_RAW, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_WAYPOINT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST, MAVLINK_MESSAGE_INFO_WAYPOINT_SET_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST_LIST, MAVLINK_MESSAGE_INFO_WAYPOINT_COUNT, MAVLINK_MESSAGE_INFO_WAYPOINT_CLEAR_ALL, MAVLINK_MESSAGE_INFO_WAYPOINT_REACHED, MAVLINK_MESSAGE_INFO_WAYPOINT_ACK, MAVLINK_MESSAGE_INFO_GPS_SET_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_LOCAL_ORIGIN_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_CONTROL_STATUS, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_POSITION_TARGET, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_SET_ALTITUDE, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OBJECT_DETECTION_EVENT, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG}
|
#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_BOOT, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_SYSTEM_TIME_UTC, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {NULL}, MAVLINK_MESSAGE_INFO_ACTION_ACK, MAVLINK_MESSAGE_INFO_ACTION, MAVLINK_MESSAGE_INFO_SET_MODE, MAVLINK_MESSAGE_INFO_SET_NAV_MODE, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, {NULL}, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_LOCAL_POSITION, MAVLINK_MESSAGE_INFO_GPS_RAW, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_WAYPOINT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST, MAVLINK_MESSAGE_INFO_WAYPOINT_SET_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST_LIST, MAVLINK_MESSAGE_INFO_WAYPOINT_COUNT, MAVLINK_MESSAGE_INFO_WAYPOINT_CLEAR_ALL, MAVLINK_MESSAGE_INFO_WAYPOINT_REACHED, MAVLINK_MESSAGE_INFO_WAYPOINT_ACK, MAVLINK_MESSAGE_INFO_GPS_SET_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_LOCAL_ORIGIN_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_CONTROL_STATUS, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_POSITION_TARGET, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_SET_ALTITUDE, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OBJECT_DETECTION_EVENT, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#include "../protocol.h"
|
#include "../protocol.h"
|
||||||
|
@ -48,6 +48,7 @@ extern "C" {
|
||||||
#include "./mavlink_msg_sensor_offsets.h"
|
#include "./mavlink_msg_sensor_offsets.h"
|
||||||
#include "./mavlink_msg_set_mag_offsets.h"
|
#include "./mavlink_msg_set_mag_offsets.h"
|
||||||
#include "./mavlink_msg_meminfo.h"
|
#include "./mavlink_msg_meminfo.h"
|
||||||
|
#include "./mavlink_msg_ap_adc.h"
|
||||||
|
|
||||||
#ifdef __cplusplus
|
#ifdef __cplusplus
|
||||||
}
|
}
|
||||||
|
|
|
@ -0,0 +1,254 @@
|
||||||
|
// MESSAGE AP_ADC PACKING
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_AP_ADC 153
|
||||||
|
|
||||||
|
typedef struct __mavlink_ap_adc_t
|
||||||
|
{
|
||||||
|
uint16_t adc1; ///< ADC output 1
|
||||||
|
uint16_t adc2; ///< ADC output 2
|
||||||
|
uint16_t adc3; ///< ADC output 3
|
||||||
|
uint16_t adc4; ///< ADC output 4
|
||||||
|
uint16_t adc5; ///< ADC output 5
|
||||||
|
uint16_t adc6; ///< ADC output 6
|
||||||
|
} mavlink_ap_adc_t;
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_AP_ADC_LEN 12
|
||||||
|
#define MAVLINK_MSG_ID_153_LEN 12
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#define MAVLINK_MESSAGE_INFO_AP_ADC { \
|
||||||
|
"AP_ADC", \
|
||||||
|
6, \
|
||||||
|
{ { "adc1", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_ap_adc_t, adc1) }, \
|
||||||
|
{ "adc2", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_ap_adc_t, adc2) }, \
|
||||||
|
{ "adc3", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_ap_adc_t, adc3) }, \
|
||||||
|
{ "adc4", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_ap_adc_t, adc4) }, \
|
||||||
|
{ "adc5", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_ap_adc_t, adc5) }, \
|
||||||
|
{ "adc6", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_ap_adc_t, adc6) }, \
|
||||||
|
} \
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Pack a ap_adc message
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
*
|
||||||
|
* @param adc1 ADC output 1
|
||||||
|
* @param adc2 ADC output 2
|
||||||
|
* @param adc3 ADC output 3
|
||||||
|
* @param adc4 ADC output 4
|
||||||
|
* @param adc5 ADC output 5
|
||||||
|
* @param adc6 ADC output 6
|
||||||
|
* @return length of the message in bytes (excluding serial stream start sign)
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ap_adc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||||
|
uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[12];
|
||||||
|
_mav_put_uint16_t(buf, 0, adc1);
|
||||||
|
_mav_put_uint16_t(buf, 2, adc2);
|
||||||
|
_mav_put_uint16_t(buf, 4, adc3);
|
||||||
|
_mav_put_uint16_t(buf, 6, adc4);
|
||||||
|
_mav_put_uint16_t(buf, 8, adc5);
|
||||||
|
_mav_put_uint16_t(buf, 10, adc6);
|
||||||
|
|
||||||
|
memcpy(_MAV_PAYLOAD(msg), buf, 12);
|
||||||
|
#else
|
||||||
|
mavlink_ap_adc_t packet;
|
||||||
|
packet.adc1 = adc1;
|
||||||
|
packet.adc2 = adc2;
|
||||||
|
packet.adc3 = adc3;
|
||||||
|
packet.adc4 = adc4;
|
||||||
|
packet.adc5 = adc5;
|
||||||
|
packet.adc6 = adc6;
|
||||||
|
|
||||||
|
memcpy(_MAV_PAYLOAD(msg), &packet, 12);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
msg->msgid = MAVLINK_MSG_ID_AP_ADC;
|
||||||
|
return mavlink_finalize_message(msg, system_id, component_id, 12);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Pack a ap_adc message on a channel
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param chan The MAVLink channel this message was sent over
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
* @param adc1 ADC output 1
|
||||||
|
* @param adc2 ADC output 2
|
||||||
|
* @param adc3 ADC output 3
|
||||||
|
* @param adc4 ADC output 4
|
||||||
|
* @param adc5 ADC output 5
|
||||||
|
* @param adc6 ADC output 6
|
||||||
|
* @return length of the message in bytes (excluding serial stream start sign)
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ap_adc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||||
|
mavlink_message_t* msg,
|
||||||
|
uint16_t adc1,uint16_t adc2,uint16_t adc3,uint16_t adc4,uint16_t adc5,uint16_t adc6)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[12];
|
||||||
|
_mav_put_uint16_t(buf, 0, adc1);
|
||||||
|
_mav_put_uint16_t(buf, 2, adc2);
|
||||||
|
_mav_put_uint16_t(buf, 4, adc3);
|
||||||
|
_mav_put_uint16_t(buf, 6, adc4);
|
||||||
|
_mav_put_uint16_t(buf, 8, adc5);
|
||||||
|
_mav_put_uint16_t(buf, 10, adc6);
|
||||||
|
|
||||||
|
memcpy(_MAV_PAYLOAD(msg), buf, 12);
|
||||||
|
#else
|
||||||
|
mavlink_ap_adc_t packet;
|
||||||
|
packet.adc1 = adc1;
|
||||||
|
packet.adc2 = adc2;
|
||||||
|
packet.adc3 = adc3;
|
||||||
|
packet.adc4 = adc4;
|
||||||
|
packet.adc5 = adc5;
|
||||||
|
packet.adc6 = adc6;
|
||||||
|
|
||||||
|
memcpy(_MAV_PAYLOAD(msg), &packet, 12);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
msg->msgid = MAVLINK_MSG_ID_AP_ADC;
|
||||||
|
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Encode a ap_adc struct into a message
|
||||||
|
*
|
||||||
|
* @param system_id ID of this system
|
||||||
|
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||||
|
* @param msg The MAVLink message to compress the data into
|
||||||
|
* @param ap_adc C-struct to read the message contents from
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ap_adc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ap_adc_t* ap_adc)
|
||||||
|
{
|
||||||
|
return mavlink_msg_ap_adc_pack(system_id, component_id, msg, ap_adc->adc1, ap_adc->adc2, ap_adc->adc3, ap_adc->adc4, ap_adc->adc5, ap_adc->adc6);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Send a ap_adc message
|
||||||
|
* @param chan MAVLink channel to send the message
|
||||||
|
*
|
||||||
|
* @param adc1 ADC output 1
|
||||||
|
* @param adc2 ADC output 2
|
||||||
|
* @param adc3 ADC output 3
|
||||||
|
* @param adc4 ADC output 4
|
||||||
|
* @param adc5 ADC output 5
|
||||||
|
* @param adc6 ADC output 6
|
||||||
|
*/
|
||||||
|
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||||
|
|
||||||
|
static inline void mavlink_msg_ap_adc_send(mavlink_channel_t chan, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[12];
|
||||||
|
_mav_put_uint16_t(buf, 0, adc1);
|
||||||
|
_mav_put_uint16_t(buf, 2, adc2);
|
||||||
|
_mav_put_uint16_t(buf, 4, adc3);
|
||||||
|
_mav_put_uint16_t(buf, 6, adc4);
|
||||||
|
_mav_put_uint16_t(buf, 8, adc5);
|
||||||
|
_mav_put_uint16_t(buf, 10, adc6);
|
||||||
|
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, buf, 12);
|
||||||
|
#else
|
||||||
|
mavlink_ap_adc_t packet;
|
||||||
|
packet.adc1 = adc1;
|
||||||
|
packet.adc2 = adc2;
|
||||||
|
packet.adc3 = adc3;
|
||||||
|
packet.adc4 = adc4;
|
||||||
|
packet.adc5 = adc5;
|
||||||
|
packet.adc6 = adc6;
|
||||||
|
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, (const char *)&packet, 12);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// MESSAGE AP_ADC UNPACKING
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field adc1 from ap_adc message
|
||||||
|
*
|
||||||
|
* @return ADC output 1
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ap_adc_get_adc1(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint16_t(msg, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field adc2 from ap_adc message
|
||||||
|
*
|
||||||
|
* @return ADC output 2
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ap_adc_get_adc2(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint16_t(msg, 2);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field adc3 from ap_adc message
|
||||||
|
*
|
||||||
|
* @return ADC output 3
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ap_adc_get_adc3(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint16_t(msg, 4);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field adc4 from ap_adc message
|
||||||
|
*
|
||||||
|
* @return ADC output 4
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ap_adc_get_adc4(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint16_t(msg, 6);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field adc5 from ap_adc message
|
||||||
|
*
|
||||||
|
* @return ADC output 5
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ap_adc_get_adc5(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint16_t(msg, 8);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field adc6 from ap_adc message
|
||||||
|
*
|
||||||
|
* @return ADC output 6
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_ap_adc_get_adc6(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint16_t(msg, 10);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Decode a ap_adc message into a struct
|
||||||
|
*
|
||||||
|
* @param msg The message to decode
|
||||||
|
* @param ap_adc C-struct to decode the message contents into
|
||||||
|
*/
|
||||||
|
static inline void mavlink_msg_ap_adc_decode(const mavlink_message_t* msg, mavlink_ap_adc_t* ap_adc)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP
|
||||||
|
ap_adc->adc1 = mavlink_msg_ap_adc_get_adc1(msg);
|
||||||
|
ap_adc->adc2 = mavlink_msg_ap_adc_get_adc2(msg);
|
||||||
|
ap_adc->adc3 = mavlink_msg_ap_adc_get_adc3(msg);
|
||||||
|
ap_adc->adc4 = mavlink_msg_ap_adc_get_adc4(msg);
|
||||||
|
ap_adc->adc5 = mavlink_msg_ap_adc_get_adc5(msg);
|
||||||
|
ap_adc->adc6 = mavlink_msg_ap_adc_get_adc6(msg);
|
||||||
|
#else
|
||||||
|
memcpy(ap_adc, _MAV_PAYLOAD(msg), 12);
|
||||||
|
#endif
|
||||||
|
}
|
|
@ -185,11 +185,65 @@ static void mavlink_test_meminfo(uint8_t system_id, uint8_t component_id, mavlin
|
||||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static void mavlink_test_ap_adc(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||||
|
{
|
||||||
|
mavlink_message_t msg;
|
||||||
|
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
|
||||||
|
uint16_t i;
|
||||||
|
mavlink_ap_adc_t packet_in = {
|
||||||
|
17235,
|
||||||
|
17339,
|
||||||
|
17443,
|
||||||
|
17547,
|
||||||
|
17651,
|
||||||
|
17755,
|
||||||
|
};
|
||||||
|
mavlink_ap_adc_t packet1, packet2;
|
||||||
|
memset(&packet1, 0, sizeof(packet1));
|
||||||
|
packet1.adc1 = packet_in.adc1;
|
||||||
|
packet1.adc2 = packet_in.adc2;
|
||||||
|
packet1.adc3 = packet_in.adc3;
|
||||||
|
packet1.adc4 = packet_in.adc4;
|
||||||
|
packet1.adc5 = packet_in.adc5;
|
||||||
|
packet1.adc6 = packet_in.adc6;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
memset(&packet2, 0, sizeof(packet2));
|
||||||
|
mavlink_msg_ap_adc_encode(system_id, component_id, &msg, &packet1);
|
||||||
|
mavlink_msg_ap_adc_decode(&msg, &packet2);
|
||||||
|
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||||
|
|
||||||
|
memset(&packet2, 0, sizeof(packet2));
|
||||||
|
mavlink_msg_ap_adc_pack(system_id, component_id, &msg , packet1.adc1 , packet1.adc2 , packet1.adc3 , packet1.adc4 , packet1.adc5 , packet1.adc6 );
|
||||||
|
mavlink_msg_ap_adc_decode(&msg, &packet2);
|
||||||
|
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||||
|
|
||||||
|
memset(&packet2, 0, sizeof(packet2));
|
||||||
|
mavlink_msg_ap_adc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.adc1 , packet1.adc2 , packet1.adc3 , packet1.adc4 , packet1.adc5 , packet1.adc6 );
|
||||||
|
mavlink_msg_ap_adc_decode(&msg, &packet2);
|
||||||
|
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||||
|
|
||||||
|
memset(&packet2, 0, sizeof(packet2));
|
||||||
|
mavlink_msg_to_send_buffer(buffer, &msg);
|
||||||
|
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
|
||||||
|
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
|
||||||
|
}
|
||||||
|
mavlink_msg_ap_adc_decode(last_msg, &packet2);
|
||||||
|
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||||
|
|
||||||
|
memset(&packet2, 0, sizeof(packet2));
|
||||||
|
mavlink_msg_ap_adc_send(MAVLINK_COMM_1 , packet1.adc1 , packet1.adc2 , packet1.adc3 , packet1.adc4 , packet1.adc5 , packet1.adc6 );
|
||||||
|
mavlink_msg_ap_adc_decode(last_msg, &packet2);
|
||||||
|
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||||
|
}
|
||||||
|
|
||||||
static void mavlink_test_ardupilotmega(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
static void mavlink_test_ardupilotmega(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||||
{
|
{
|
||||||
mavlink_test_sensor_offsets(system_id, component_id, last_msg);
|
mavlink_test_sensor_offsets(system_id, component_id, last_msg);
|
||||||
mavlink_test_set_mag_offsets(system_id, component_id, last_msg);
|
mavlink_test_set_mag_offsets(system_id, component_id, last_msg);
|
||||||
mavlink_test_meminfo(system_id, component_id, last_msg);
|
mavlink_test_meminfo(system_id, component_id, last_msg);
|
||||||
|
mavlink_test_ap_adc(system_id, component_id, last_msg);
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef __cplusplus
|
#ifdef __cplusplus
|
||||||
|
|
|
@ -5,7 +5,7 @@
|
||||||
#ifndef MAVLINK_VERSION_H
|
#ifndef MAVLINK_VERSION_H
|
||||||
#define MAVLINK_VERSION_H
|
#define MAVLINK_VERSION_H
|
||||||
|
|
||||||
#define MAVLINK_BUILD_DATE "Sun Sep 4 18:16:41 2011"
|
#define MAVLINK_BUILD_DATE "Sat Sep 10 18:09:49 2011"
|
||||||
#define MAVLINK_WIRE_PROTOCOL_VERSION "0.9"
|
#define MAVLINK_WIRE_PROTOCOL_VERSION "0.9"
|
||||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
|
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
|
||||||
|
|
||||||
|
|
|
@ -5,7 +5,7 @@
|
||||||
#ifndef MAVLINK_VERSION_H
|
#ifndef MAVLINK_VERSION_H
|
||||||
#define MAVLINK_VERSION_H
|
#define MAVLINK_VERSION_H
|
||||||
|
|
||||||
#define MAVLINK_BUILD_DATE "Sun Sep 4 18:16:41 2011"
|
#define MAVLINK_BUILD_DATE "Sat Sep 10 18:09:49 2011"
|
||||||
#define MAVLINK_WIRE_PROTOCOL_VERSION "0.9"
|
#define MAVLINK_WIRE_PROTOCOL_VERSION "0.9"
|
||||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
|
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
|
||||||
|
|
||||||
|
|
|
@ -41,5 +41,15 @@
|
||||||
<field type="uint16_t" name="freemem">free memory</field>
|
<field type="uint16_t" name="freemem">free memory</field>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
|
<message id="153" name="AP_ADC">
|
||||||
|
<description>raw ADC output</description>
|
||||||
|
<field type="uint16_t" name="adc1">ADC output 1</field>
|
||||||
|
<field type="uint16_t" name="adc2">ADC output 2</field>
|
||||||
|
<field type="uint16_t" name="adc3">ADC output 3</field>
|
||||||
|
<field type="uint16_t" name="adc4">ADC output 4</field>
|
||||||
|
<field type="uint16_t" name="adc5">ADC output 5</field>
|
||||||
|
<field type="uint16_t" name="adc6">ADC output 6</field>
|
||||||
|
</message>
|
||||||
|
|
||||||
</messages>
|
</messages>
|
||||||
</mavlink>
|
</mavlink>
|
||||||
|
|
|
@ -0,0 +1,31 @@
|
||||||
|
<?xml version='1.0'?>
|
||||||
|
<mavlink>
|
||||||
|
<version>3</version>
|
||||||
|
<messages>
|
||||||
|
<message id="0" name="TEST_TYPES">
|
||||||
|
<description>Test all field types</description>
|
||||||
|
<field type="char" name="c">char</field>
|
||||||
|
<field type="char[10]" name="s">string</field>
|
||||||
|
<field type="uint8_t" name="u8">uint8_t</field>
|
||||||
|
<field type="uint16_t" name="u16">uint16_t</field>
|
||||||
|
<field type="uint32_t" name="u32" print_format="0x%08x">uint32_t</field>
|
||||||
|
<field type="uint64_t" name="u64">uint64_t</field>
|
||||||
|
<field type="int8_t" name="s8">int8_t</field>
|
||||||
|
<field type="int16_t" name="s16">int16_t</field>
|
||||||
|
<field type="int32_t" name="s32">int32_t</field>
|
||||||
|
<field type="int64_t" name="s64">int64_t</field>
|
||||||
|
<field type="float" name="f">float</field>
|
||||||
|
<field type="double" name="d">double</field>
|
||||||
|
<field type="uint8_t[3]" name="u8_array">uint8_t_array</field>
|
||||||
|
<field type="uint16_t[3]" name="u16_array">uint16_t_array</field>
|
||||||
|
<field type="uint32_t[3]" name="u32_array">uint32_t_array</field>
|
||||||
|
<field type="uint64_t[3]" name="u64_array">uint64_t_array</field>
|
||||||
|
<field type="int8_t[3]" name="s8_array">int8_t_array</field>
|
||||||
|
<field type="int16_t[3]" name="s16_array">int16_t_array</field>
|
||||||
|
<field type="int32_t[3]" name="s32_array">int32_t_array</field>
|
||||||
|
<field type="int64_t[3]" name="s64_array">int64_t_array</field>
|
||||||
|
<field type="float[3]" name="f_array">float_array</field>
|
||||||
|
<field type="double[3]" name="d_array">double_array</field>
|
||||||
|
</message>
|
||||||
|
</messages>
|
||||||
|
</mavlink>
|
Loading…
Reference in New Issue