mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
MAVLink: bring the v1.0 MAVLink in sync with 0.9
This commit is contained in:
parent
fed5426274
commit
6d06d9d070
@ -5,7 +5,7 @@
|
|||||||
#ifndef MAVLINK_VERSION_H
|
#ifndef MAVLINK_VERSION_H
|
||||||
#define MAVLINK_VERSION_H
|
#define MAVLINK_VERSION_H
|
||||||
|
|
||||||
#define MAVLINK_BUILD_DATE "Thu Mar 1 13:22:36 2012"
|
#define MAVLINK_BUILD_DATE "Sat Mar 10 09:38:12 2012"
|
||||||
#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 "Thu Mar 1 13:22:36 2012"
|
#define MAVLINK_BUILD_DATE "Sat Mar 10 09:38:12 2012"
|
||||||
#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
|
||||||
|
|
||||||
|
@ -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 {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 0, 0, 26, 0, 36, 0, 6, 4, 0, 21, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 18, 32, 32, 20, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 30, 18, 18, 51, 9, 3}
|
#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 0, 0, 26, 0, 36, 0, 6, 4, 0, 21, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 18, 32, 32, 20, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 36, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 30, 18, 18, 51, 9, 3}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef MAVLINK_MESSAGE_CRCS
|
#ifndef MAVLINK_MESSAGE_CRCS
|
||||||
#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 0, 0, 183, 0, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 19, 102, 158, 208, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 205, 42, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 247}
|
#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 0, 0, 183, 0, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 19, 102, 158, 208, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 205, 42, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 247}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef MAVLINK_MESSAGE_INFO
|
#ifndef MAVLINK_MESSAGE_INFO
|
||||||
#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {NULL}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_SET_MODE, {NULL}, {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, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, 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}, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, {NULL}, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {NULL}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {NULL}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_VFR_HUD, {NULL}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, {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_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE, MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE, MAVLINK_MESSAGE_INFO_MOUNT_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_STATUS, {NULL}, MAVLINK_MESSAGE_INFO_FENCE_POINT, MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_DCM, MAVLINK_MESSAGE_INFO_SIMSTATE, {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_MEMORY_VECT, 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, MAVLINK_MESSAGE_INFO_EXTENDED_MESSAGE}
|
#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {NULL}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_SET_MODE, {NULL}, {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, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, 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}, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, {NULL}, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {NULL}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {NULL}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_VFR_HUD, {NULL}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, {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_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE, MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE, MAVLINK_MESSAGE_INFO_MOUNT_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_STATUS, {NULL}, MAVLINK_MESSAGE_INFO_FENCE_POINT, MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_DCM, MAVLINK_MESSAGE_INFO_SIMSTATE, MAVLINK_MESSAGE_INFO_HWSTATUS, {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_MEMORY_VECT, 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, MAVLINK_MESSAGE_INFO_EXTENDED_MESSAGE}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#include "../protocol.h"
|
#include "../protocol.h"
|
||||||
@ -144,6 +144,7 @@ enum FENCE_BREACH
|
|||||||
#include "./mavlink_msg_fence_status.h"
|
#include "./mavlink_msg_fence_status.h"
|
||||||
#include "./mavlink_msg_dcm.h"
|
#include "./mavlink_msg_dcm.h"
|
||||||
#include "./mavlink_msg_simstate.h"
|
#include "./mavlink_msg_simstate.h"
|
||||||
|
#include "./mavlink_msg_hwstatus.h"
|
||||||
|
|
||||||
#ifdef __cplusplus
|
#ifdef __cplusplus
|
||||||
}
|
}
|
||||||
|
@ -0,0 +1,166 @@
|
|||||||
|
// MESSAGE HWSTATUS PACKING
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_HWSTATUS 165
|
||||||
|
|
||||||
|
typedef struct __mavlink_hwstatus_t
|
||||||
|
{
|
||||||
|
uint16_t Vcc; ///< board voltage (mV)
|
||||||
|
uint8_t I2Cerr; ///< I2C error count
|
||||||
|
} mavlink_hwstatus_t;
|
||||||
|
|
||||||
|
#define MAVLINK_MSG_ID_HWSTATUS_LEN 3
|
||||||
|
#define MAVLINK_MSG_ID_165_LEN 3
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#define MAVLINK_MESSAGE_INFO_HWSTATUS { \
|
||||||
|
"HWSTATUS", \
|
||||||
|
2, \
|
||||||
|
{ { "Vcc", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_hwstatus_t, Vcc) }, \
|
||||||
|
{ "I2Cerr", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_hwstatus_t, I2Cerr) }, \
|
||||||
|
} \
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Pack a hwstatus 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 Vcc board voltage (mV)
|
||||||
|
* @param I2Cerr I2C error count
|
||||||
|
* @return length of the message in bytes (excluding serial stream start sign)
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_hwstatus_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||||
|
uint16_t Vcc, uint8_t I2Cerr)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[3];
|
||||||
|
_mav_put_uint16_t(buf, 0, Vcc);
|
||||||
|
_mav_put_uint8_t(buf, 2, I2Cerr);
|
||||||
|
|
||||||
|
memcpy(_MAV_PAYLOAD(msg), buf, 3);
|
||||||
|
#else
|
||||||
|
mavlink_hwstatus_t packet;
|
||||||
|
packet.Vcc = Vcc;
|
||||||
|
packet.I2Cerr = I2Cerr;
|
||||||
|
|
||||||
|
memcpy(_MAV_PAYLOAD(msg), &packet, 3);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
msg->msgid = MAVLINK_MSG_ID_HWSTATUS;
|
||||||
|
return mavlink_finalize_message(msg, system_id, component_id, 3, 21);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Pack a hwstatus 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 Vcc board voltage (mV)
|
||||||
|
* @param I2Cerr I2C error count
|
||||||
|
* @return length of the message in bytes (excluding serial stream start sign)
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_hwstatus_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||||
|
mavlink_message_t* msg,
|
||||||
|
uint16_t Vcc,uint8_t I2Cerr)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[3];
|
||||||
|
_mav_put_uint16_t(buf, 0, Vcc);
|
||||||
|
_mav_put_uint8_t(buf, 2, I2Cerr);
|
||||||
|
|
||||||
|
memcpy(_MAV_PAYLOAD(msg), buf, 3);
|
||||||
|
#else
|
||||||
|
mavlink_hwstatus_t packet;
|
||||||
|
packet.Vcc = Vcc;
|
||||||
|
packet.I2Cerr = I2Cerr;
|
||||||
|
|
||||||
|
memcpy(_MAV_PAYLOAD(msg), &packet, 3);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
msg->msgid = MAVLINK_MSG_ID_HWSTATUS;
|
||||||
|
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 21);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Encode a hwstatus 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 hwstatus C-struct to read the message contents from
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_hwstatus_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hwstatus_t* hwstatus)
|
||||||
|
{
|
||||||
|
return mavlink_msg_hwstatus_pack(system_id, component_id, msg, hwstatus->Vcc, hwstatus->I2Cerr);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Send a hwstatus message
|
||||||
|
* @param chan MAVLink channel to send the message
|
||||||
|
*
|
||||||
|
* @param Vcc board voltage (mV)
|
||||||
|
* @param I2Cerr I2C error count
|
||||||
|
*/
|
||||||
|
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||||
|
|
||||||
|
static inline void mavlink_msg_hwstatus_send(mavlink_channel_t chan, uint16_t Vcc, uint8_t I2Cerr)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||||
|
char buf[3];
|
||||||
|
_mav_put_uint16_t(buf, 0, Vcc);
|
||||||
|
_mav_put_uint8_t(buf, 2, I2Cerr);
|
||||||
|
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, buf, 3, 21);
|
||||||
|
#else
|
||||||
|
mavlink_hwstatus_t packet;
|
||||||
|
packet.Vcc = Vcc;
|
||||||
|
packet.I2Cerr = I2Cerr;
|
||||||
|
|
||||||
|
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, (const char *)&packet, 3, 21);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// MESSAGE HWSTATUS UNPACKING
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field Vcc from hwstatus message
|
||||||
|
*
|
||||||
|
* @return board voltage (mV)
|
||||||
|
*/
|
||||||
|
static inline uint16_t mavlink_msg_hwstatus_get_Vcc(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint16_t(msg, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get field I2Cerr from hwstatus message
|
||||||
|
*
|
||||||
|
* @return I2C error count
|
||||||
|
*/
|
||||||
|
static inline uint8_t mavlink_msg_hwstatus_get_I2Cerr(const mavlink_message_t* msg)
|
||||||
|
{
|
||||||
|
return _MAV_RETURN_uint8_t(msg, 2);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Decode a hwstatus message into a struct
|
||||||
|
*
|
||||||
|
* @param msg The message to decode
|
||||||
|
* @param hwstatus C-struct to decode the message contents into
|
||||||
|
*/
|
||||||
|
static inline void mavlink_msg_hwstatus_decode(const mavlink_message_t* msg, mavlink_hwstatus_t* hwstatus)
|
||||||
|
{
|
||||||
|
#if MAVLINK_NEED_BYTE_SWAP
|
||||||
|
hwstatus->Vcc = mavlink_msg_hwstatus_get_Vcc(msg);
|
||||||
|
hwstatus->I2Cerr = mavlink_msg_hwstatus_get_I2Cerr(msg);
|
||||||
|
#else
|
||||||
|
memcpy(hwstatus, _MAV_PAYLOAD(msg), 3);
|
||||||
|
#endif
|
||||||
|
}
|
@ -782,6 +782,51 @@ static void mavlink_test_simstate(uint8_t system_id, uint8_t component_id, mavli
|
|||||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static void mavlink_test_hwstatus(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_hwstatus_t packet_in = {
|
||||||
|
17235,
|
||||||
|
139,
|
||||||
|
};
|
||||||
|
mavlink_hwstatus_t packet1, packet2;
|
||||||
|
memset(&packet1, 0, sizeof(packet1));
|
||||||
|
packet1.Vcc = packet_in.Vcc;
|
||||||
|
packet1.I2Cerr = packet_in.I2Cerr;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
memset(&packet2, 0, sizeof(packet2));
|
||||||
|
mavlink_msg_hwstatus_encode(system_id, component_id, &msg, &packet1);
|
||||||
|
mavlink_msg_hwstatus_decode(&msg, &packet2);
|
||||||
|
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||||
|
|
||||||
|
memset(&packet2, 0, sizeof(packet2));
|
||||||
|
mavlink_msg_hwstatus_pack(system_id, component_id, &msg , packet1.Vcc , packet1.I2Cerr );
|
||||||
|
mavlink_msg_hwstatus_decode(&msg, &packet2);
|
||||||
|
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||||
|
|
||||||
|
memset(&packet2, 0, sizeof(packet2));
|
||||||
|
mavlink_msg_hwstatus_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.Vcc , packet1.I2Cerr );
|
||||||
|
mavlink_msg_hwstatus_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_hwstatus_decode(last_msg, &packet2);
|
||||||
|
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||||
|
|
||||||
|
memset(&packet2, 0, sizeof(packet2));
|
||||||
|
mavlink_msg_hwstatus_send(MAVLINK_COMM_1 , packet1.Vcc , packet1.I2Cerr );
|
||||||
|
mavlink_msg_hwstatus_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);
|
||||||
@ -798,6 +843,7 @@ static void mavlink_test_ardupilotmega(uint8_t system_id, uint8_t component_id,
|
|||||||
mavlink_test_fence_status(system_id, component_id, last_msg);
|
mavlink_test_fence_status(system_id, component_id, last_msg);
|
||||||
mavlink_test_dcm(system_id, component_id, last_msg);
|
mavlink_test_dcm(system_id, component_id, last_msg);
|
||||||
mavlink_test_simstate(system_id, component_id, last_msg);
|
mavlink_test_simstate(system_id, component_id, last_msg);
|
||||||
|
mavlink_test_hwstatus(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 "Thu Mar 1 13:22:36 2012"
|
#define MAVLINK_BUILD_DATE "Sat Mar 10 09:38:13 2012"
|
||||||
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
|
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
|
||||||
#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 "Thu Mar 1 13:22:36 2012"
|
#define MAVLINK_BUILD_DATE "Sat Mar 10 09:38:13 2012"
|
||||||
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
|
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
|
||||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
|
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
|
||||||
|
|
||||||
|
@ -164,7 +164,7 @@
|
|||||||
<field name="focus_lock" type="uint8_t">0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus</field>
|
<field name="focus_lock" type="uint8_t">0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus</field>
|
||||||
<field name="shot" type="uint8_t">0: ignore, 1: shot or start filming</field>
|
<field name="shot" type="uint8_t">0: ignore, 1: shot or start filming</field>
|
||||||
<field name="command_id" type="uint8_t">Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once</field>
|
<field name="command_id" type="uint8_t">Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once</field>
|
||||||
<field name="extra_param" type="uint8">Extra parameters enumeration (0 means ignore)</field>
|
<field name="extra_param" type="uint8_t">Extra parameters enumeration (0 means ignore)</field>
|
||||||
<field name="extra_value" type="float">Correspondent value to given extra_param</field>
|
<field name="extra_value" type="float">Correspondent value to given extra_param</field>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
@ -249,5 +249,11 @@
|
|||||||
<field type="float" name="ygyro">Angular speed around Y axis rad/s</field>
|
<field type="float" name="ygyro">Angular speed around Y axis rad/s</field>
|
||||||
<field type="float" name="zgyro">Angular speed around Z axis rad/s</field>
|
<field type="float" name="zgyro">Angular speed around Z axis rad/s</field>
|
||||||
</message>
|
</message>
|
||||||
|
|
||||||
|
<message name="HWSTATUS" id="165">
|
||||||
|
<description>Status of key hardware</description>
|
||||||
|
<field type="uint16_t" name="Vcc">board voltage (mV)</field>
|
||||||
|
<field type="uint8_t" name="I2Cerr">I2C error count</field>
|
||||||
|
</message>
|
||||||
</messages>
|
</messages>
|
||||||
</mavlink>
|
</mavlink>
|
||||||
|
Loading…
Reference in New Issue
Block a user