From 754ab0290bcb6b84432e943db0982bf14abef13d Mon Sep 17 00:00:00 2001 From: "tridge60@gmail.com" Date: Sun, 4 Sep 2011 08:50:24 +0000 Subject: [PATCH] import new mavlink version git-svn-id: https://arducopter.googlecode.com/svn/trunk@3238 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- .../ardupilotmega/mavlink_msg_meminfo.h | 4 +-- .../mavlink_msg_sensor_offsets.h | 24 +++++++------- .../mavlink_msg_set_mag_offsets.h | 10 +++--- .../include/ardupilotmega/version.h | 7 ++-- .../include/common/mavlink_msg_action.h | 6 ++-- .../include/common/mavlink_msg_action_ack.h | 4 +-- .../include/common/mavlink_msg_attitude.h | 14 ++++---- .../include/common/mavlink_msg_auth_key.h | 2 +- .../include/common/mavlink_msg_boot.h | 2 +- .../mavlink_msg_change_operator_control.h | 8 ++--- .../mavlink_msg_change_operator_control_ack.h | 6 ++-- .../include/common/mavlink_msg_command.h | 16 +++++----- .../include/common/mavlink_msg_command_ack.h | 4 +-- .../common/mavlink_msg_control_status.h | 16 +++++----- .../include/common/mavlink_msg_debug.h | 4 +-- .../include/common/mavlink_msg_debug_vect.h | 10 +++--- .../common/mavlink_msg_global_position.h | 14 ++++---- .../common/mavlink_msg_global_position_int.h | 12 +++---- .../common/mavlink_msg_gps_local_origin_set.h | 6 ++-- .../include/common/mavlink_msg_gps_raw.h | 18 +++++------ .../include/common/mavlink_msg_gps_raw_int.h | 18 +++++------ .../mavlink_msg_gps_set_global_origin.h | 10 +++--- .../include/common/mavlink_msg_gps_status.h | 12 +++---- .../include/common/mavlink_msg_heartbeat.h | 6 ++-- .../include/common/mavlink_msg_hil_controls.h | 14 ++++---- .../include/common/mavlink_msg_hil_state.h | 32 +++++++++---------- .../common/mavlink_msg_local_position.h | 14 ++++---- .../mavlink_msg_local_position_setpoint.h | 8 ++--- .../mavlink_msg_local_position_setpoint_set.h | 12 +++---- .../common/mavlink_msg_manual_control.h | 18 +++++------ .../common/mavlink_msg_named_value_float.h | 4 +-- .../common/mavlink_msg_named_value_int.h | 4 +-- .../mavlink_msg_nav_controller_output.h | 16 +++++----- .../mavlink_msg_object_detection_event.h | 14 ++++---- .../include/common/mavlink_msg_optical_flow.h | 12 +++---- .../common/mavlink_msg_param_request_list.h | 4 +-- .../common/mavlink_msg_param_request_read.h | 8 ++--- .../include/common/mavlink_msg_param_set.h | 8 ++--- .../include/common/mavlink_msg_param_value.h | 8 ++--- .../include/common/mavlink_msg_ping.h | 8 ++--- .../common/mavlink_msg_position_target.h | 8 ++--- .../include/common/mavlink_msg_raw_imu.h | 20 ++++++------ .../include/common/mavlink_msg_raw_pressure.h | 10 +++--- .../common/mavlink_msg_rc_channels_override.h | 20 ++++++------ .../common/mavlink_msg_rc_channels_raw.h | 18 +++++------ .../common/mavlink_msg_rc_channels_scaled.h | 18 +++++------ .../common/mavlink_msg_request_data_stream.h | 10 +++--- ...msg_roll_pitch_yaw_speed_thrust_setpoint.h | 10 +++--- ...vlink_msg_roll_pitch_yaw_thrust_setpoint.h | 10 +++--- .../common/mavlink_msg_safety_allowed_area.h | 14 ++++---- .../mavlink_msg_safety_set_allowed_area.h | 18 +++++------ .../include/common/mavlink_msg_scaled_imu.h | 20 ++++++------ .../common/mavlink_msg_scaled_pressure.h | 8 ++--- .../common/mavlink_msg_servo_output_raw.h | 16 +++++----- .../include/common/mavlink_msg_set_altitude.h | 4 +-- .../include/common/mavlink_msg_set_mode.h | 4 +-- .../include/common/mavlink_msg_set_nav_mode.h | 4 +-- ...link_msg_set_roll_pitch_yaw_speed_thrust.h | 12 +++---- .../mavlink_msg_set_roll_pitch_yaw_thrust.h | 12 +++---- .../common/mavlink_msg_state_correction.h | 18 +++++------ .../include/common/mavlink_msg_statustext.h | 4 +-- .../include/common/mavlink_msg_sys_status.h | 14 ++++---- .../include/common/mavlink_msg_system_time.h | 2 +- .../common/mavlink_msg_system_time_utc.h | 4 +-- .../include/common/mavlink_msg_vfr_hud.h | 12 +++---- .../include/common/mavlink_msg_waypoint.h | 28 ++++++++-------- .../include/common/mavlink_msg_waypoint_ack.h | 6 ++-- .../common/mavlink_msg_waypoint_clear_all.h | 4 +-- .../common/mavlink_msg_waypoint_count.h | 6 ++-- .../common/mavlink_msg_waypoint_current.h | 2 +- .../common/mavlink_msg_waypoint_reached.h | 2 +- .../common/mavlink_msg_waypoint_request.h | 6 ++-- .../mavlink_msg_waypoint_request_list.h | 4 +-- .../common/mavlink_msg_waypoint_set_current.h | 6 ++-- .../GCS_MAVLink/include/common/version.h | 7 ++-- .../GCS_MAVLink/include/mavlink_helpers.h | 2 +- libraries/GCS_MAVLink/include/mavlink_types.h | 6 +++- 77 files changed, 394 insertions(+), 392 deletions(-) diff --git a/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_meminfo.h b/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_meminfo.h index bd69363c19..b131967df9 100644 --- a/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_meminfo.h +++ b/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_meminfo.h @@ -16,8 +16,8 @@ typedef struct __mavlink_meminfo_t #define MAVLINK_MESSAGE_INFO_MEMINFO { \ "MEMINFO", \ 2, \ - { { "brkval", MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_meminfo_t, brkval) }, \ - { "freemem", MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_meminfo_t, freemem) }, \ + { { "brkval", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_meminfo_t, brkval) }, \ + { "freemem", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_meminfo_t, freemem) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_sensor_offsets.h b/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_sensor_offsets.h index d88471380d..216211a8f8 100644 --- a/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_sensor_offsets.h +++ b/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_sensor_offsets.h @@ -26,18 +26,18 @@ typedef struct __mavlink_sensor_offsets_t #define MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS { \ "SENSOR_OFFSETS", \ 12, \ - { { "mag_ofs_x", MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_sensor_offsets_t, mag_ofs_x) }, \ - { "mag_ofs_y", MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_sensor_offsets_t, mag_ofs_y) }, \ - { "mag_ofs_z", MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_sensor_offsets_t, mag_ofs_z) }, \ - { "mag_declination", MAVLINK_TYPE_FLOAT, 0, 6, offsetof(mavlink_sensor_offsets_t, mag_declination) }, \ - { "raw_press", MAVLINK_TYPE_INT32_T, 0, 10, offsetof(mavlink_sensor_offsets_t, raw_press) }, \ - { "raw_temp", MAVLINK_TYPE_INT32_T, 0, 14, offsetof(mavlink_sensor_offsets_t, raw_temp) }, \ - { "gyro_cal_x", MAVLINK_TYPE_FLOAT, 0, 18, offsetof(mavlink_sensor_offsets_t, gyro_cal_x) }, \ - { "gyro_cal_y", MAVLINK_TYPE_FLOAT, 0, 22, offsetof(mavlink_sensor_offsets_t, gyro_cal_y) }, \ - { "gyro_cal_z", MAVLINK_TYPE_FLOAT, 0, 26, offsetof(mavlink_sensor_offsets_t, gyro_cal_z) }, \ - { "accel_cal_x", MAVLINK_TYPE_FLOAT, 0, 30, offsetof(mavlink_sensor_offsets_t, accel_cal_x) }, \ - { "accel_cal_y", MAVLINK_TYPE_FLOAT, 0, 34, offsetof(mavlink_sensor_offsets_t, accel_cal_y) }, \ - { "accel_cal_z", MAVLINK_TYPE_FLOAT, 0, 38, offsetof(mavlink_sensor_offsets_t, accel_cal_z) }, \ + { { "mag_ofs_x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_sensor_offsets_t, mag_ofs_x) }, \ + { "mag_ofs_y", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_sensor_offsets_t, mag_ofs_y) }, \ + { "mag_ofs_z", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_sensor_offsets_t, mag_ofs_z) }, \ + { "mag_declination", NULL, MAVLINK_TYPE_FLOAT, 0, 6, offsetof(mavlink_sensor_offsets_t, mag_declination) }, \ + { "raw_press", NULL, MAVLINK_TYPE_INT32_T, 0, 10, offsetof(mavlink_sensor_offsets_t, raw_press) }, \ + { "raw_temp", NULL, MAVLINK_TYPE_INT32_T, 0, 14, offsetof(mavlink_sensor_offsets_t, raw_temp) }, \ + { "gyro_cal_x", NULL, MAVLINK_TYPE_FLOAT, 0, 18, offsetof(mavlink_sensor_offsets_t, gyro_cal_x) }, \ + { "gyro_cal_y", NULL, MAVLINK_TYPE_FLOAT, 0, 22, offsetof(mavlink_sensor_offsets_t, gyro_cal_y) }, \ + { "gyro_cal_z", NULL, MAVLINK_TYPE_FLOAT, 0, 26, offsetof(mavlink_sensor_offsets_t, gyro_cal_z) }, \ + { "accel_cal_x", NULL, MAVLINK_TYPE_FLOAT, 0, 30, offsetof(mavlink_sensor_offsets_t, accel_cal_x) }, \ + { "accel_cal_y", NULL, MAVLINK_TYPE_FLOAT, 0, 34, offsetof(mavlink_sensor_offsets_t, accel_cal_y) }, \ + { "accel_cal_z", NULL, MAVLINK_TYPE_FLOAT, 0, 38, offsetof(mavlink_sensor_offsets_t, accel_cal_z) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_set_mag_offsets.h b/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_set_mag_offsets.h index 96f09664e6..6243b440a9 100644 --- a/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_set_mag_offsets.h +++ b/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_set_mag_offsets.h @@ -19,11 +19,11 @@ typedef struct __mavlink_set_mag_offsets_t #define MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS { \ "SET_MAG_OFFSETS", \ 5, \ - { { "target_system", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_mag_offsets_t, target_system) }, \ - { "target_component", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_set_mag_offsets_t, target_component) }, \ - { "mag_ofs_x", MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_set_mag_offsets_t, mag_ofs_x) }, \ - { "mag_ofs_y", MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_set_mag_offsets_t, mag_ofs_y) }, \ - { "mag_ofs_z", MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_set_mag_offsets_t, mag_ofs_z) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_mag_offsets_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_set_mag_offsets_t, target_component) }, \ + { "mag_ofs_x", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_set_mag_offsets_t, mag_ofs_x) }, \ + { "mag_ofs_y", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_set_mag_offsets_t, mag_ofs_y) }, \ + { "mag_ofs_z", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_set_mag_offsets_t, mag_ofs_z) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/ardupilotmega/version.h b/libraries/GCS_MAVLink/include/ardupilotmega/version.h index eb5e6d1a31..56cea57450 100644 --- a/libraries/GCS_MAVLink/include/ardupilotmega/version.h +++ b/libraries/GCS_MAVLink/include/ardupilotmega/version.h @@ -5,9 +5,8 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Thu Sep 1 10:26:27 2011" +#define MAVLINK_BUILD_DATE "Sun Sep 4 18:16:41 2011" #define MAVLINK_WIRE_PROTOCOL_VERSION "0.9" - -#include "mavlink.h" - +#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101 + #endif // MAVLINK_VERSION_H diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_action.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_action.h index 43639cf546..a92f3e0052 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_action.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_action.h @@ -17,9 +17,9 @@ typedef struct __mavlink_action_t #define MAVLINK_MESSAGE_INFO_ACTION { \ "ACTION", \ 3, \ - { { "target", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_action_t, target) }, \ - { "target_component", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_action_t, target_component) }, \ - { "action", MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_action_t, action) }, \ + { { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_action_t, target) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_action_t, target_component) }, \ + { "action", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_action_t, action) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_action_ack.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_action_ack.h index 21daa2942e..b7fb3256db 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_action_ack.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_action_ack.h @@ -16,8 +16,8 @@ typedef struct __mavlink_action_ack_t #define MAVLINK_MESSAGE_INFO_ACTION_ACK { \ "ACTION_ACK", \ 2, \ - { { "action", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_action_ack_t, action) }, \ - { "result", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_action_ack_t, result) }, \ + { { "action", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_action_ack_t, action) }, \ + { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_action_ack_t, result) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_attitude.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_attitude.h index 0387be6ef4..d3e3cb3dc2 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_attitude.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_attitude.h @@ -21,13 +21,13 @@ typedef struct __mavlink_attitude_t #define MAVLINK_MESSAGE_INFO_ATTITUDE { \ "ATTITUDE", \ 7, \ - { { "usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_attitude_t, usec) }, \ - { "roll", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_t, roll) }, \ - { "pitch", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_t, pitch) }, \ - { "yaw", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_t, yaw) }, \ - { "rollspeed", MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_t, rollspeed) }, \ - { "pitchspeed", MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_t, pitchspeed) }, \ - { "yawspeed", MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_t, yawspeed) }, \ + { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_attitude_t, usec) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_t, yaw) }, \ + { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_t, rollspeed) }, \ + { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_t, pitchspeed) }, \ + { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_t, yawspeed) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_auth_key.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_auth_key.h index 33a05efda5..d7becd9952 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_auth_key.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_auth_key.h @@ -15,7 +15,7 @@ typedef struct __mavlink_auth_key_t #define MAVLINK_MESSAGE_INFO_AUTH_KEY { \ "AUTH_KEY", \ 1, \ - { { "key", MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_auth_key_t, key) }, \ + { { "key", NULL, MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_auth_key_t, key) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_boot.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_boot.h index 68c3c0b8fa..7541cabef6 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_boot.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_boot.h @@ -15,7 +15,7 @@ typedef struct __mavlink_boot_t #define MAVLINK_MESSAGE_INFO_BOOT { \ "BOOT", \ 1, \ - { { "version", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_boot_t, version) }, \ + { { "version", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_boot_t, version) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_change_operator_control.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_change_operator_control.h index 3837e9f5d5..f6842e9451 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_change_operator_control.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_change_operator_control.h @@ -18,10 +18,10 @@ typedef struct __mavlink_change_operator_control_t #define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL { \ "CHANGE_OPERATOR_CONTROL", \ 4, \ - { { "target_system", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_t, target_system) }, \ - { "control_request", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_t, control_request) }, \ - { "version", MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_t, version) }, \ - { "passkey", MAVLINK_TYPE_CHAR, 25, 3, offsetof(mavlink_change_operator_control_t, passkey) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_t, target_system) }, \ + { "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_t, control_request) }, \ + { "version", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_t, version) }, \ + { "passkey", NULL, MAVLINK_TYPE_CHAR, 25, 3, offsetof(mavlink_change_operator_control_t, passkey) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_change_operator_control_ack.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_change_operator_control_ack.h index 27b3e12d00..a24c6f5a06 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_change_operator_control_ack.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_change_operator_control_ack.h @@ -17,9 +17,9 @@ typedef struct __mavlink_change_operator_control_ack_t #define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK { \ "CHANGE_OPERATOR_CONTROL_ACK", \ 3, \ - { { "gcs_system_id", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_ack_t, gcs_system_id) }, \ - { "control_request", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_ack_t, control_request) }, \ - { "ack", MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_ack_t, ack) }, \ + { { "gcs_system_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_ack_t, gcs_system_id) }, \ + { "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_ack_t, control_request) }, \ + { "ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_ack_t, ack) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_command.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_command.h index 065893327f..a7221fa444 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_command.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_command.h @@ -22,14 +22,14 @@ typedef struct __mavlink_command_t #define MAVLINK_MESSAGE_INFO_COMMAND { \ "COMMAND", \ 8, \ - { { "target_system", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_command_t, target_system) }, \ - { "target_component", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_command_t, target_component) }, \ - { "command", MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_t, command) }, \ - { "confirmation", MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_command_t, confirmation) }, \ - { "param1", MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_t, param1) }, \ - { "param2", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_t, param2) }, \ - { "param3", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_t, param3) }, \ - { "param4", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_t, param4) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_command_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_command_t, target_component) }, \ + { "command", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_t, command) }, \ + { "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_command_t, confirmation) }, \ + { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_t, param1) }, \ + { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_t, param2) }, \ + { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_t, param3) }, \ + { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_t, param4) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_command_ack.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_command_ack.h index be37eeca73..7fc8c86232 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_command_ack.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_command_ack.h @@ -16,8 +16,8 @@ typedef struct __mavlink_command_ack_t #define MAVLINK_MESSAGE_INFO_COMMAND_ACK { \ "COMMAND_ACK", \ 2, \ - { { "command", MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_ack_t, command) }, \ - { "result", MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_ack_t, result) }, \ + { { "command", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_ack_t, command) }, \ + { "result", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_ack_t, result) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_control_status.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_control_status.h index 534abe60e0..617cf5ba98 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_control_status.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_control_status.h @@ -22,14 +22,14 @@ typedef struct __mavlink_control_status_t #define MAVLINK_MESSAGE_INFO_CONTROL_STATUS { \ "CONTROL_STATUS", \ 8, \ - { { "position_fix", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_control_status_t, position_fix) }, \ - { "vision_fix", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_control_status_t, vision_fix) }, \ - { "gps_fix", MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_control_status_t, gps_fix) }, \ - { "ahrs_health", MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_control_status_t, ahrs_health) }, \ - { "control_att", MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_control_status_t, control_att) }, \ - { "control_pos_xy", MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_control_status_t, control_pos_xy) }, \ - { "control_pos_z", MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_control_status_t, control_pos_z) }, \ - { "control_pos_yaw", MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_control_status_t, control_pos_yaw) }, \ + { { "position_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_control_status_t, position_fix) }, \ + { "vision_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_control_status_t, vision_fix) }, \ + { "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_control_status_t, gps_fix) }, \ + { "ahrs_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_control_status_t, ahrs_health) }, \ + { "control_att", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_control_status_t, control_att) }, \ + { "control_pos_xy", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_control_status_t, control_pos_xy) }, \ + { "control_pos_z", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_control_status_t, control_pos_z) }, \ + { "control_pos_yaw", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_control_status_t, control_pos_yaw) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_debug.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_debug.h index 7e80a146b1..1f0788a3a4 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_debug.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_debug.h @@ -16,8 +16,8 @@ typedef struct __mavlink_debug_t #define MAVLINK_MESSAGE_INFO_DEBUG { \ "DEBUG", \ 2, \ - { { "ind", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_debug_t, ind) }, \ - { "value", MAVLINK_TYPE_FLOAT, 0, 1, offsetof(mavlink_debug_t, value) }, \ + { { "ind", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_debug_t, ind) }, \ + { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 1, offsetof(mavlink_debug_t, value) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_debug_vect.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_debug_vect.h index 500284e9ba..196d539b39 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_debug_vect.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_debug_vect.h @@ -19,11 +19,11 @@ typedef struct __mavlink_debug_vect_t #define MAVLINK_MESSAGE_INFO_DEBUG_VECT { \ "DEBUG_VECT", \ 5, \ - { { "name", MAVLINK_TYPE_CHAR, 10, 0, offsetof(mavlink_debug_vect_t, name) }, \ - { "usec", MAVLINK_TYPE_UINT64_T, 0, 10, offsetof(mavlink_debug_vect_t, usec) }, \ - { "x", MAVLINK_TYPE_FLOAT, 0, 18, offsetof(mavlink_debug_vect_t, x) }, \ - { "y", MAVLINK_TYPE_FLOAT, 0, 22, offsetof(mavlink_debug_vect_t, y) }, \ - { "z", MAVLINK_TYPE_FLOAT, 0, 26, offsetof(mavlink_debug_vect_t, z) }, \ + { { "name", NULL, MAVLINK_TYPE_CHAR, 10, 0, offsetof(mavlink_debug_vect_t, name) }, \ + { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 10, offsetof(mavlink_debug_vect_t, usec) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 18, offsetof(mavlink_debug_vect_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 22, offsetof(mavlink_debug_vect_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 26, offsetof(mavlink_debug_vect_t, z) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_global_position.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_global_position.h index 05cd7456dd..d281646a56 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_global_position.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_global_position.h @@ -21,13 +21,13 @@ typedef struct __mavlink_global_position_t #define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION { \ "GLOBAL_POSITION", \ 7, \ - { { "usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_t, usec) }, \ - { "lat", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_global_position_t, lat) }, \ - { "lon", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_global_position_t, lon) }, \ - { "alt", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_global_position_t, alt) }, \ - { "vx", MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_global_position_t, vx) }, \ - { "vy", MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_position_t, vy) }, \ - { "vz", MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_t, vz) }, \ + { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_t, usec) }, \ + { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_global_position_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_global_position_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_global_position_t, alt) }, \ + { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_global_position_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_position_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_t, vz) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_global_position_int.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_global_position_int.h index 233665115f..fa984daadf 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_global_position_int.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_global_position_int.h @@ -20,12 +20,12 @@ typedef struct __mavlink_global_position_int_t #define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT { \ "GLOBAL_POSITION_INT", \ 6, \ - { { "lat", MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_global_position_int_t, lat) }, \ - { "lon", MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_int_t, lon) }, \ - { "alt", MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_t, alt) }, \ - { "vx", MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_global_position_int_t, vx) }, \ - { "vy", MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_global_position_int_t, vy) }, \ - { "vz", MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_global_position_int_t, vz) }, \ + { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_global_position_int_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_int_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_t, alt) }, \ + { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_global_position_int_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_global_position_int_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_global_position_int_t, vz) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_gps_local_origin_set.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_gps_local_origin_set.h index d71fc7758a..0e011483bd 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_gps_local_origin_set.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_gps_local_origin_set.h @@ -17,9 +17,9 @@ typedef struct __mavlink_gps_local_origin_set_t #define MAVLINK_MESSAGE_INFO_GPS_LOCAL_ORIGIN_SET { \ "GPS_LOCAL_ORIGIN_SET", \ 3, \ - { { "latitude", MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_gps_local_origin_set_t, latitude) }, \ - { "longitude", MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_gps_local_origin_set_t, longitude) }, \ - { "altitude", MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_local_origin_set_t, altitude) }, \ + { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_gps_local_origin_set_t, latitude) }, \ + { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_gps_local_origin_set_t, longitude) }, \ + { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_local_origin_set_t, altitude) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_gps_raw.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_gps_raw.h index 9a91a3e0eb..e2e0051498 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_gps_raw.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_gps_raw.h @@ -23,15 +23,15 @@ typedef struct __mavlink_gps_raw_t #define MAVLINK_MESSAGE_INFO_GPS_RAW { \ "GPS_RAW", \ 9, \ - { { "usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_t, usec) }, \ - { "fix_type", MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_gps_raw_t, fix_type) }, \ - { "lat", MAVLINK_TYPE_FLOAT, 0, 9, offsetof(mavlink_gps_raw_t, lat) }, \ - { "lon", MAVLINK_TYPE_FLOAT, 0, 13, offsetof(mavlink_gps_raw_t, lon) }, \ - { "alt", MAVLINK_TYPE_FLOAT, 0, 17, offsetof(mavlink_gps_raw_t, alt) }, \ - { "eph", MAVLINK_TYPE_FLOAT, 0, 21, offsetof(mavlink_gps_raw_t, eph) }, \ - { "epv", MAVLINK_TYPE_FLOAT, 0, 25, offsetof(mavlink_gps_raw_t, epv) }, \ - { "v", MAVLINK_TYPE_FLOAT, 0, 29, offsetof(mavlink_gps_raw_t, v) }, \ - { "hdg", MAVLINK_TYPE_FLOAT, 0, 33, offsetof(mavlink_gps_raw_t, hdg) }, \ + { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_t, usec) }, \ + { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_gps_raw_t, fix_type) }, \ + { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 9, offsetof(mavlink_gps_raw_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 13, offsetof(mavlink_gps_raw_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 17, offsetof(mavlink_gps_raw_t, alt) }, \ + { "eph", NULL, MAVLINK_TYPE_FLOAT, 0, 21, offsetof(mavlink_gps_raw_t, eph) }, \ + { "epv", NULL, MAVLINK_TYPE_FLOAT, 0, 25, offsetof(mavlink_gps_raw_t, epv) }, \ + { "v", NULL, MAVLINK_TYPE_FLOAT, 0, 29, offsetof(mavlink_gps_raw_t, v) }, \ + { "hdg", NULL, MAVLINK_TYPE_FLOAT, 0, 33, offsetof(mavlink_gps_raw_t, hdg) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_gps_raw_int.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_gps_raw_int.h index 9edb55a8f2..5f5b595601 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_gps_raw_int.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_gps_raw_int.h @@ -23,15 +23,15 @@ typedef struct __mavlink_gps_raw_int_t #define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \ "GPS_RAW_INT", \ 9, \ - { { "usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, usec) }, \ - { "fix_type", MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_gps_raw_int_t, fix_type) }, \ - { "lat", MAVLINK_TYPE_INT32_T, 0, 9, offsetof(mavlink_gps_raw_int_t, lat) }, \ - { "lon", MAVLINK_TYPE_INT32_T, 0, 13, offsetof(mavlink_gps_raw_int_t, lon) }, \ - { "alt", MAVLINK_TYPE_INT32_T, 0, 17, offsetof(mavlink_gps_raw_int_t, alt) }, \ - { "eph", MAVLINK_TYPE_FLOAT, 0, 21, offsetof(mavlink_gps_raw_int_t, eph) }, \ - { "epv", MAVLINK_TYPE_FLOAT, 0, 25, offsetof(mavlink_gps_raw_int_t, epv) }, \ - { "v", MAVLINK_TYPE_FLOAT, 0, 29, offsetof(mavlink_gps_raw_int_t, v) }, \ - { "hdg", MAVLINK_TYPE_FLOAT, 0, 33, offsetof(mavlink_gps_raw_int_t, hdg) }, \ + { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, usec) }, \ + { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_gps_raw_int_t, fix_type) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 9, offsetof(mavlink_gps_raw_int_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 13, offsetof(mavlink_gps_raw_int_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 17, offsetof(mavlink_gps_raw_int_t, alt) }, \ + { "eph", NULL, MAVLINK_TYPE_FLOAT, 0, 21, offsetof(mavlink_gps_raw_int_t, eph) }, \ + { "epv", NULL, MAVLINK_TYPE_FLOAT, 0, 25, offsetof(mavlink_gps_raw_int_t, epv) }, \ + { "v", NULL, MAVLINK_TYPE_FLOAT, 0, 29, offsetof(mavlink_gps_raw_int_t, v) }, \ + { "hdg", NULL, MAVLINK_TYPE_FLOAT, 0, 33, offsetof(mavlink_gps_raw_int_t, hdg) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_gps_set_global_origin.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_gps_set_global_origin.h index 48cd0f42d6..664f781646 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_gps_set_global_origin.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_gps_set_global_origin.h @@ -19,11 +19,11 @@ typedef struct __mavlink_gps_set_global_origin_t #define MAVLINK_MESSAGE_INFO_GPS_SET_GLOBAL_ORIGIN { \ "GPS_SET_GLOBAL_ORIGIN", \ 5, \ - { { "target_system", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_set_global_origin_t, target_system) }, \ - { "target_component", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gps_set_global_origin_t, target_component) }, \ - { "latitude", MAVLINK_TYPE_INT32_T, 0, 2, offsetof(mavlink_gps_set_global_origin_t, latitude) }, \ - { "longitude", MAVLINK_TYPE_INT32_T, 0, 6, offsetof(mavlink_gps_set_global_origin_t, longitude) }, \ - { "altitude", MAVLINK_TYPE_INT32_T, 0, 10, offsetof(mavlink_gps_set_global_origin_t, altitude) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_set_global_origin_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gps_set_global_origin_t, target_component) }, \ + { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 2, offsetof(mavlink_gps_set_global_origin_t, latitude) }, \ + { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 6, offsetof(mavlink_gps_set_global_origin_t, longitude) }, \ + { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 10, offsetof(mavlink_gps_set_global_origin_t, altitude) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_gps_status.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_gps_status.h index 6d415dbd03..099a03af8d 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_gps_status.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_gps_status.h @@ -24,12 +24,12 @@ typedef struct __mavlink_gps_status_t #define MAVLINK_MESSAGE_INFO_GPS_STATUS { \ "GPS_STATUS", \ 6, \ - { { "satellites_visible", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_status_t, satellites_visible) }, \ - { "satellite_prn", MAVLINK_TYPE_INT8_T, 20, 1, offsetof(mavlink_gps_status_t, satellite_prn) }, \ - { "satellite_used", MAVLINK_TYPE_INT8_T, 20, 21, offsetof(mavlink_gps_status_t, satellite_used) }, \ - { "satellite_elevation", MAVLINK_TYPE_INT8_T, 20, 41, offsetof(mavlink_gps_status_t, satellite_elevation) }, \ - { "satellite_azimuth", MAVLINK_TYPE_INT8_T, 20, 61, offsetof(mavlink_gps_status_t, satellite_azimuth) }, \ - { "satellite_snr", MAVLINK_TYPE_INT8_T, 20, 81, offsetof(mavlink_gps_status_t, satellite_snr) }, \ + { { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_status_t, satellites_visible) }, \ + { "satellite_prn", NULL, MAVLINK_TYPE_INT8_T, 20, 1, offsetof(mavlink_gps_status_t, satellite_prn) }, \ + { "satellite_used", NULL, MAVLINK_TYPE_INT8_T, 20, 21, offsetof(mavlink_gps_status_t, satellite_used) }, \ + { "satellite_elevation", NULL, MAVLINK_TYPE_INT8_T, 20, 41, offsetof(mavlink_gps_status_t, satellite_elevation) }, \ + { "satellite_azimuth", NULL, MAVLINK_TYPE_INT8_T, 20, 61, offsetof(mavlink_gps_status_t, satellite_azimuth) }, \ + { "satellite_snr", NULL, MAVLINK_TYPE_INT8_T, 20, 81, offsetof(mavlink_gps_status_t, satellite_snr) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_heartbeat.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_heartbeat.h index 4006cd5585..86bf637b1b 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_heartbeat.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_heartbeat.h @@ -17,9 +17,9 @@ typedef struct __mavlink_heartbeat_t #define MAVLINK_MESSAGE_INFO_HEARTBEAT { \ "HEARTBEAT", \ 3, \ - { { "type", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_heartbeat_t, type) }, \ - { "autopilot", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_heartbeat_t, autopilot) }, \ - { "mavlink_version", MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_heartbeat_t, mavlink_version) }, \ + { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_heartbeat_t, type) }, \ + { "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_heartbeat_t, autopilot) }, \ + { "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_heartbeat_t, mavlink_version) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_hil_controls.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_hil_controls.h index 6f43ff26ac..302b23d41c 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_hil_controls.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_hil_controls.h @@ -21,13 +21,13 @@ typedef struct __mavlink_hil_controls_t #define MAVLINK_MESSAGE_INFO_HIL_CONTROLS { \ "HIL_CONTROLS", \ 7, \ - { { "time_us", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_controls_t, time_us) }, \ - { "roll_ailerons", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_controls_t, roll_ailerons) }, \ - { "pitch_elevator", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_controls_t, pitch_elevator) }, \ - { "yaw_rudder", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_controls_t, yaw_rudder) }, \ - { "throttle", MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_controls_t, throttle) }, \ - { "mode", MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_hil_controls_t, mode) }, \ - { "nav_mode", MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_hil_controls_t, nav_mode) }, \ + { { "time_us", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_controls_t, time_us) }, \ + { "roll_ailerons", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_controls_t, roll_ailerons) }, \ + { "pitch_elevator", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_controls_t, pitch_elevator) }, \ + { "yaw_rudder", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_controls_t, yaw_rudder) }, \ + { "throttle", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_controls_t, throttle) }, \ + { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_hil_controls_t, mode) }, \ + { "nav_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_hil_controls_t, nav_mode) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_hil_state.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_hil_state.h index 9f6af9c0cb..53c3a8efeb 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_hil_state.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_hil_state.h @@ -30,22 +30,22 @@ typedef struct __mavlink_hil_state_t #define MAVLINK_MESSAGE_INFO_HIL_STATE { \ "HIL_STATE", \ 16, \ - { { "usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_t, usec) }, \ - { "roll", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_state_t, roll) }, \ - { "pitch", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_state_t, pitch) }, \ - { "yaw", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_state_t, yaw) }, \ - { "rollspeed", MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_state_t, rollspeed) }, \ - { "pitchspeed", MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_t, pitchspeed) }, \ - { "yawspeed", MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_t, yawspeed) }, \ - { "lat", MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_hil_state_t, lat) }, \ - { "lon", MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_t, lon) }, \ - { "alt", MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_t, alt) }, \ - { "vx", MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_hil_state_t, vx) }, \ - { "vy", MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_hil_state_t, vy) }, \ - { "vz", MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_t, vz) }, \ - { "xacc", MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_t, xacc) }, \ - { "yacc", MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_t, yacc) }, \ - { "zacc", MAVLINK_TYPE_INT16_T, 0, 54, offsetof(mavlink_hil_state_t, zacc) }, \ + { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_t, usec) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_state_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_state_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_state_t, yaw) }, \ + { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_state_t, rollspeed) }, \ + { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_t, pitchspeed) }, \ + { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_t, yawspeed) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_hil_state_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_t, alt) }, \ + { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_hil_state_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_hil_state_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_t, vz) }, \ + { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 54, offsetof(mavlink_hil_state_t, zacc) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_local_position.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_local_position.h index 1adbd0c540..fca313b8e9 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_local_position.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_local_position.h @@ -21,13 +21,13 @@ typedef struct __mavlink_local_position_t #define MAVLINK_MESSAGE_INFO_LOCAL_POSITION { \ "LOCAL_POSITION", \ 7, \ - { { "usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_local_position_t, usec) }, \ - { "x", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_t, x) }, \ - { "y", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_t, y) }, \ - { "z", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_t, z) }, \ - { "vx", MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_t, vx) }, \ - { "vy", MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_t, vy) }, \ - { "vz", MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_local_position_t, vz) }, \ + { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_local_position_t, usec) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_t, z) }, \ + { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_local_position_t, vz) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_local_position_setpoint.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_local_position_setpoint.h index 0bc4d98007..08c8e35eb2 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_local_position_setpoint.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_local_position_setpoint.h @@ -18,10 +18,10 @@ typedef struct __mavlink_local_position_setpoint_t #define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT { \ "LOCAL_POSITION_SETPOINT", \ 4, \ - { { "x", MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_local_position_setpoint_t, x) }, \ - { "y", MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_setpoint_t, y) }, \ - { "z", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_setpoint_t, z) }, \ - { "yaw", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_setpoint_t, yaw) }, \ + { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_local_position_setpoint_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_setpoint_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_setpoint_t, z) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_setpoint_t, yaw) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_local_position_setpoint_set.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_local_position_setpoint_set.h index 9eea4d7195..de3aee9498 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_local_position_setpoint_set.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_local_position_setpoint_set.h @@ -20,12 +20,12 @@ typedef struct __mavlink_local_position_setpoint_set_t #define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT_SET { \ "LOCAL_POSITION_SETPOINT_SET", \ 6, \ - { { "target_system", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_local_position_setpoint_set_t, target_system) }, \ - { "target_component", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_local_position_setpoint_set_t, target_component) }, \ - { "x", MAVLINK_TYPE_FLOAT, 0, 2, offsetof(mavlink_local_position_setpoint_set_t, x) }, \ - { "y", MAVLINK_TYPE_FLOAT, 0, 6, offsetof(mavlink_local_position_setpoint_set_t, y) }, \ - { "z", MAVLINK_TYPE_FLOAT, 0, 10, offsetof(mavlink_local_position_setpoint_set_t, z) }, \ - { "yaw", MAVLINK_TYPE_FLOAT, 0, 14, offsetof(mavlink_local_position_setpoint_set_t, yaw) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_local_position_setpoint_set_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_local_position_setpoint_set_t, target_component) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 2, offsetof(mavlink_local_position_setpoint_set_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 6, offsetof(mavlink_local_position_setpoint_set_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 10, offsetof(mavlink_local_position_setpoint_set_t, z) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 14, offsetof(mavlink_local_position_setpoint_set_t, yaw) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_manual_control.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_manual_control.h index 8b2e24d43a..09db3d9216 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_manual_control.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_manual_control.h @@ -23,15 +23,15 @@ typedef struct __mavlink_manual_control_t #define MAVLINK_MESSAGE_INFO_MANUAL_CONTROL { \ "MANUAL_CONTROL", \ 9, \ - { { "target", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_manual_control_t, target) }, \ - { "roll", MAVLINK_TYPE_FLOAT, 0, 1, offsetof(mavlink_manual_control_t, roll) }, \ - { "pitch", MAVLINK_TYPE_FLOAT, 0, 5, offsetof(mavlink_manual_control_t, pitch) }, \ - { "yaw", MAVLINK_TYPE_FLOAT, 0, 9, offsetof(mavlink_manual_control_t, yaw) }, \ - { "thrust", MAVLINK_TYPE_FLOAT, 0, 13, offsetof(mavlink_manual_control_t, thrust) }, \ - { "roll_manual", MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_manual_control_t, roll_manual) }, \ - { "pitch_manual", MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_manual_control_t, pitch_manual) }, \ - { "yaw_manual", MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_manual_control_t, yaw_manual) }, \ - { "thrust_manual", MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_manual_control_t, thrust_manual) }, \ + { { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_manual_control_t, target) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 1, offsetof(mavlink_manual_control_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 5, offsetof(mavlink_manual_control_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 9, offsetof(mavlink_manual_control_t, yaw) }, \ + { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 13, offsetof(mavlink_manual_control_t, thrust) }, \ + { "roll_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_manual_control_t, roll_manual) }, \ + { "pitch_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_manual_control_t, pitch_manual) }, \ + { "yaw_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_manual_control_t, yaw_manual) }, \ + { "thrust_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_manual_control_t, thrust_manual) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_named_value_float.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_named_value_float.h index 791e32421c..0cd255286e 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_named_value_float.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_named_value_float.h @@ -16,8 +16,8 @@ typedef struct __mavlink_named_value_float_t #define MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT { \ "NAMED_VALUE_FLOAT", \ 2, \ - { { "name", MAVLINK_TYPE_CHAR, 10, 0, offsetof(mavlink_named_value_float_t, name) }, \ - { "value", MAVLINK_TYPE_FLOAT, 0, 10, offsetof(mavlink_named_value_float_t, value) }, \ + { { "name", NULL, MAVLINK_TYPE_CHAR, 10, 0, offsetof(mavlink_named_value_float_t, name) }, \ + { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 10, offsetof(mavlink_named_value_float_t, value) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_named_value_int.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_named_value_int.h index 18bad80a11..7d864eb69f 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_named_value_int.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_named_value_int.h @@ -16,8 +16,8 @@ typedef struct __mavlink_named_value_int_t #define MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT { \ "NAMED_VALUE_INT", \ 2, \ - { { "name", MAVLINK_TYPE_CHAR, 10, 0, offsetof(mavlink_named_value_int_t, name) }, \ - { "value", MAVLINK_TYPE_INT32_T, 0, 10, offsetof(mavlink_named_value_int_t, value) }, \ + { { "name", NULL, MAVLINK_TYPE_CHAR, 10, 0, offsetof(mavlink_named_value_int_t, name) }, \ + { "value", NULL, MAVLINK_TYPE_INT32_T, 0, 10, offsetof(mavlink_named_value_int_t, value) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_nav_controller_output.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_nav_controller_output.h index 34cdb4b671..8322c8fabb 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_nav_controller_output.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_nav_controller_output.h @@ -22,14 +22,14 @@ typedef struct __mavlink_nav_controller_output_t #define MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT { \ "NAV_CONTROLLER_OUTPUT", \ 8, \ - { { "nav_roll", MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_nav_controller_output_t, nav_roll) }, \ - { "nav_pitch", MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_nav_controller_output_t, nav_pitch) }, \ - { "nav_bearing", MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_nav_controller_output_t, nav_bearing) }, \ - { "target_bearing", MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_nav_controller_output_t, target_bearing) }, \ - { "wp_dist", MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_nav_controller_output_t, wp_dist) }, \ - { "alt_error", MAVLINK_TYPE_FLOAT, 0, 14, offsetof(mavlink_nav_controller_output_t, alt_error) }, \ - { "aspd_error", MAVLINK_TYPE_FLOAT, 0, 18, offsetof(mavlink_nav_controller_output_t, aspd_error) }, \ - { "xtrack_error", MAVLINK_TYPE_FLOAT, 0, 22, offsetof(mavlink_nav_controller_output_t, xtrack_error) }, \ + { { "nav_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_nav_controller_output_t, nav_roll) }, \ + { "nav_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_nav_controller_output_t, nav_pitch) }, \ + { "nav_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_nav_controller_output_t, nav_bearing) }, \ + { "target_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_nav_controller_output_t, target_bearing) }, \ + { "wp_dist", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_nav_controller_output_t, wp_dist) }, \ + { "alt_error", NULL, MAVLINK_TYPE_FLOAT, 0, 14, offsetof(mavlink_nav_controller_output_t, alt_error) }, \ + { "aspd_error", NULL, MAVLINK_TYPE_FLOAT, 0, 18, offsetof(mavlink_nav_controller_output_t, aspd_error) }, \ + { "xtrack_error", NULL, MAVLINK_TYPE_FLOAT, 0, 22, offsetof(mavlink_nav_controller_output_t, xtrack_error) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_object_detection_event.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_object_detection_event.h index ac53aab00b..a2ec12ec3f 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_object_detection_event.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_object_detection_event.h @@ -21,13 +21,13 @@ typedef struct __mavlink_object_detection_event_t #define MAVLINK_MESSAGE_INFO_OBJECT_DETECTION_EVENT { \ "OBJECT_DETECTION_EVENT", \ 7, \ - { { "time", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_object_detection_event_t, time) }, \ - { "object_id", MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_object_detection_event_t, object_id) }, \ - { "type", MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_object_detection_event_t, type) }, \ - { "name", MAVLINK_TYPE_CHAR, 20, 7, offsetof(mavlink_object_detection_event_t, name) }, \ - { "quality", MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_object_detection_event_t, quality) }, \ - { "bearing", MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_object_detection_event_t, bearing) }, \ - { "distance", MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_object_detection_event_t, distance) }, \ + { { "time", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_object_detection_event_t, time) }, \ + { "object_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_object_detection_event_t, object_id) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_object_detection_event_t, type) }, \ + { "name", NULL, MAVLINK_TYPE_CHAR, 20, 7, offsetof(mavlink_object_detection_event_t, name) }, \ + { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_object_detection_event_t, quality) }, \ + { "bearing", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_object_detection_event_t, bearing) }, \ + { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_object_detection_event_t, distance) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_optical_flow.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_optical_flow.h index 00f1c4c237..a4bfb18a7c 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_optical_flow.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_optical_flow.h @@ -20,12 +20,12 @@ typedef struct __mavlink_optical_flow_t #define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW { \ "OPTICAL_FLOW", \ 6, \ - { { "time", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time) }, \ - { "sensor_id", MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_optical_flow_t, sensor_id) }, \ - { "flow_x", MAVLINK_TYPE_INT16_T, 0, 9, offsetof(mavlink_optical_flow_t, flow_x) }, \ - { "flow_y", MAVLINK_TYPE_INT16_T, 0, 11, offsetof(mavlink_optical_flow_t, flow_y) }, \ - { "quality", MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_optical_flow_t, quality) }, \ - { "ground_distance", MAVLINK_TYPE_FLOAT, 0, 14, offsetof(mavlink_optical_flow_t, ground_distance) }, \ + { { "time", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time) }, \ + { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_optical_flow_t, sensor_id) }, \ + { "flow_x", NULL, MAVLINK_TYPE_INT16_T, 0, 9, offsetof(mavlink_optical_flow_t, flow_x) }, \ + { "flow_y", NULL, MAVLINK_TYPE_INT16_T, 0, 11, offsetof(mavlink_optical_flow_t, flow_y) }, \ + { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_optical_flow_t, quality) }, \ + { "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 14, offsetof(mavlink_optical_flow_t, ground_distance) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_param_request_list.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_param_request_list.h index 817f50a3f3..123ac79778 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_param_request_list.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_param_request_list.h @@ -16,8 +16,8 @@ typedef struct __mavlink_param_request_list_t #define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST { \ "PARAM_REQUEST_LIST", \ 2, \ - { { "target_system", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_param_request_list_t, target_system) }, \ - { "target_component", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_param_request_list_t, target_component) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_param_request_list_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_param_request_list_t, target_component) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_param_request_read.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_param_request_read.h index 93db0b610e..6968420ded 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_param_request_read.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_param_request_read.h @@ -18,10 +18,10 @@ typedef struct __mavlink_param_request_read_t #define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ { \ "PARAM_REQUEST_READ", \ 4, \ - { { "target_system", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_param_request_read_t, target_system) }, \ - { "target_component", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_param_request_read_t, target_component) }, \ - { "param_id", MAVLINK_TYPE_INT8_T, 15, 2, offsetof(mavlink_param_request_read_t, param_id) }, \ - { "param_index", MAVLINK_TYPE_INT16_T, 0, 17, offsetof(mavlink_param_request_read_t, param_index) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_param_request_read_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_param_request_read_t, target_component) }, \ + { "param_id", NULL, MAVLINK_TYPE_INT8_T, 15, 2, offsetof(mavlink_param_request_read_t, param_id) }, \ + { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 17, offsetof(mavlink_param_request_read_t, param_index) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_param_set.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_param_set.h index e54b9ba38a..a2feed407b 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_param_set.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_param_set.h @@ -18,10 +18,10 @@ typedef struct __mavlink_param_set_t #define MAVLINK_MESSAGE_INFO_PARAM_SET { \ "PARAM_SET", \ 4, \ - { { "target_system", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_param_set_t, target_system) }, \ - { "target_component", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_param_set_t, target_component) }, \ - { "param_id", MAVLINK_TYPE_INT8_T, 15, 2, offsetof(mavlink_param_set_t, param_id) }, \ - { "param_value", MAVLINK_TYPE_FLOAT, 0, 17, offsetof(mavlink_param_set_t, param_value) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_param_set_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_param_set_t, target_component) }, \ + { "param_id", NULL, MAVLINK_TYPE_INT8_T, 15, 2, offsetof(mavlink_param_set_t, param_id) }, \ + { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 17, offsetof(mavlink_param_set_t, param_value) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_param_value.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_param_value.h index 84b4e7dd16..8e1408790d 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_param_value.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_param_value.h @@ -18,10 +18,10 @@ typedef struct __mavlink_param_value_t #define MAVLINK_MESSAGE_INFO_PARAM_VALUE { \ "PARAM_VALUE", \ 4, \ - { { "param_id", MAVLINK_TYPE_INT8_T, 15, 0, offsetof(mavlink_param_value_t, param_id) }, \ - { "param_value", MAVLINK_TYPE_FLOAT, 0, 15, offsetof(mavlink_param_value_t, param_value) }, \ - { "param_count", MAVLINK_TYPE_UINT16_T, 0, 19, offsetof(mavlink_param_value_t, param_count) }, \ - { "param_index", MAVLINK_TYPE_UINT16_T, 0, 21, offsetof(mavlink_param_value_t, param_index) }, \ + { { "param_id", NULL, MAVLINK_TYPE_INT8_T, 15, 0, offsetof(mavlink_param_value_t, param_id) }, \ + { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 15, offsetof(mavlink_param_value_t, param_value) }, \ + { "param_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 19, offsetof(mavlink_param_value_t, param_count) }, \ + { "param_index", NULL, MAVLINK_TYPE_UINT16_T, 0, 21, offsetof(mavlink_param_value_t, param_index) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_ping.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_ping.h index 536c7f1d58..c424221380 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_ping.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_ping.h @@ -18,10 +18,10 @@ typedef struct __mavlink_ping_t #define MAVLINK_MESSAGE_INFO_PING { \ "PING", \ 4, \ - { { "seq", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_ping_t, seq) }, \ - { "target_system", MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_ping_t, target_system) }, \ - { "target_component", MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_ping_t, target_component) }, \ - { "time", MAVLINK_TYPE_UINT64_T, 0, 6, offsetof(mavlink_ping_t, time) }, \ + { { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_ping_t, seq) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_ping_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_ping_t, target_component) }, \ + { "time", NULL, MAVLINK_TYPE_UINT64_T, 0, 6, offsetof(mavlink_ping_t, time) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_position_target.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_position_target.h index 42998e267d..4d9cdc4806 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_position_target.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_position_target.h @@ -18,10 +18,10 @@ typedef struct __mavlink_position_target_t #define MAVLINK_MESSAGE_INFO_POSITION_TARGET { \ "POSITION_TARGET", \ 4, \ - { { "x", MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_position_target_t, x) }, \ - { "y", MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_position_target_t, y) }, \ - { "z", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_position_target_t, z) }, \ - { "yaw", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_t, yaw) }, \ + { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_position_target_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_position_target_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_position_target_t, z) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_t, yaw) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_raw_imu.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_raw_imu.h index f31a232990..a3a3500fde 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_raw_imu.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_raw_imu.h @@ -24,16 +24,16 @@ typedef struct __mavlink_raw_imu_t #define MAVLINK_MESSAGE_INFO_RAW_IMU { \ "RAW_IMU", \ 10, \ - { { "usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_imu_t, usec) }, \ - { "xacc", MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_imu_t, xacc) }, \ - { "yacc", MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_imu_t, yacc) }, \ - { "zacc", MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_imu_t, zacc) }, \ - { "xgyro", MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_imu_t, xgyro) }, \ - { "ygyro", MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_raw_imu_t, ygyro) }, \ - { "zgyro", MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_raw_imu_t, zgyro) }, \ - { "xmag", MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_raw_imu_t, xmag) }, \ - { "ymag", MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_raw_imu_t, ymag) }, \ - { "zmag", MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_raw_imu_t, zmag) }, \ + { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_imu_t, usec) }, \ + { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_imu_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_imu_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_imu_t, zacc) }, \ + { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_imu_t, xgyro) }, \ + { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_raw_imu_t, ygyro) }, \ + { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_raw_imu_t, zgyro) }, \ + { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_raw_imu_t, xmag) }, \ + { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_raw_imu_t, ymag) }, \ + { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_raw_imu_t, zmag) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_raw_pressure.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_raw_pressure.h index 598e3c2059..b56d3e622e 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_raw_pressure.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_raw_pressure.h @@ -19,11 +19,11 @@ typedef struct __mavlink_raw_pressure_t #define MAVLINK_MESSAGE_INFO_RAW_PRESSURE { \ "RAW_PRESSURE", \ 5, \ - { { "usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_pressure_t, usec) }, \ - { "press_abs", MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_pressure_t, press_abs) }, \ - { "press_diff1", MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_pressure_t, press_diff1) }, \ - { "press_diff2", MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_pressure_t, press_diff2) }, \ - { "temperature", MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_pressure_t, temperature) }, \ + { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_pressure_t, usec) }, \ + { "press_abs", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_pressure_t, press_abs) }, \ + { "press_diff1", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_pressure_t, press_diff1) }, \ + { "press_diff2", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_pressure_t, press_diff2) }, \ + { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_pressure_t, temperature) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_rc_channels_override.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_rc_channels_override.h index f254ece156..d163158f7f 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_rc_channels_override.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_rc_channels_override.h @@ -24,16 +24,16 @@ typedef struct __mavlink_rc_channels_override_t #define MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE { \ "RC_CHANNELS_OVERRIDE", \ 10, \ - { { "target_system", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_rc_channels_override_t, target_system) }, \ - { "target_component", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_rc_channels_override_t, target_component) }, \ - { "chan1_raw", MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_rc_channels_override_t, chan1_raw) }, \ - { "chan2_raw", MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_override_t, chan2_raw) }, \ - { "chan3_raw", MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_override_t, chan3_raw) }, \ - { "chan4_raw", MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_override_t, chan4_raw) }, \ - { "chan5_raw", MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_override_t, chan5_raw) }, \ - { "chan6_raw", MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_override_t, chan6_raw) }, \ - { "chan7_raw", MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_override_t, chan7_raw) }, \ - { "chan8_raw", MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_override_t, chan8_raw) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_rc_channels_override_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_rc_channels_override_t, target_component) }, \ + { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_rc_channels_override_t, chan1_raw) }, \ + { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_override_t, chan2_raw) }, \ + { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_override_t, chan3_raw) }, \ + { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_override_t, chan4_raw) }, \ + { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_override_t, chan5_raw) }, \ + { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_override_t, chan6_raw) }, \ + { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_override_t, chan7_raw) }, \ + { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_override_t, chan8_raw) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_rc_channels_raw.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_rc_channels_raw.h index 461955b6f3..6df3485082 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_rc_channels_raw.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_rc_channels_raw.h @@ -23,15 +23,15 @@ typedef struct __mavlink_rc_channels_raw_t #define MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW { \ "RC_CHANNELS_RAW", \ 9, \ - { { "chan1_raw", MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_rc_channels_raw_t, chan1_raw) }, \ - { "chan2_raw", MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_rc_channels_raw_t, chan2_raw) }, \ - { "chan3_raw", MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_raw_t, chan3_raw) }, \ - { "chan4_raw", MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_raw_t, chan4_raw) }, \ - { "chan5_raw", MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_raw_t, chan5_raw) }, \ - { "chan6_raw", MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_raw_t, chan6_raw) }, \ - { "chan7_raw", MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_raw_t, chan7_raw) }, \ - { "chan8_raw", MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_raw_t, chan8_raw) }, \ - { "rssi", MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rc_channels_raw_t, rssi) }, \ + { { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_rc_channels_raw_t, chan1_raw) }, \ + { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_rc_channels_raw_t, chan2_raw) }, \ + { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_raw_t, chan3_raw) }, \ + { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_raw_t, chan4_raw) }, \ + { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_raw_t, chan5_raw) }, \ + { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_raw_t, chan6_raw) }, \ + { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_raw_t, chan7_raw) }, \ + { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_raw_t, chan8_raw) }, \ + { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rc_channels_raw_t, rssi) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_rc_channels_scaled.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_rc_channels_scaled.h index 042d0ae902..b178ad1731 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_rc_channels_scaled.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_rc_channels_scaled.h @@ -23,15 +23,15 @@ typedef struct __mavlink_rc_channels_scaled_t #define MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED { \ "RC_CHANNELS_SCALED", \ 9, \ - { { "chan1_scaled", MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_rc_channels_scaled_t, chan1_scaled) }, \ - { "chan2_scaled", MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_rc_channels_scaled_t, chan2_scaled) }, \ - { "chan3_scaled", MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_rc_channels_scaled_t, chan3_scaled) }, \ - { "chan4_scaled", MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_rc_channels_scaled_t, chan4_scaled) }, \ - { "chan5_scaled", MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_rc_channels_scaled_t, chan5_scaled) }, \ - { "chan6_scaled", MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_rc_channels_scaled_t, chan6_scaled) }, \ - { "chan7_scaled", MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_rc_channels_scaled_t, chan7_scaled) }, \ - { "chan8_scaled", MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_rc_channels_scaled_t, chan8_scaled) }, \ - { "rssi", MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rc_channels_scaled_t, rssi) }, \ + { { "chan1_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_rc_channels_scaled_t, chan1_scaled) }, \ + { "chan2_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_rc_channels_scaled_t, chan2_scaled) }, \ + { "chan3_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_rc_channels_scaled_t, chan3_scaled) }, \ + { "chan4_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_rc_channels_scaled_t, chan4_scaled) }, \ + { "chan5_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_rc_channels_scaled_t, chan5_scaled) }, \ + { "chan6_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_rc_channels_scaled_t, chan6_scaled) }, \ + { "chan7_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_rc_channels_scaled_t, chan7_scaled) }, \ + { "chan8_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_rc_channels_scaled_t, chan8_scaled) }, \ + { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rc_channels_scaled_t, rssi) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_request_data_stream.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_request_data_stream.h index 5cbd3d5efa..895897738c 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_request_data_stream.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_request_data_stream.h @@ -19,11 +19,11 @@ typedef struct __mavlink_request_data_stream_t #define MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM { \ "REQUEST_DATA_STREAM", \ 5, \ - { { "target_system", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_request_data_stream_t, target_system) }, \ - { "target_component", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_request_data_stream_t, target_component) }, \ - { "req_stream_id", MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_request_data_stream_t, req_stream_id) }, \ - { "req_message_rate", MAVLINK_TYPE_UINT16_T, 0, 3, offsetof(mavlink_request_data_stream_t, req_message_rate) }, \ - { "start_stop", MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_request_data_stream_t, start_stop) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_request_data_stream_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_request_data_stream_t, target_component) }, \ + { "req_stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_request_data_stream_t, req_stream_id) }, \ + { "req_message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 3, offsetof(mavlink_request_data_stream_t, req_message_rate) }, \ + { "start_stop", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_request_data_stream_t, start_stop) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h index 5ac8ebb087..4d0a87e2fd 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h @@ -19,11 +19,11 @@ typedef struct __mavlink_roll_pitch_yaw_speed_thrust_setpoint_t #define MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT { \ "ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT", \ 5, \ - { { "time_us", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, time_us) }, \ - { "roll_speed", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, roll_speed) }, \ - { "pitch_speed", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, pitch_speed) }, \ - { "yaw_speed", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, yaw_speed) }, \ - { "thrust", MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, thrust) }, \ + { { "time_us", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, time_us) }, \ + { "roll_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, roll_speed) }, \ + { "pitch_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, pitch_speed) }, \ + { "yaw_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, yaw_speed) }, \ + { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, thrust) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h index 5fbe945fa5..7de8441ab0 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h @@ -19,11 +19,11 @@ typedef struct __mavlink_roll_pitch_yaw_thrust_setpoint_t #define MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT { \ "ROLL_PITCH_YAW_THRUST_SETPOINT", \ 5, \ - { { "time_us", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, time_us) }, \ - { "roll", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, roll) }, \ - { "pitch", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, pitch) }, \ - { "yaw", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, yaw) }, \ - { "thrust", MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, thrust) }, \ + { { "time_us", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, time_us) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, yaw) }, \ + { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, thrust) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_safety_allowed_area.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_safety_allowed_area.h index 462f82f3e4..d76c204f7a 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_safety_allowed_area.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_safety_allowed_area.h @@ -21,13 +21,13 @@ typedef struct __mavlink_safety_allowed_area_t #define MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA { \ "SAFETY_ALLOWED_AREA", \ 7, \ - { { "frame", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_safety_allowed_area_t, frame) }, \ - { "p1x", MAVLINK_TYPE_FLOAT, 0, 1, offsetof(mavlink_safety_allowed_area_t, p1x) }, \ - { "p1y", MAVLINK_TYPE_FLOAT, 0, 5, offsetof(mavlink_safety_allowed_area_t, p1y) }, \ - { "p1z", MAVLINK_TYPE_FLOAT, 0, 9, offsetof(mavlink_safety_allowed_area_t, p1z) }, \ - { "p2x", MAVLINK_TYPE_FLOAT, 0, 13, offsetof(mavlink_safety_allowed_area_t, p2x) }, \ - { "p2y", MAVLINK_TYPE_FLOAT, 0, 17, offsetof(mavlink_safety_allowed_area_t, p2y) }, \ - { "p2z", MAVLINK_TYPE_FLOAT, 0, 21, offsetof(mavlink_safety_allowed_area_t, p2z) }, \ + { { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_safety_allowed_area_t, frame) }, \ + { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 1, offsetof(mavlink_safety_allowed_area_t, p1x) }, \ + { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 5, offsetof(mavlink_safety_allowed_area_t, p1y) }, \ + { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 9, offsetof(mavlink_safety_allowed_area_t, p1z) }, \ + { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 13, offsetof(mavlink_safety_allowed_area_t, p2x) }, \ + { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 17, offsetof(mavlink_safety_allowed_area_t, p2y) }, \ + { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 21, offsetof(mavlink_safety_allowed_area_t, p2z) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_safety_set_allowed_area.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_safety_set_allowed_area.h index b8b0bc66c8..8afdf6f133 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_safety_set_allowed_area.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_safety_set_allowed_area.h @@ -23,15 +23,15 @@ typedef struct __mavlink_safety_set_allowed_area_t #define MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA { \ "SAFETY_SET_ALLOWED_AREA", \ 9, \ - { { "target_system", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_safety_set_allowed_area_t, target_system) }, \ - { "target_component", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_safety_set_allowed_area_t, target_component) }, \ - { "frame", MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_safety_set_allowed_area_t, frame) }, \ - { "p1x", MAVLINK_TYPE_FLOAT, 0, 3, offsetof(mavlink_safety_set_allowed_area_t, p1x) }, \ - { "p1y", MAVLINK_TYPE_FLOAT, 0, 7, offsetof(mavlink_safety_set_allowed_area_t, p1y) }, \ - { "p1z", MAVLINK_TYPE_FLOAT, 0, 11, offsetof(mavlink_safety_set_allowed_area_t, p1z) }, \ - { "p2x", MAVLINK_TYPE_FLOAT, 0, 15, offsetof(mavlink_safety_set_allowed_area_t, p2x) }, \ - { "p2y", MAVLINK_TYPE_FLOAT, 0, 19, offsetof(mavlink_safety_set_allowed_area_t, p2y) }, \ - { "p2z", MAVLINK_TYPE_FLOAT, 0, 23, offsetof(mavlink_safety_set_allowed_area_t, p2z) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_safety_set_allowed_area_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_safety_set_allowed_area_t, target_component) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_safety_set_allowed_area_t, frame) }, \ + { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 3, offsetof(mavlink_safety_set_allowed_area_t, p1x) }, \ + { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 7, offsetof(mavlink_safety_set_allowed_area_t, p1y) }, \ + { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 11, offsetof(mavlink_safety_set_allowed_area_t, p1z) }, \ + { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 15, offsetof(mavlink_safety_set_allowed_area_t, p2x) }, \ + { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 19, offsetof(mavlink_safety_set_allowed_area_t, p2y) }, \ + { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 23, offsetof(mavlink_safety_set_allowed_area_t, p2z) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_scaled_imu.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_scaled_imu.h index 553bbc5383..7bec81d9d5 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_scaled_imu.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_scaled_imu.h @@ -24,16 +24,16 @@ typedef struct __mavlink_scaled_imu_t #define MAVLINK_MESSAGE_INFO_SCALED_IMU { \ "SCALED_IMU", \ 10, \ - { { "usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_scaled_imu_t, usec) }, \ - { "xacc", MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu_t, xacc) }, \ - { "yacc", MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu_t, yacc) }, \ - { "zacc", MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu_t, zacc) }, \ - { "xgyro", MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu_t, xgyro) }, \ - { "ygyro", MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu_t, ygyro) }, \ - { "zgyro", MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu_t, zgyro) }, \ - { "xmag", MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu_t, xmag) }, \ - { "ymag", MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_scaled_imu_t, ymag) }, \ - { "zmag", MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_scaled_imu_t, zmag) }, \ + { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_scaled_imu_t, usec) }, \ + { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu_t, zacc) }, \ + { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu_t, xgyro) }, \ + { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu_t, ygyro) }, \ + { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu_t, zgyro) }, \ + { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu_t, xmag) }, \ + { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_scaled_imu_t, ymag) }, \ + { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_scaled_imu_t, zmag) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_scaled_pressure.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_scaled_pressure.h index 273228ddc4..287c9a95b7 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_scaled_pressure.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_scaled_pressure.h @@ -18,10 +18,10 @@ typedef struct __mavlink_scaled_pressure_t #define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE { \ "SCALED_PRESSURE", \ 4, \ - { { "usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_scaled_pressure_t, usec) }, \ - { "press_abs", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure_t, press_abs) }, \ - { "press_diff", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_scaled_pressure_t, press_diff) }, \ - { "temperature", MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_pressure_t, temperature) }, \ + { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_scaled_pressure_t, usec) }, \ + { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure_t, press_abs) }, \ + { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_scaled_pressure_t, press_diff) }, \ + { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_pressure_t, temperature) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_servo_output_raw.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_servo_output_raw.h index 848b82b85d..3c2b52e906 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_servo_output_raw.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_servo_output_raw.h @@ -22,14 +22,14 @@ typedef struct __mavlink_servo_output_raw_t #define MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW { \ "SERVO_OUTPUT_RAW", \ 8, \ - { { "servo1_raw", MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_servo_output_raw_t, servo1_raw) }, \ - { "servo2_raw", MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_servo_output_raw_t, servo2_raw) }, \ - { "servo3_raw", MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_servo_output_raw_t, servo3_raw) }, \ - { "servo4_raw", MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_servo_output_raw_t, servo4_raw) }, \ - { "servo5_raw", MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_servo_output_raw_t, servo5_raw) }, \ - { "servo6_raw", MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_servo_output_raw_t, servo6_raw) }, \ - { "servo7_raw", MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_servo_output_raw_t, servo7_raw) }, \ - { "servo8_raw", MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_servo_output_raw_t, servo8_raw) }, \ + { { "servo1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_servo_output_raw_t, servo1_raw) }, \ + { "servo2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_servo_output_raw_t, servo2_raw) }, \ + { "servo3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_servo_output_raw_t, servo3_raw) }, \ + { "servo4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_servo_output_raw_t, servo4_raw) }, \ + { "servo5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_servo_output_raw_t, servo5_raw) }, \ + { "servo6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_servo_output_raw_t, servo6_raw) }, \ + { "servo7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_servo_output_raw_t, servo7_raw) }, \ + { "servo8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_servo_output_raw_t, servo8_raw) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_set_altitude.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_set_altitude.h index c49941bac4..14398bc53e 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_set_altitude.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_set_altitude.h @@ -16,8 +16,8 @@ typedef struct __mavlink_set_altitude_t #define MAVLINK_MESSAGE_INFO_SET_ALTITUDE { \ "SET_ALTITUDE", \ 2, \ - { { "target", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_altitude_t, target) }, \ - { "mode", MAVLINK_TYPE_UINT32_T, 0, 1, offsetof(mavlink_set_altitude_t, mode) }, \ + { { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_altitude_t, target) }, \ + { "mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 1, offsetof(mavlink_set_altitude_t, mode) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_set_mode.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_set_mode.h index 9836756d19..6630aea486 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_set_mode.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_set_mode.h @@ -16,8 +16,8 @@ typedef struct __mavlink_set_mode_t #define MAVLINK_MESSAGE_INFO_SET_MODE { \ "SET_MODE", \ 2, \ - { { "target", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_mode_t, target) }, \ - { "mode", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_set_mode_t, mode) }, \ + { { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_mode_t, target) }, \ + { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_set_mode_t, mode) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_set_nav_mode.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_set_nav_mode.h index c808b453d0..fafb6ec7e5 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_set_nav_mode.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_set_nav_mode.h @@ -16,8 +16,8 @@ typedef struct __mavlink_set_nav_mode_t #define MAVLINK_MESSAGE_INFO_SET_NAV_MODE { \ "SET_NAV_MODE", \ 2, \ - { { "target", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_nav_mode_t, target) }, \ - { "nav_mode", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_set_nav_mode_t, nav_mode) }, \ + { { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_nav_mode_t, target) }, \ + { "nav_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_set_nav_mode_t, nav_mode) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h index e8f2399750..d666d0cca6 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h @@ -20,12 +20,12 @@ typedef struct __mavlink_set_roll_pitch_yaw_speed_thrust_t #define MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST { \ "SET_ROLL_PITCH_YAW_SPEED_THRUST", \ 6, \ - { { "target_system", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, target_system) }, \ - { "target_component", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, target_component) }, \ - { "roll_speed", MAVLINK_TYPE_FLOAT, 0, 2, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, roll_speed) }, \ - { "pitch_speed", MAVLINK_TYPE_FLOAT, 0, 6, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, pitch_speed) }, \ - { "yaw_speed", MAVLINK_TYPE_FLOAT, 0, 10, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, yaw_speed) }, \ - { "thrust", MAVLINK_TYPE_FLOAT, 0, 14, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, thrust) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, target_component) }, \ + { "roll_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 2, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, roll_speed) }, \ + { "pitch_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 6, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, pitch_speed) }, \ + { "yaw_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 10, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, yaw_speed) }, \ + { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 14, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, thrust) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_set_roll_pitch_yaw_thrust.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_set_roll_pitch_yaw_thrust.h index 9ad4c32562..ad9425158e 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_set_roll_pitch_yaw_thrust.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_set_roll_pitch_yaw_thrust.h @@ -20,12 +20,12 @@ typedef struct __mavlink_set_roll_pitch_yaw_thrust_t #define MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST { \ "SET_ROLL_PITCH_YAW_THRUST", \ 6, \ - { { "target_system", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, target_system) }, \ - { "target_component", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, target_component) }, \ - { "roll", MAVLINK_TYPE_FLOAT, 0, 2, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, roll) }, \ - { "pitch", MAVLINK_TYPE_FLOAT, 0, 6, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, pitch) }, \ - { "yaw", MAVLINK_TYPE_FLOAT, 0, 10, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, yaw) }, \ - { "thrust", MAVLINK_TYPE_FLOAT, 0, 14, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, thrust) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, target_component) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 2, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 6, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 10, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, yaw) }, \ + { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 14, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, thrust) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_state_correction.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_state_correction.h index a06fac2444..9c9f6d9b89 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_state_correction.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_state_correction.h @@ -23,15 +23,15 @@ typedef struct __mavlink_state_correction_t #define MAVLINK_MESSAGE_INFO_STATE_CORRECTION { \ "STATE_CORRECTION", \ 9, \ - { { "xErr", MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_state_correction_t, xErr) }, \ - { "yErr", MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_state_correction_t, yErr) }, \ - { "zErr", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_state_correction_t, zErr) }, \ - { "rollErr", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_state_correction_t, rollErr) }, \ - { "pitchErr", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_state_correction_t, pitchErr) }, \ - { "yawErr", MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_state_correction_t, yawErr) }, \ - { "vxErr", MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_state_correction_t, vxErr) }, \ - { "vyErr", MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_state_correction_t, vyErr) }, \ - { "vzErr", MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_state_correction_t, vzErr) }, \ + { { "xErr", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_state_correction_t, xErr) }, \ + { "yErr", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_state_correction_t, yErr) }, \ + { "zErr", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_state_correction_t, zErr) }, \ + { "rollErr", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_state_correction_t, rollErr) }, \ + { "pitchErr", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_state_correction_t, pitchErr) }, \ + { "yawErr", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_state_correction_t, yawErr) }, \ + { "vxErr", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_state_correction_t, vxErr) }, \ + { "vyErr", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_state_correction_t, vyErr) }, \ + { "vzErr", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_state_correction_t, vzErr) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_statustext.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_statustext.h index d39f9b850a..1dbba58a8b 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_statustext.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_statustext.h @@ -16,8 +16,8 @@ typedef struct __mavlink_statustext_t #define MAVLINK_MESSAGE_INFO_STATUSTEXT { \ "STATUSTEXT", \ 2, \ - { { "severity", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_statustext_t, severity) }, \ - { "text", MAVLINK_TYPE_INT8_T, 50, 1, offsetof(mavlink_statustext_t, text) }, \ + { { "severity", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_statustext_t, severity) }, \ + { "text", NULL, MAVLINK_TYPE_INT8_T, 50, 1, offsetof(mavlink_statustext_t, text) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_sys_status.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_sys_status.h index 1113149fa4..9add0d069f 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_sys_status.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_sys_status.h @@ -21,13 +21,13 @@ typedef struct __mavlink_sys_status_t #define MAVLINK_MESSAGE_INFO_SYS_STATUS { \ "SYS_STATUS", \ 7, \ - { { "mode", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_sys_status_t, mode) }, \ - { "nav_mode", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_sys_status_t, nav_mode) }, \ - { "status", MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_sys_status_t, status) }, \ - { "load", MAVLINK_TYPE_UINT16_T, 0, 3, offsetof(mavlink_sys_status_t, load) }, \ - { "vbat", MAVLINK_TYPE_UINT16_T, 0, 5, offsetof(mavlink_sys_status_t, vbat) }, \ - { "battery_remaining", MAVLINK_TYPE_UINT16_T, 0, 7, offsetof(mavlink_sys_status_t, battery_remaining) }, \ - { "packet_drop", MAVLINK_TYPE_UINT16_T, 0, 9, offsetof(mavlink_sys_status_t, packet_drop) }, \ + { { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_sys_status_t, mode) }, \ + { "nav_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_sys_status_t, nav_mode) }, \ + { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_sys_status_t, status) }, \ + { "load", NULL, MAVLINK_TYPE_UINT16_T, 0, 3, offsetof(mavlink_sys_status_t, load) }, \ + { "vbat", NULL, MAVLINK_TYPE_UINT16_T, 0, 5, offsetof(mavlink_sys_status_t, vbat) }, \ + { "battery_remaining", NULL, MAVLINK_TYPE_UINT16_T, 0, 7, offsetof(mavlink_sys_status_t, battery_remaining) }, \ + { "packet_drop", NULL, MAVLINK_TYPE_UINT16_T, 0, 9, offsetof(mavlink_sys_status_t, packet_drop) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_system_time.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_system_time.h index 4473dff1cb..cf2b1f6fe9 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_system_time.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_system_time.h @@ -15,7 +15,7 @@ typedef struct __mavlink_system_time_t #define MAVLINK_MESSAGE_INFO_SYSTEM_TIME { \ "SYSTEM_TIME", \ 1, \ - { { "time_usec", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_system_time_t, time_usec) }, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_system_time_t, time_usec) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_system_time_utc.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_system_time_utc.h index 39a45237da..70ebf56389 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_system_time_utc.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_system_time_utc.h @@ -16,8 +16,8 @@ typedef struct __mavlink_system_time_utc_t #define MAVLINK_MESSAGE_INFO_SYSTEM_TIME_UTC { \ "SYSTEM_TIME_UTC", \ 2, \ - { { "utc_date", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_system_time_utc_t, utc_date) }, \ - { "utc_time", MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_system_time_utc_t, utc_time) }, \ + { { "utc_date", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_system_time_utc_t, utc_date) }, \ + { "utc_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_system_time_utc_t, utc_time) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_vfr_hud.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_vfr_hud.h index 064d3d0362..705d8d4db0 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_vfr_hud.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_vfr_hud.h @@ -20,12 +20,12 @@ typedef struct __mavlink_vfr_hud_t #define MAVLINK_MESSAGE_INFO_VFR_HUD { \ "VFR_HUD", \ 6, \ - { { "airspeed", MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_vfr_hud_t, airspeed) }, \ - { "groundspeed", MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_vfr_hud_t, groundspeed) }, \ - { "heading", MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_vfr_hud_t, heading) }, \ - { "throttle", MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_vfr_hud_t, throttle) }, \ - { "alt", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vfr_hud_t, alt) }, \ - { "climb", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vfr_hud_t, climb) }, \ + { { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_vfr_hud_t, airspeed) }, \ + { "groundspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_vfr_hud_t, groundspeed) }, \ + { "heading", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_vfr_hud_t, heading) }, \ + { "throttle", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_vfr_hud_t, throttle) }, \ + { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vfr_hud_t, alt) }, \ + { "climb", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vfr_hud_t, climb) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint.h index bce7018b25..27e89de1f7 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint.h @@ -28,20 +28,20 @@ typedef struct __mavlink_waypoint_t #define MAVLINK_MESSAGE_INFO_WAYPOINT { \ "WAYPOINT", \ 14, \ - { { "target_system", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_waypoint_t, target_system) }, \ - { "target_component", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_waypoint_t, target_component) }, \ - { "seq", MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_waypoint_t, seq) }, \ - { "frame", MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_waypoint_t, frame) }, \ - { "command", MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_waypoint_t, command) }, \ - { "current", MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_waypoint_t, current) }, \ - { "autocontinue", MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_waypoint_t, autocontinue) }, \ - { "param1", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_waypoint_t, param1) }, \ - { "param2", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_waypoint_t, param2) }, \ - { "param3", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_waypoint_t, param3) }, \ - { "param4", MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_waypoint_t, param4) }, \ - { "x", MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_waypoint_t, x) }, \ - { "y", MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_waypoint_t, y) }, \ - { "z", MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_waypoint_t, z) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_waypoint_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_waypoint_t, target_component) }, \ + { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_waypoint_t, seq) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_waypoint_t, frame) }, \ + { "command", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_waypoint_t, command) }, \ + { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_waypoint_t, current) }, \ + { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_waypoint_t, autocontinue) }, \ + { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_waypoint_t, param1) }, \ + { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_waypoint_t, param2) }, \ + { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_waypoint_t, param3) }, \ + { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_waypoint_t, param4) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_waypoint_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_waypoint_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_waypoint_t, z) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_ack.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_ack.h index 271d3d3c44..2b36087189 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_ack.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_ack.h @@ -17,9 +17,9 @@ typedef struct __mavlink_waypoint_ack_t #define MAVLINK_MESSAGE_INFO_WAYPOINT_ACK { \ "WAYPOINT_ACK", \ 3, \ - { { "target_system", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_waypoint_ack_t, target_system) }, \ - { "target_component", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_waypoint_ack_t, target_component) }, \ - { "type", MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_waypoint_ack_t, type) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_waypoint_ack_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_waypoint_ack_t, target_component) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_waypoint_ack_t, type) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_clear_all.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_clear_all.h index a25f608bed..bca8dcc1f4 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_clear_all.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_clear_all.h @@ -16,8 +16,8 @@ typedef struct __mavlink_waypoint_clear_all_t #define MAVLINK_MESSAGE_INFO_WAYPOINT_CLEAR_ALL { \ "WAYPOINT_CLEAR_ALL", \ 2, \ - { { "target_system", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_waypoint_clear_all_t, target_system) }, \ - { "target_component", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_waypoint_clear_all_t, target_component) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_waypoint_clear_all_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_waypoint_clear_all_t, target_component) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_count.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_count.h index 7fb6bfdcea..73c62f831d 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_count.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_count.h @@ -17,9 +17,9 @@ typedef struct __mavlink_waypoint_count_t #define MAVLINK_MESSAGE_INFO_WAYPOINT_COUNT { \ "WAYPOINT_COUNT", \ 3, \ - { { "target_system", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_waypoint_count_t, target_system) }, \ - { "target_component", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_waypoint_count_t, target_component) }, \ - { "count", MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_waypoint_count_t, count) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_waypoint_count_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_waypoint_count_t, target_component) }, \ + { "count", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_waypoint_count_t, count) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_current.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_current.h index 086a5f3462..411b867667 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_current.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_current.h @@ -15,7 +15,7 @@ typedef struct __mavlink_waypoint_current_t #define MAVLINK_MESSAGE_INFO_WAYPOINT_CURRENT { \ "WAYPOINT_CURRENT", \ 1, \ - { { "seq", MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_waypoint_current_t, seq) }, \ + { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_waypoint_current_t, seq) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_reached.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_reached.h index 515d32c12f..6f291c7095 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_reached.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_reached.h @@ -15,7 +15,7 @@ typedef struct __mavlink_waypoint_reached_t #define MAVLINK_MESSAGE_INFO_WAYPOINT_REACHED { \ "WAYPOINT_REACHED", \ 1, \ - { { "seq", MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_waypoint_reached_t, seq) }, \ + { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_waypoint_reached_t, seq) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_request.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_request.h index 9f16849f63..e9d616ab1d 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_request.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_request.h @@ -17,9 +17,9 @@ typedef struct __mavlink_waypoint_request_t #define MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST { \ "WAYPOINT_REQUEST", \ 3, \ - { { "target_system", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_waypoint_request_t, target_system) }, \ - { "target_component", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_waypoint_request_t, target_component) }, \ - { "seq", MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_waypoint_request_t, seq) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_waypoint_request_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_waypoint_request_t, target_component) }, \ + { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_waypoint_request_t, seq) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_request_list.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_request_list.h index 8ab2a578f1..caeb620375 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_request_list.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_request_list.h @@ -16,8 +16,8 @@ typedef struct __mavlink_waypoint_request_list_t #define MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST_LIST { \ "WAYPOINT_REQUEST_LIST", \ 2, \ - { { "target_system", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_waypoint_request_list_t, target_system) }, \ - { "target_component", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_waypoint_request_list_t, target_component) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_waypoint_request_list_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_waypoint_request_list_t, target_component) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_set_current.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_set_current.h index b75b6863d6..7a9fd614a4 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_set_current.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_set_current.h @@ -17,9 +17,9 @@ typedef struct __mavlink_waypoint_set_current_t #define MAVLINK_MESSAGE_INFO_WAYPOINT_SET_CURRENT { \ "WAYPOINT_SET_CURRENT", \ 3, \ - { { "target_system", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_waypoint_set_current_t, target_system) }, \ - { "target_component", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_waypoint_set_current_t, target_component) }, \ - { "seq", MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_waypoint_set_current_t, seq) }, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_waypoint_set_current_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_waypoint_set_current_t, target_component) }, \ + { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_waypoint_set_current_t, seq) }, \ } \ } diff --git a/libraries/GCS_MAVLink/include/common/version.h b/libraries/GCS_MAVLink/include/common/version.h index cda41b19cb..f563c9bd2f 100644 --- a/libraries/GCS_MAVLink/include/common/version.h +++ b/libraries/GCS_MAVLink/include/common/version.h @@ -5,9 +5,8 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Thu Sep 1 10:26:27 2011" +#define MAVLINK_BUILD_DATE "Sun Sep 4 18:16:41 2011" #define MAVLINK_WIRE_PROTOCOL_VERSION "0.9" - -#include "mavlink.h" - +#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101 + #endif // MAVLINK_VERSION_H diff --git a/libraries/GCS_MAVLink/include/mavlink_helpers.h b/libraries/GCS_MAVLink/include/mavlink_helpers.h index e43249121c..9f4f063780 100644 --- a/libraries/GCS_MAVLink/include/mavlink_helpers.h +++ b/libraries/GCS_MAVLink/include/mavlink_helpers.h @@ -214,7 +214,7 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa break; case MAVLINK_PARSE_STATE_GOT_STX: - if (status->msg_received) + if (status->msg_received || c > MAVLINK_MAX_PAYLOAD_LEN) { status->buffer_overrun++; status->parse_error++; diff --git a/libraries/GCS_MAVLink/include/mavlink_types.h b/libraries/GCS_MAVLink/include/mavlink_types.h index 54874e633e..9daeffc63f 100644 --- a/libraries/GCS_MAVLink/include/mavlink_types.h +++ b/libraries/GCS_MAVLink/include/mavlink_types.h @@ -167,7 +167,10 @@ enum MAVLINK_DATA_STREAM_TYPE MAVLINK_DATA_STREAM_IMG_PNG }; +#ifndef MAVLINK_MAX_PAYLOAD_LEN +// it is possible to override this, but be careful! #define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length +#endif #define MAVLINK_CORE_HEADER_LEN 5 ///< Length of core header (of the comm. layer): message length (1 byte) + message sequence (1 byte) + message system id (1 byte) + message component id (1 byte) + message type id (1 byte) #define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and checksum @@ -177,7 +180,7 @@ enum MAVLINK_DATA_STREAM_TYPE #define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length typedef struct param_union { - struct { + union { float param_float; int32_t param_int32; uint32_t param_uint32; @@ -223,6 +226,7 @@ typedef enum { typedef struct __mavlink_field_info { const char *name; // name of this field + const char *print_format; // printing format hint, or NULL mavlink_message_type_t type; // type of this field unsigned array_length; // if non-zero, field is an array unsigned wire_offset; // offset of each field in the payload