From 3020a471da6ae3a6cc543ad07989698ed432bfd2 Mon Sep 17 00:00:00 2001 From: "james.goppert" Date: Sat, 7 May 2011 20:49:13 +0000 Subject: [PATCH] Updated mavlink to latest roi branch. git-svn-id: https://arducopter.googlecode.com/svn/trunk@2187 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- .../include/ardupilotmega/ardupilotmega.h | 9 +- .../include/ardupilotmega/mavlink.h | 2 +- libraries/GCS_MAVLink/include/common/common.h | 23 ++- .../GCS_MAVLink/include/common/mavlink.h | 2 +- .../mavlink_msg_gps_set_global_origin.h | 52 +++--- .../include/common/mavlink_msg_raw_pressure.h | 102 +++++----- .../common/mavlink_msg_scaled_pressure.h | 174 ++++++++++++++++++ libraries/GCS_MAVLink/include/mavlink_types.h | 22 ++- .../GCS_MAVLink/include/pixhawk/mavlink.h | 2 +- .../GCS_MAVLink/include/pixhawk/pixhawk.h | 9 +- libraries/GCS_MAVLink/include/protocol.h | 149 +++++++++++---- libraries/GCS_MAVLink/include/slugs/mavlink.h | 2 +- .../include/slugs/mavlink_msg_air_data.h | 55 +++++- .../include/slugs/mavlink_msg_cpu_load.h | 55 +++++- .../include/slugs/mavlink_msg_ctrl_srfc_pt.h | 53 +++++- .../include/slugs/mavlink_msg_data_log.h | 73 +++++++- .../include/slugs/mavlink_msg_diagnostic.h | 73 ++++++-- .../include/slugs/mavlink_msg_gps_date_time.h | 78 +++++++- .../include/slugs/mavlink_msg_mid_lvl_cmds.h | 63 ++++++- .../include/slugs/mavlink_msg_sensor_bias.h | 73 ++++++-- .../include/slugs/mavlink_msg_slugs_action.h | 58 +++++- .../slugs/mavlink_msg_slugs_navigation.h | 88 +++++++-- libraries/GCS_MAVLink/include/slugs/slugs.h | 24 ++- .../GCS_MAVLink/include/ualberta/mavlink.h | 2 +- .../GCS_MAVLink/include/ualberta/ualberta.h | 9 +- .../message_definitions/common.xml | 64 +++++-- .../GCS_MAVLink/message_definitions/slugs.xml | 44 ----- libraries/GCS_MAVLink/sync | 6 +- 28 files changed, 1072 insertions(+), 294 deletions(-) create mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_scaled_pressure.h diff --git a/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h b/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h index 31697f2a0d..e002077c4f 100644 --- a/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h +++ b/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h @@ -1,7 +1,7 @@ /** @file * @brief MAVLink comm protocol. * @see http://pixhawk.ethz.ch/software/mavlink - * Generated on Tuesday, February 15 2011, 15:57 UTC + * Generated on Saturday, April 16 2011, 04:01 UTC */ #ifndef ARDUPILOTMEGA_H #define ARDUPILOTMEGA_H @@ -33,6 +33,13 @@ extern "C" { // MESSAGE DEFINITIONS + + +// MESSAGE LENGTHS + +#undef MAVLINK_MESSAGE_LENGTHS +#define MAVLINK_MESSAGE_LENGTHS { 3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 0, 0, 0, 0, 0, 5, 5, 26, 16, 36, 5, 6, 0, 0, 21, 0, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51 } + #ifdef __cplusplus } #endif diff --git a/libraries/GCS_MAVLink/include/ardupilotmega/mavlink.h b/libraries/GCS_MAVLink/include/ardupilotmega/mavlink.h index 2b50957a32..b9f073a07d 100644 --- a/libraries/GCS_MAVLink/include/ardupilotmega/mavlink.h +++ b/libraries/GCS_MAVLink/include/ardupilotmega/mavlink.h @@ -1,7 +1,7 @@ /** @file * @brief MAVLink comm protocol. * @see http://pixhawk.ethz.ch/software/mavlink - * Generated on Tuesday, February 15 2011, 15:57 UTC + * Generated on Saturday, April 16 2011, 04:01 UTC */ #ifndef MAVLINK_H #define MAVLINK_H diff --git a/libraries/GCS_MAVLink/include/common/common.h b/libraries/GCS_MAVLink/include/common/common.h index eafeec6217..833ffabc57 100644 --- a/libraries/GCS_MAVLink/include/common/common.h +++ b/libraries/GCS_MAVLink/include/common/common.h @@ -1,7 +1,7 @@ /** @file * @brief MAVLink comm protocol. * @see http://pixhawk.ethz.ch/software/mavlink - * Generated on Tuesday, March 15 2011, 19:25 UTC + * Generated on Saturday, May 7 2011, 19:14 UTC */ #ifndef COMMON_H #define COMMON_H @@ -38,7 +38,6 @@ enum MAV_CMD MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch locationEmptyEmptyEmptyEmptyEmptyEmptyEmpty*/ MAV_CMD_NAV_LAND=21, /* Land at locationEmptyEmptyEmptyDesired yaw angle.LatitudeLongitudeAltitude*/ MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / handMinimum pitch (if airspeed sensor present), desired pitch without sensorEmptyEmptyYaw angle (if magnetometer present), ignored without magnetometerLatitudeLongitudeAltitude*/ - MAV_CMD_NAV_ORIENTATION_TARGET=80, /* Set the location the system should be heading towards (camera heads or rotary wing aircraft).EmptyEmptyEmptyEmptyLatitudeLongitudeAltitude*/ MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV.0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy gridEmptyYaw angle at goal, in compass degrees, [0..360]Latitude/X of goalLongitude/Y of goalAltitude/Z of goal*/ MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumerationEmptyEmptyEmptyEmptyEmptyEmptyEmpty*/ MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine.Delay in seconds (decimal)EmptyEmptyEmptyEmptyEmptyEmpty*/ @@ -56,6 +55,7 @@ enum MAV_CMD MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value.Servo numberPWM (microseconds, 1000 to 2000 typical)EmptyEmptyEmptyEmptyEmpty*/ MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.Servo numberPWM (microseconds, 1000 to 2000 typical)Cycle countCycle time (seconds)EmptyEmptyEmpty*/ MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system.Camera ID (-1 for all)Transmission: 0: disabled, 1: enabled compressed, 2: enabled rawTransmission mode: 0: video stream, >0: single images every n seconds (decimal)Recording: 0: disabled, 1: enabled compressed, 2: enabled rawEmptyEmptyEmpty*/ + MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various devices such as cameras.Region of interest mode. (see MAV_ROI enum)Waypoint index/ target ID. (see MAV_ROI enum)ROI index (allows a vehicle to manage multiple cameras etc.)Emptyx the location of the fixed ROI (see MAV_FRAME)yz*/ MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumerationEmptyEmptyEmptyEmptyEmptyEmptyEmpty*/ MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode.Gyro calibration: 0: no, 1: yesMagnetometer calibration: 0: no, 1: yesGround pressure: 0: no, 1: yesRadio calibration: 0: no, 1: yesEmptyEmptyEmpty*/ MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROMMission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROMReservedReservedEmptyEmptyEmpty*/ @@ -77,6 +77,17 @@ enum MAV_DATA_STREAM MAV_DATA_STREAM_ENUM_END }; +/** @brief The ROI (region of interest) for the vehicle. This can be be used by the vehicle for camera/vehicle attitude alignment (see MAV_CMD_DO_SET_ROI). */ +enum MAV_ROI +{ + MAV_ROI_NONE=0, /* No region of interest.*/ + MAV_ROI_WPNEXT=1, /* Point toward next waypoint.*/ + MAV_ROI_WPINDEX=2, /* Point toward given waypoint.*/ + MAV_ROI_LOCATION=3, /* Point toward fixed location.*/ + MAV_ROI_TARGET=4, /* Point toward target of given id.*/ + MAV_ROI_ENUM_END +}; + // MESSAGE DEFINITIONS @@ -101,6 +112,7 @@ enum MAV_DATA_STREAM #include "./mavlink_msg_gps_status.h" #include "./mavlink_msg_raw_imu.h" #include "./mavlink_msg_raw_pressure.h" +#include "./mavlink_msg_scaled_pressure.h" #include "./mavlink_msg_attitude.h" #include "./mavlink_msg_local_position.h" #include "./mavlink_msg_global_position.h" @@ -142,6 +154,13 @@ enum MAV_DATA_STREAM #include "./mavlink_msg_named_value_int.h" #include "./mavlink_msg_statustext.h" #include "./mavlink_msg_debug.h" + + +// MESSAGE LENGTHS + +#undef MAVLINK_MESSAGE_LENGTHS +#define MAVLINK_MESSAGE_LENGTHS { 3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 0, 0, 0, 0, 0, 5, 5, 26, 16, 36, 5, 6, 0, 0, 21, 0, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51 } + #ifdef __cplusplus } #endif diff --git a/libraries/GCS_MAVLink/include/common/mavlink.h b/libraries/GCS_MAVLink/include/common/mavlink.h index a5190a92c8..10256851f2 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink.h +++ b/libraries/GCS_MAVLink/include/common/mavlink.h @@ -1,7 +1,7 @@ /** @file * @brief MAVLink comm protocol. * @see http://pixhawk.ethz.ch/software/mavlink - * Generated on Tuesday, March 15 2011, 19:25 UTC + * Generated on Saturday, May 7 2011, 19:14 UTC */ #ifndef MAVLINK_H #define MAVLINK_H 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 a4b485222c..47ddc2e23b 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 @@ -6,9 +6,9 @@ typedef struct __mavlink_gps_set_global_origin_t { uint8_t target_system; ///< System ID uint8_t target_component; ///< Component ID - uint32_t latitude; ///< global position * 1E7 - uint32_t longitude; ///< global position * 1E7 - uint32_t altitude; ///< global position * 1000 + int32_t latitude; ///< global position * 1E7 + int32_t longitude; ///< global position * 1E7 + int32_t altitude; ///< global position * 1000 } mavlink_gps_set_global_origin_t; @@ -27,16 +27,16 @@ typedef struct __mavlink_gps_set_global_origin_t * @param altitude global position * 1000 * @return length of the message in bytes (excluding serial stream start sign) */ -static inline uint16_t mavlink_msg_gps_set_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint32_t latitude, uint32_t longitude, uint32_t altitude) +static inline uint16_t mavlink_msg_gps_set_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, int32_t latitude, int32_t longitude, int32_t altitude) { uint16_t i = 0; msg->msgid = MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN; i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID - i += put_uint32_t_by_index(latitude, i, msg->payload); // global position * 1E7 - i += put_uint32_t_by_index(longitude, i, msg->payload); // global position * 1E7 - i += put_uint32_t_by_index(altitude, i, msg->payload); // global position * 1000 + i += put_int32_t_by_index(latitude, i, msg->payload); // global position * 1E7 + i += put_int32_t_by_index(longitude, i, msg->payload); // global position * 1E7 + i += put_int32_t_by_index(altitude, i, msg->payload); // global position * 1000 return mavlink_finalize_message(msg, system_id, component_id, i); } @@ -54,16 +54,16 @@ static inline uint16_t mavlink_msg_gps_set_global_origin_pack(uint8_t system_id, * @param altitude global position * 1000 * @return length of the message in bytes (excluding serial stream start sign) */ -static inline uint16_t mavlink_msg_gps_set_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint32_t latitude, uint32_t longitude, uint32_t altitude) +static inline uint16_t mavlink_msg_gps_set_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, int32_t latitude, int32_t longitude, int32_t altitude) { uint16_t i = 0; msg->msgid = MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN; i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID - i += put_uint32_t_by_index(latitude, i, msg->payload); // global position * 1E7 - i += put_uint32_t_by_index(longitude, i, msg->payload); // global position * 1E7 - i += put_uint32_t_by_index(altitude, i, msg->payload); // global position * 1000 + i += put_int32_t_by_index(latitude, i, msg->payload); // global position * 1E7 + i += put_int32_t_by_index(longitude, i, msg->payload); // global position * 1E7 + i += put_int32_t_by_index(altitude, i, msg->payload); // global position * 1000 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); } @@ -93,7 +93,7 @@ static inline uint16_t mavlink_msg_gps_set_global_origin_encode(uint8_t system_i */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -static inline void mavlink_msg_gps_set_global_origin_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t latitude, uint32_t longitude, uint32_t altitude) +static inline void mavlink_msg_gps_set_global_origin_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t latitude, int32_t longitude, int32_t altitude) { mavlink_message_t msg; mavlink_msg_gps_set_global_origin_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, latitude, longitude, altitude); @@ -128,14 +128,14 @@ static inline uint8_t mavlink_msg_gps_set_global_origin_get_target_component(con * * @return global position * 1E7 */ -static inline uint32_t mavlink_msg_gps_set_global_origin_get_latitude(const mavlink_message_t* msg) +static inline int32_t mavlink_msg_gps_set_global_origin_get_latitude(const mavlink_message_t* msg) { generic_32bit r; r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1]; r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[2]; r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[3]; - return (uint32_t)r.i; + return (int32_t)r.i; } /** @@ -143,14 +143,14 @@ static inline uint32_t mavlink_msg_gps_set_global_origin_get_latitude(const mavl * * @return global position * 1E7 */ -static inline uint32_t mavlink_msg_gps_set_global_origin_get_longitude(const mavlink_message_t* msg) +static inline int32_t mavlink_msg_gps_set_global_origin_get_longitude(const mavlink_message_t* msg) { generic_32bit r; - r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t))[0]; - r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t))[1]; - r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t))[2]; - r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t))[3]; - return (uint32_t)r.i; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t))[3]; + return (int32_t)r.i; } /** @@ -158,14 +158,14 @@ static inline uint32_t mavlink_msg_gps_set_global_origin_get_longitude(const mav * * @return global position * 1000 */ -static inline uint32_t mavlink_msg_gps_set_global_origin_get_altitude(const mavlink_message_t* msg) +static inline int32_t mavlink_msg_gps_set_global_origin_get_altitude(const mavlink_message_t* msg) { generic_32bit r; - r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t))[0]; - r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t))[1]; - r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t))[2]; - r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t))[3]; - return (uint32_t)r.i; + r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[0]; + r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[1]; + r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[2]; + r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(int32_t)+sizeof(int32_t))[3]; + return (int32_t)r.i; } /** 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 735ee8ada8..8346ac6286 100644 --- a/libraries/GCS_MAVLink/include/common/mavlink_msg_raw_pressure.h +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_raw_pressure.h @@ -5,10 +5,10 @@ typedef struct __mavlink_raw_pressure_t { uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - float press_abs; ///< Absolute pressure (hectopascal) - float press_diff1; ///< Differential pressure 1 (hectopascal) - float press_diff2; ///< Differential pressure 2 (hectopascal) - int16_t temperature; ///< Raw Temperature measurement (0.01 degrees celsius per tick is default unit) + int16_t press_abs; ///< Absolute pressure (raw) + int16_t press_diff1; ///< Differential pressure 1 (raw) + int16_t press_diff2; ///< Differential pressure 2 (raw) + int16_t temperature; ///< Raw Temperature measurement (raw) } mavlink_raw_pressure_t; @@ -21,22 +21,22 @@ typedef struct __mavlink_raw_pressure_t * @param msg The MAVLink message to compress the data into * * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff1 Differential pressure 1 (hectopascal) - * @param press_diff2 Differential pressure 2 (hectopascal) - * @param temperature Raw Temperature measurement (0.01 degrees celsius per tick is default unit) + * @param press_abs Absolute pressure (raw) + * @param press_diff1 Differential pressure 1 (raw) + * @param press_diff2 Differential pressure 2 (raw) + * @param temperature Raw Temperature measurement (raw) * @return length of the message in bytes (excluding serial stream start sign) */ -static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float press_abs, float press_diff1, float press_diff2, int16_t temperature) +static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature) { uint16_t i = 0; msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE; i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot) - i += put_float_by_index(press_abs, i, msg->payload); // Absolute pressure (hectopascal) - i += put_float_by_index(press_diff1, i, msg->payload); // Differential pressure 1 (hectopascal) - i += put_float_by_index(press_diff2, i, msg->payload); // Differential pressure 2 (hectopascal) - i += put_int16_t_by_index(temperature, i, msg->payload); // Raw Temperature measurement (0.01 degrees celsius per tick is default unit) + i += put_int16_t_by_index(press_abs, i, msg->payload); // Absolute pressure (raw) + i += put_int16_t_by_index(press_diff1, i, msg->payload); // Differential pressure 1 (raw) + i += put_int16_t_by_index(press_diff2, i, msg->payload); // Differential pressure 2 (raw) + i += put_int16_t_by_index(temperature, i, msg->payload); // Raw Temperature measurement (raw) return mavlink_finalize_message(msg, system_id, component_id, i); } @@ -48,22 +48,22 @@ static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t * @param chan The MAVLink channel this message was sent over * @param msg The MAVLink message to compress the data into * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff1 Differential pressure 1 (hectopascal) - * @param press_diff2 Differential pressure 2 (hectopascal) - * @param temperature Raw Temperature measurement (0.01 degrees celsius per tick is default unit) + * @param press_abs Absolute pressure (raw) + * @param press_diff1 Differential pressure 1 (raw) + * @param press_diff2 Differential pressure 2 (raw) + * @param temperature Raw Temperature measurement (raw) * @return length of the message in bytes (excluding serial stream start sign) */ -static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float press_abs, float press_diff1, float press_diff2, int16_t temperature) +static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature) { uint16_t i = 0; msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE; i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot) - i += put_float_by_index(press_abs, i, msg->payload); // Absolute pressure (hectopascal) - i += put_float_by_index(press_diff1, i, msg->payload); // Differential pressure 1 (hectopascal) - i += put_float_by_index(press_diff2, i, msg->payload); // Differential pressure 2 (hectopascal) - i += put_int16_t_by_index(temperature, i, msg->payload); // Raw Temperature measurement (0.01 degrees celsius per tick is default unit) + i += put_int16_t_by_index(press_abs, i, msg->payload); // Absolute pressure (raw) + i += put_int16_t_by_index(press_diff1, i, msg->payload); // Differential pressure 1 (raw) + i += put_int16_t_by_index(press_diff2, i, msg->payload); // Differential pressure 2 (raw) + i += put_int16_t_by_index(temperature, i, msg->payload); // Raw Temperature measurement (raw) return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); } @@ -86,14 +86,14 @@ static inline uint16_t mavlink_msg_raw_pressure_encode(uint8_t system_id, uint8_ * @param chan MAVLink channel to send the message * * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff1 Differential pressure 1 (hectopascal) - * @param press_diff2 Differential pressure 2 (hectopascal) - * @param temperature Raw Temperature measurement (0.01 degrees celsius per tick is default unit) + * @param press_abs Absolute pressure (raw) + * @param press_diff1 Differential pressure 1 (raw) + * @param press_diff2 Differential pressure 2 (raw) + * @param temperature Raw Temperature measurement (raw) */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -static inline void mavlink_msg_raw_pressure_send(mavlink_channel_t chan, uint64_t usec, float press_abs, float press_diff1, float press_diff2, int16_t temperature) +static inline void mavlink_msg_raw_pressure_send(mavlink_channel_t chan, uint64_t usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature) { mavlink_message_t msg; mavlink_msg_raw_pressure_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, press_abs, press_diff1, press_diff2, temperature); @@ -125,58 +125,52 @@ static inline uint64_t mavlink_msg_raw_pressure_get_usec(const mavlink_message_t /** * @brief Get field press_abs from raw_pressure message * - * @return Absolute pressure (hectopascal) + * @return Absolute pressure (raw) */ -static inline float mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg) +static inline int16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg) { - generic_32bit r; - r.b[3] = (msg->payload+sizeof(uint64_t))[0]; - r.b[2] = (msg->payload+sizeof(uint64_t))[1]; - r.b[1] = (msg->payload+sizeof(uint64_t))[2]; - r.b[0] = (msg->payload+sizeof(uint64_t))[3]; - return (float)r.f; + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t))[0]; + r.b[0] = (msg->payload+sizeof(uint64_t))[1]; + return (int16_t)r.s; } /** * @brief Get field press_diff1 from raw_pressure message * - * @return Differential pressure 1 (hectopascal) + * @return Differential pressure 1 (raw) */ -static inline float mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t* msg) +static inline int16_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t* msg) { - generic_32bit r; - r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0]; - r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1]; - r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2]; - r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3]; - return (float)r.f; + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; } /** * @brief Get field press_diff2 from raw_pressure message * - * @return Differential pressure 2 (hectopascal) + * @return Differential pressure 2 (raw) */ -static inline float mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t* msg) +static inline int16_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t* msg) { - generic_32bit r; - r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0]; - r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1]; - r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2]; - r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3]; - return (float)r.f; + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t))[1]; + return (int16_t)r.s; } /** * @brief Get field temperature from raw_pressure message * - * @return Raw Temperature measurement (0.01 degrees celsius per tick is default unit) + * @return Raw Temperature measurement (raw) */ static inline int16_t mavlink_msg_raw_pressure_get_temperature(const mavlink_message_t* msg) { generic_16bit r; - r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; - r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1]; return (int16_t)r.s; } diff --git a/libraries/GCS_MAVLink/include/common/mavlink_msg_scaled_pressure.h b/libraries/GCS_MAVLink/include/common/mavlink_msg_scaled_pressure.h new file mode 100644 index 0000000000..08a9bedd37 --- /dev/null +++ b/libraries/GCS_MAVLink/include/common/mavlink_msg_scaled_pressure.h @@ -0,0 +1,174 @@ +// MESSAGE SCALED_PRESSURE PACKING + +#define MAVLINK_MSG_ID_SCALED_PRESSURE 38 + +typedef struct __mavlink_scaled_pressure_t +{ + uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) + float press_abs; ///< Absolute pressure (hectopascal) + float press_diff; ///< Differential pressure 1 (hectopascal) + int16_t temperature; ///< Temperature measurement (0.01 degrees celsius) + +} mavlink_scaled_pressure_t; + + + +/** + * @brief Pack a scaled_pressure message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float press_abs, float press_diff, int16_t temperature) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE; + + i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot) + i += put_float_by_index(press_abs, i, msg->payload); // Absolute pressure (hectopascal) + i += put_float_by_index(press_diff, i, msg->payload); // Differential pressure 1 (hectopascal) + i += put_int16_t_by_index(temperature, i, msg->payload); // Temperature measurement (0.01 degrees celsius) + + return mavlink_finalize_message(msg, system_id, component_id, i); +} + +/** + * @brief Pack a scaled_pressure message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float press_abs, float press_diff, int16_t temperature) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE; + + i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot) + i += put_float_by_index(press_abs, i, msg->payload); // Absolute pressure (hectopascal) + i += put_float_by_index(press_diff, i, msg->payload); // Differential pressure 1 (hectopascal) + i += put_int16_t_by_index(temperature, i, msg->payload); // Temperature measurement (0.01 degrees celsius) + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a scaled_pressure struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param scaled_pressure C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_pressure_t* scaled_pressure) +{ + return mavlink_msg_scaled_pressure_pack(system_id, component_id, msg, scaled_pressure->usec, scaled_pressure->press_abs, scaled_pressure->press_diff, scaled_pressure->temperature); +} + +/** + * @brief Send a scaled_pressure message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_scaled_pressure_send(mavlink_channel_t chan, uint64_t usec, float press_abs, float press_diff, int16_t temperature) +{ + mavlink_message_t msg; + mavlink_msg_scaled_pressure_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, press_abs, press_diff, temperature); + mavlink_send_uart(chan, &msg); +} + +#endif +// MESSAGE SCALED_PRESSURE UNPACKING + +/** + * @brief Get field usec from scaled_pressure message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_scaled_pressure_get_usec(const mavlink_message_t* msg) +{ + generic_64bit r; + r.b[7] = (msg->payload)[0]; + r.b[6] = (msg->payload)[1]; + r.b[5] = (msg->payload)[2]; + r.b[4] = (msg->payload)[3]; + r.b[3] = (msg->payload)[4]; + r.b[2] = (msg->payload)[5]; + r.b[1] = (msg->payload)[6]; + r.b[0] = (msg->payload)[7]; + return (uint64_t)r.ll; +} + +/** + * @brief Get field press_abs from scaled_pressure message + * + * @return Absolute pressure (hectopascal) + */ +static inline float mavlink_msg_scaled_pressure_get_press_abs(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t))[3]; + return (float)r.f; +} + +/** + * @brief Get field press_diff from scaled_pressure message + * + * @return Differential pressure 1 (hectopascal) + */ +static inline float mavlink_msg_scaled_pressure_get_press_diff(const mavlink_message_t* msg) +{ + generic_32bit r; + r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0]; + r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1]; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3]; + return (float)r.f; +} + +/** + * @brief Get field temperature from scaled_pressure message + * + * @return Temperature measurement (0.01 degrees celsius) + */ +static inline int16_t mavlink_msg_scaled_pressure_get_temperature(const mavlink_message_t* msg) +{ + generic_16bit r; + r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0]; + r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1]; + return (int16_t)r.s; +} + +/** + * @brief Decode a scaled_pressure message into a struct + * + * @param msg The message to decode + * @param scaled_pressure C-struct to decode the message contents into + */ +static inline void mavlink_msg_scaled_pressure_decode(const mavlink_message_t* msg, mavlink_scaled_pressure_t* scaled_pressure) +{ + scaled_pressure->usec = mavlink_msg_scaled_pressure_get_usec(msg); + scaled_pressure->press_abs = mavlink_msg_scaled_pressure_get_press_abs(msg); + scaled_pressure->press_diff = mavlink_msg_scaled_pressure_get_press_diff(msg); + scaled_pressure->temperature = mavlink_msg_scaled_pressure_get_temperature(msg); +} diff --git a/libraries/GCS_MAVLink/include/mavlink_types.h b/libraries/GCS_MAVLink/include/mavlink_types.h index 609cb7071f..2eff48ef8f 100644 --- a/libraries/GCS_MAVLink/include/mavlink_types.h +++ b/libraries/GCS_MAVLink/include/mavlink_types.h @@ -59,6 +59,8 @@ enum MAV_ACTION MAV_ACTION_CHANGE_MODE = 38, MAV_ACTION_LOITER_MAX_TURNS = 39, MAV_ACTION_LOITER_MAX_TIME = 40, + MAV_ACTION_START_HILSIM = 41, + MAV_ACTION_STOP_HILSIM = 42, MAV_ACTION_NB ///< Number of MAV actions }; @@ -85,6 +87,7 @@ enum MAV_STATE MAV_STATE_ACTIVE, MAV_STATE_CRITICAL, MAV_STATE_EMERGENCY, + MAV_STATE_HILSIM, MAV_STATE_POWEROFF }; @@ -179,10 +182,21 @@ typedef enum { MAVLINK_COMM_0, MAVLINK_COMM_1, MAVLINK_COMM_2, - MAVLINK_COMM_3, - MAVLINK_COMM_NB, - MAVLINK_COMM_NB_HIGH = 16 - } mavlink_channel_t; + MAVLINK_COMM_3 +} mavlink_channel_t; + +/* + * applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number + * of buffers they will use. If more are used, then the result will be + * a stack overrun + */ +#ifndef MAVLINK_COMM_NUM_BUFFERS +#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32) +# define MAVLINK_COMM_NUM_BUFFERS 16 +#else +# define MAVLINK_COMM_NUM_BUFFERS 4 +#endif +#endif typedef enum { MAVLINK_PARSE_STATE_UNINIT=0, diff --git a/libraries/GCS_MAVLink/include/pixhawk/mavlink.h b/libraries/GCS_MAVLink/include/pixhawk/mavlink.h index 8a2c65c080..6a5785af15 100644 --- a/libraries/GCS_MAVLink/include/pixhawk/mavlink.h +++ b/libraries/GCS_MAVLink/include/pixhawk/mavlink.h @@ -1,7 +1,7 @@ /** @file * @brief MAVLink comm protocol. * @see http://pixhawk.ethz.ch/software/mavlink - * Generated on Wednesday, March 2 2011, 13:12 UTC + * Generated on Saturday, April 16 2011, 04:02 UTC */ #ifndef MAVLINK_H #define MAVLINK_H diff --git a/libraries/GCS_MAVLink/include/pixhawk/pixhawk.h b/libraries/GCS_MAVLink/include/pixhawk/pixhawk.h index 7436b922c5..08f466fd2d 100644 --- a/libraries/GCS_MAVLink/include/pixhawk/pixhawk.h +++ b/libraries/GCS_MAVLink/include/pixhawk/pixhawk.h @@ -1,7 +1,7 @@ /** @file * @brief MAVLink comm protocol. * @see http://pixhawk.ethz.ch/software/mavlink - * Generated on Wednesday, March 2 2011, 13:12 UTC + * Generated on Saturday, April 16 2011, 04:02 UTC */ #ifndef PIXHAWK_H #define PIXHAWK_H @@ -74,6 +74,13 @@ enum DATA_TYPES #include "./mavlink_msg_data_transmission_handshake.h" #include "./mavlink_msg_encapsulated_data.h" #include "./mavlink_msg_brief_feature.h" + + +// MESSAGE LENGTHS + +#undef MAVLINK_MESSAGE_LENGTHS +#define MAVLINK_MESSAGE_LENGTHS { 3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 0, 0, 0, 0, 0, 5, 5, 26, 16, 36, 5, 6, 0, 0, 21, 0, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 11, 40, 1, 80, 0, 0, 0, 0, 0, 0, 0, 32, 32, 0, 0, 0, 0, 0, 0, 0, 20, 18, 0, 0, 0, 0, 0, 0, 0, 0, 26, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 12, 0, 0, 0, 0, 0, 0, 0, 4, 255, 12, 6, 18, 0, 0, 0, 0, 0, 106, 42, 54, 0, 0, 0, 0, 0, 0, 0, 8, 255, 53, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51 } + #ifdef __cplusplus } #endif diff --git a/libraries/GCS_MAVLink/include/protocol.h b/libraries/GCS_MAVLink/include/protocol.h index 09409fcd4f..ed1f9546b4 100644 --- a/libraries/GCS_MAVLink/include/protocol.h +++ b/libraries/GCS_MAVLink/include/protocol.h @@ -34,12 +34,7 @@ static void mavlink_parse_state_initialize(mavlink_status_t* initStatus) static inline mavlink_status_t* mavlink_get_channel_status(uint8_t chan) { -#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32) - static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NB_HIGH]; -#else - static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NB]; -#endif - + static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS]; return &m_mavlink_status[chan]; } @@ -73,7 +68,7 @@ static inline uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t msg->compid = component_id; // One sequence number per component msg->seq = mavlink_get_channel_status(MAVLINK_COMM_0)->current_tx_seq; - mavlink_get_channel_status(MAVLINK_COMM_0)->current_tx_seq = mavlink_get_channel_status(MAVLINK_COMM_0)->current_tx_seq+1; + mavlink_get_channel_status(MAVLINK_COMM_0)->current_tx_seq = mavlink_get_channel_status(MAVLINK_COMM_0)->current_tx_seq+1; checksum = crc_calculate((uint8_t*)((void*)msg), length + MAVLINK_CORE_HEADER_LEN); msg->ck_a = (uint8_t)(checksum & 0xFF); ///< High byte msg->ck_b = (uint8_t)(checksum >> 8); ///< Low byte @@ -202,11 +197,8 @@ static inline void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c) */ static inline uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) { -#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32) - static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NB_HIGH]; -#else - static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NB]; -#endif + static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NUM_BUFFERS]; + // Initializes only once, values keep unchanged after first initialization mavlink_parse_state_initialize(mavlink_get_channel_status(chan)); @@ -391,23 +383,13 @@ static inline uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messag /* static inline uint8_t mavlink_parse_char_new(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) { - #if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32) - static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NB_HIGH]; - static uint8_t m_msgbuf[MAVLINK_COMM_NB_HIGH][MAVLINK_MAX_PACKET_LEN * 2]; - static uint8_t m_msgbuf_index[MAVLINK_COMM_NB_HIGH]; - static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NB_HIGH]; - static uint8_t m_packet_start[MAVLINK_COMM_NB_HIGH][MAVLINK_PACKET_START_CANDIDATES]; - static uint8_t m_packet_start_index_read[MAVLINK_COMM_NB_HIGH]; - static uint8_t m_packet_start_index_write[MAVLINK_COMM_NB_HIGH]; - #else - static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NB]; - static uint8_t m_msgbuf[MAVLINK_COMM_NB][MAVLINK_MAX_PACKET_LEN * 2]; - static uint8_t m_msgbuf_index[MAVLINK_COMM_NB]; - static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NB]; - static uint8_t m_packet_start[MAVLINK_COMM_NB][MAVLINK_PACKET_START_CANDIDATES]; - static uint8_t m_packet_start_index_read[MAVLINK_COMM_NB]; - static uint8_t m_packet_start_index_write[MAVLINK_COMM_NB]; - #endif + static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS]; + static uint8_t m_msgbuf[MAVLINK_COMM_NUM_BUFFERS][MAVLINK_MAX_PACKET_LEN * 2]; + static uint8_t m_msgbuf_index[MAVLINK_COMM_NUM_BUFFERS]; + static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NUM_BUFFERS]; + static uint8_t m_packet_start[MAVLINK_COMM_NUM_BUFFERS][MAVLINK_PACKET_START_CANDIDATES]; + static uint8_t m_packet_start_index_read[MAVLINK_COMM_NUM_BUFFERS]; + static uint8_t m_packet_start_index_write[MAVLINK_COMM_NUM_BUFFERS]; // Set a packet start candidate index if sign is start sign if (c == MAVLINK_STX) @@ -417,13 +399,8 @@ static inline uint8_t mavlink_parse_char_new(uint8_t chan, uint8_t c, mavlink_me // Parse normally, if a CRC mismatch occurs retry with the next packet index } -//#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32) -// static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NB_HIGH]; -// static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NB_HIGH]; -//#else -// static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NB]; -// static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NB]; -//#endif +// static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS]; +// static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NUM_BUFFERS]; //// Initializes only once, values keep unchanged after first initialization // mavlink_parse_state_initialize(&m_mavlink_status[chan]); // @@ -575,6 +552,7 @@ typedef union __generic_64bit { uint8_t b[8]; int64_t ll; ///< Long long (64 bit) + double d; ///< IEEE-754 double precision floating point } generic_64bit; /** @@ -827,7 +805,7 @@ static inline uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t p // First pack everything we can into the current 'open' byte //curr_bits_n = bits_remain << 3; // Equals bits_remain mod 8 //FIXME - if (bits_remain <= uint16_t(8 - i_bit_index)) + if (bits_remain <= (8 - i_bit_index)) { // Enough space curr_bits_n = bits_remain; @@ -883,6 +861,103 @@ void comm_send_ch(mavlink_channel_t chan, uint8_t ch) } */ +static inline void mavlink_send_uart_uint8_t(mavlink_channel_t chan, uint8_t b, uint16_t* checksum) +{ + crc_accumulate(b, checksum); + comm_send_ch(chan, b); +} + +static inline void mavlink_send_uart_int8_t(mavlink_channel_t chan, int8_t b, uint16_t* checksum) +{ + crc_accumulate(b, checksum); + comm_send_ch(chan, b); +} + +static inline void mavlink_send_uart_uint16_t(mavlink_channel_t chan, uint16_t b, uint16_t* checksum) +{ + char s; + s = (b>>8)&0xff; + comm_send_ch(chan, s); + crc_accumulate(s, checksum); + s = (b & 0xff); + comm_send_ch(chan, s); + crc_accumulate(s, checksum); +} + +static inline void mavlink_send_uart_int16_t(mavlink_channel_t chan, int16_t b, uint16_t* checksum) +{ + mavlink_send_uart_uint16_t(chan, b, checksum); +} + +static inline void mavlink_send_uart_uint32_t(mavlink_channel_t chan, uint32_t b, uint16_t* checksum) +{ + char s; + s = (b>>24)&0xff; + comm_send_ch(chan, s); + crc_accumulate(s, checksum); + s = (b>>16)&0xff; + comm_send_ch(chan, s); + crc_accumulate(s, checksum); + s = (b>>8)&0xff; + comm_send_ch(chan, s); + crc_accumulate(s, checksum); + s = (b & 0xff); + comm_send_ch(chan, s); + crc_accumulate(s, checksum); +} + +static inline void mavlink_send_uart_int32_t(mavlink_channel_t chan, int32_t b, uint16_t* checksum) +{ + mavlink_send_uart_uint32_t(chan, b, checksum); +} + +static inline void mavlink_send_uart_uint64_t(mavlink_channel_t chan, uint64_t b, uint16_t* checksum) +{ + char s; + s = (b>>56)&0xff; + comm_send_ch(chan, s); + crc_accumulate(s, checksum); + s = (b>>48)&0xff; + comm_send_ch(chan, s); + crc_accumulate(s, checksum); + s = (b>>40)&0xff; + comm_send_ch(chan, s); + crc_accumulate(s, checksum); + s = (b>>32)&0xff; + comm_send_ch(chan, s); + crc_accumulate(s, checksum); + s = (b>>24)&0xff; + comm_send_ch(chan, s); + crc_accumulate(s, checksum); + s = (b>>16)&0xff; + comm_send_ch(chan, s); + crc_accumulate(s, checksum); + s = (b>>8)&0xff; + comm_send_ch(chan, s); + crc_accumulate(s, checksum); + s = (b & 0xff); + comm_send_ch(chan, s); + crc_accumulate(s, checksum); +} + +static inline void mavlink_send_uart_int64_t(mavlink_channel_t chan, int64_t b, uint16_t* checksum) +{ + mavlink_send_uart_uint64_t(chan, b, checksum); +} + +static inline void mavlink_send_uart_float(mavlink_channel_t chan, float b, uint16_t* checksum) +{ + generic_32bit g; + g.f = b; + mavlink_send_uart_uint32_t(chan, g.i, checksum); +} + +static inline void mavlink_send_uart_double(mavlink_channel_t chan, double b, uint16_t* checksum) +{ + generic_64bit g; + g.d = b; + mavlink_send_uart_uint32_t(chan, g.ll, checksum); +} static inline void mavlink_send_uart(mavlink_channel_t chan, mavlink_message_t* msg) { diff --git a/libraries/GCS_MAVLink/include/slugs/mavlink.h b/libraries/GCS_MAVLink/include/slugs/mavlink.h index 52e095ad3c..d456a6bc56 100644 --- a/libraries/GCS_MAVLink/include/slugs/mavlink.h +++ b/libraries/GCS_MAVLink/include/slugs/mavlink.h @@ -1,7 +1,7 @@ /** @file * @brief MAVLink comm protocol. * @see http://pixhawk.ethz.ch/software/mavlink - * Generated on Thursday, December 2 2010, 10:44 UTC + * Generated on Saturday, April 16 2011, 04:02 UTC */ #ifndef MAVLINK_H #define MAVLINK_H diff --git a/libraries/GCS_MAVLink/include/slugs/mavlink_msg_air_data.h b/libraries/GCS_MAVLink/include/slugs/mavlink_msg_air_data.h index 0a54502db5..2b212ae1ba 100644 --- a/libraries/GCS_MAVLink/include/slugs/mavlink_msg_air_data.h +++ b/libraries/GCS_MAVLink/include/slugs/mavlink_msg_air_data.h @@ -13,7 +13,10 @@ typedef struct __mavlink_air_data_t /** - * @brief Send a air_data message + * @brief Pack a air_data message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into * * @param dynamicPressure Dynamic pressure (Pa) * @param staticPressure Static pressure (Pa) @@ -25,37 +28,63 @@ static inline uint16_t mavlink_msg_air_data_pack(uint8_t system_id, uint8_t comp uint16_t i = 0; msg->msgid = MAVLINK_MSG_ID_AIR_DATA; - i += put_float_by_index(dynamicPressure, i, msg->payload); //Dynamic pressure (Pa) - i += put_float_by_index(staticPressure, i, msg->payload); //Static pressure (Pa) - i += put_uint16_t_by_index(temperature, i, msg->payload); //Board temperature + i += put_float_by_index(dynamicPressure, i, msg->payload); // Dynamic pressure (Pa) + i += put_float_by_index(staticPressure, i, msg->payload); // Static pressure (Pa) + i += put_uint16_t_by_index(temperature, i, msg->payload); // Board temperature return mavlink_finalize_message(msg, system_id, component_id, i); } -static inline uint16_t mavlink_msg_air_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, float dynamicPressure, float staticPressure, uint16_t temperature) +/** + * @brief Pack a air_data message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param dynamicPressure Dynamic pressure (Pa) + * @param staticPressure Static pressure (Pa) + * @param temperature Board temperature + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_air_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float dynamicPressure, float staticPressure, uint16_t temperature) { uint16_t i = 0; msg->msgid = MAVLINK_MSG_ID_AIR_DATA; - i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the air data - i += put_float_by_index(dynamicPressure, i, msg->payload); //Dynamic pressure (Pa) - i += put_float_by_index(staticPressure, i, msg->payload); //Static pressure (Pa) - i += put_uint16_t_by_index(temperature, i, msg->payload); //Board temperature + i += put_float_by_index(dynamicPressure, i, msg->payload); // Dynamic pressure (Pa) + i += put_float_by_index(staticPressure, i, msg->payload); // Static pressure (Pa) + i += put_uint16_t_by_index(temperature, i, msg->payload); // Board temperature return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); } +/** + * @brief Encode a air_data struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param air_data C-struct to read the message contents from + */ static inline uint16_t mavlink_msg_air_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_air_data_t* air_data) { return mavlink_msg_air_data_pack(system_id, component_id, msg, air_data->dynamicPressure, air_data->staticPressure, air_data->temperature); } +/** + * @brief Send a air_data message + * @param chan MAVLink channel to send the message + * + * @param dynamicPressure Dynamic pressure (Pa) + * @param staticPressure Static pressure (Pa) + * @param temperature Board temperature + */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS static inline void mavlink_msg_air_data_send(mavlink_channel_t chan, float dynamicPressure, float staticPressure, uint16_t temperature) { mavlink_message_t msg; - mavlink_msg_air_data_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, dynamicPressure, staticPressure, temperature); + mavlink_msg_air_data_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, dynamicPressure, staticPressure, temperature); mavlink_send_uart(chan, &msg); } @@ -105,6 +134,12 @@ static inline uint16_t mavlink_msg_air_data_get_temperature(const mavlink_messag return (uint16_t)r.s; } +/** + * @brief Decode a air_data message into a struct + * + * @param msg The message to decode + * @param air_data C-struct to decode the message contents into + */ static inline void mavlink_msg_air_data_decode(const mavlink_message_t* msg, mavlink_air_data_t* air_data) { air_data->dynamicPressure = mavlink_msg_air_data_get_dynamicPressure(msg); diff --git a/libraries/GCS_MAVLink/include/slugs/mavlink_msg_cpu_load.h b/libraries/GCS_MAVLink/include/slugs/mavlink_msg_cpu_load.h index 78a69ab9b8..265aa3fcee 100644 --- a/libraries/GCS_MAVLink/include/slugs/mavlink_msg_cpu_load.h +++ b/libraries/GCS_MAVLink/include/slugs/mavlink_msg_cpu_load.h @@ -13,7 +13,10 @@ typedef struct __mavlink_cpu_load_t /** - * @brief Send a cpu_load message + * @brief Pack a cpu_load message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into * * @param sensLoad Sensor DSC Load * @param ctrlLoad Control DSC Load @@ -25,37 +28,63 @@ static inline uint16_t mavlink_msg_cpu_load_pack(uint8_t system_id, uint8_t comp uint16_t i = 0; msg->msgid = MAVLINK_MSG_ID_CPU_LOAD; - i += put_uint8_t_by_index(sensLoad, i, msg->payload); //Sensor DSC Load - i += put_uint8_t_by_index(ctrlLoad, i, msg->payload); //Control DSC Load - i += put_uint16_t_by_index(batVolt, i, msg->payload); //Battery Voltage in millivolts + i += put_uint8_t_by_index(sensLoad, i, msg->payload); // Sensor DSC Load + i += put_uint8_t_by_index(ctrlLoad, i, msg->payload); // Control DSC Load + i += put_uint16_t_by_index(batVolt, i, msg->payload); // Battery Voltage in millivolts return mavlink_finalize_message(msg, system_id, component_id, i); } -static inline uint16_t mavlink_msg_cpu_load_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, uint8_t sensLoad, uint8_t ctrlLoad, uint16_t batVolt) +/** + * @brief Pack a cpu_load message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param sensLoad Sensor DSC Load + * @param ctrlLoad Control DSC Load + * @param batVolt Battery Voltage in millivolts + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_cpu_load_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t sensLoad, uint8_t ctrlLoad, uint16_t batVolt) { uint16_t i = 0; msg->msgid = MAVLINK_MSG_ID_CPU_LOAD; - i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the CPU load - i += put_uint8_t_by_index(sensLoad, i, msg->payload); //Sensor DSC Load - i += put_uint8_t_by_index(ctrlLoad, i, msg->payload); //Control DSC Load - i += put_uint16_t_by_index(batVolt, i, msg->payload); //Battery Voltage in millivolts + i += put_uint8_t_by_index(sensLoad, i, msg->payload); // Sensor DSC Load + i += put_uint8_t_by_index(ctrlLoad, i, msg->payload); // Control DSC Load + i += put_uint16_t_by_index(batVolt, i, msg->payload); // Battery Voltage in millivolts return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); } +/** + * @brief Encode a cpu_load struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param cpu_load C-struct to read the message contents from + */ static inline uint16_t mavlink_msg_cpu_load_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_cpu_load_t* cpu_load) { return mavlink_msg_cpu_load_pack(system_id, component_id, msg, cpu_load->sensLoad, cpu_load->ctrlLoad, cpu_load->batVolt); } +/** + * @brief Send a cpu_load message + * @param chan MAVLink channel to send the message + * + * @param sensLoad Sensor DSC Load + * @param ctrlLoad Control DSC Load + * @param batVolt Battery Voltage in millivolts + */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS static inline void mavlink_msg_cpu_load_send(mavlink_channel_t chan, uint8_t sensLoad, uint8_t ctrlLoad, uint16_t batVolt) { mavlink_message_t msg; - mavlink_msg_cpu_load_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, sensLoad, ctrlLoad, batVolt); + mavlink_msg_cpu_load_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, sensLoad, ctrlLoad, batVolt); mavlink_send_uart(chan, &msg); } @@ -95,6 +124,12 @@ static inline uint16_t mavlink_msg_cpu_load_get_batVolt(const mavlink_message_t* return (uint16_t)r.s; } +/** + * @brief Decode a cpu_load message into a struct + * + * @param msg The message to decode + * @param cpu_load C-struct to decode the message contents into + */ static inline void mavlink_msg_cpu_load_decode(const mavlink_message_t* msg, mavlink_cpu_load_t* cpu_load) { cpu_load->sensLoad = mavlink_msg_cpu_load_get_sensLoad(msg); diff --git a/libraries/GCS_MAVLink/include/slugs/mavlink_msg_ctrl_srfc_pt.h b/libraries/GCS_MAVLink/include/slugs/mavlink_msg_ctrl_srfc_pt.h index 570659893b..9221dc4f00 100644 --- a/libraries/GCS_MAVLink/include/slugs/mavlink_msg_ctrl_srfc_pt.h +++ b/libraries/GCS_MAVLink/include/slugs/mavlink_msg_ctrl_srfc_pt.h @@ -12,7 +12,10 @@ typedef struct __mavlink_ctrl_srfc_pt_t /** - * @brief Send a ctrl_srfc_pt message + * @brief Pack a ctrl_srfc_pt message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into * * @param target The system setting the commands * @param bitfieldPt Bitfield containing the PT configuration @@ -23,23 +26,59 @@ static inline uint16_t mavlink_msg_ctrl_srfc_pt_pack(uint8_t system_id, uint8_t uint16_t i = 0; msg->msgid = MAVLINK_MSG_ID_CTRL_SRFC_PT; - i += put_uint8_t_by_index(target, i, msg->payload); //The system setting the commands - i += put_uint16_t_by_index(bitfieldPt, i, msg->payload); //Bitfield containing the PT configuration + i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the commands + i += put_uint16_t_by_index(bitfieldPt, i, msg->payload); // Bitfield containing the PT configuration return mavlink_finalize_message(msg, system_id, component_id, i); } +/** + * @brief Pack a ctrl_srfc_pt message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target The system setting the commands + * @param bitfieldPt Bitfield containing the PT configuration + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_ctrl_srfc_pt_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, uint16_t bitfieldPt) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_CTRL_SRFC_PT; + + i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the commands + i += put_uint16_t_by_index(bitfieldPt, i, msg->payload); // Bitfield containing the PT configuration + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a ctrl_srfc_pt struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param ctrl_srfc_pt C-struct to read the message contents from + */ static inline uint16_t mavlink_msg_ctrl_srfc_pt_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ctrl_srfc_pt_t* ctrl_srfc_pt) { return mavlink_msg_ctrl_srfc_pt_pack(system_id, component_id, msg, ctrl_srfc_pt->target, ctrl_srfc_pt->bitfieldPt); } +/** + * @brief Send a ctrl_srfc_pt message + * @param chan MAVLink channel to send the message + * + * @param target The system setting the commands + * @param bitfieldPt Bitfield containing the PT configuration + */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS static inline void mavlink_msg_ctrl_srfc_pt_send(mavlink_channel_t chan, uint8_t target, uint16_t bitfieldPt) { mavlink_message_t msg; - mavlink_msg_ctrl_srfc_pt_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, bitfieldPt); + mavlink_msg_ctrl_srfc_pt_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, bitfieldPt); mavlink_send_uart(chan, &msg); } @@ -69,6 +108,12 @@ static inline uint16_t mavlink_msg_ctrl_srfc_pt_get_bitfieldPt(const mavlink_mes return (uint16_t)r.s; } +/** + * @brief Decode a ctrl_srfc_pt message into a struct + * + * @param msg The message to decode + * @param ctrl_srfc_pt C-struct to decode the message contents into + */ static inline void mavlink_msg_ctrl_srfc_pt_decode(const mavlink_message_t* msg, mavlink_ctrl_srfc_pt_t* ctrl_srfc_pt) { ctrl_srfc_pt->target = mavlink_msg_ctrl_srfc_pt_get_target(msg); diff --git a/libraries/GCS_MAVLink/include/slugs/mavlink_msg_data_log.h b/libraries/GCS_MAVLink/include/slugs/mavlink_msg_data_log.h index d56eb577f4..cbcc0daba3 100644 --- a/libraries/GCS_MAVLink/include/slugs/mavlink_msg_data_log.h +++ b/libraries/GCS_MAVLink/include/slugs/mavlink_msg_data_log.h @@ -16,7 +16,10 @@ typedef struct __mavlink_data_log_t /** - * @brief Send a data_log message + * @brief Pack a data_log message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into * * @param fl_1 Log value 1 * @param fl_2 Log value 2 @@ -31,27 +34,75 @@ static inline uint16_t mavlink_msg_data_log_pack(uint8_t system_id, uint8_t comp uint16_t i = 0; msg->msgid = MAVLINK_MSG_ID_DATA_LOG; - i += put_float_by_index(fl_1, i, msg->payload); //Log value 1 - i += put_float_by_index(fl_2, i, msg->payload); //Log value 2 - i += put_float_by_index(fl_3, i, msg->payload); //Log value 3 - i += put_float_by_index(fl_4, i, msg->payload); //Log value 4 - i += put_float_by_index(fl_5, i, msg->payload); //Log value 5 - i += put_float_by_index(fl_6, i, msg->payload); //Log value 6 + i += put_float_by_index(fl_1, i, msg->payload); // Log value 1 + i += put_float_by_index(fl_2, i, msg->payload); // Log value 2 + i += put_float_by_index(fl_3, i, msg->payload); // Log value 3 + i += put_float_by_index(fl_4, i, msg->payload); // Log value 4 + i += put_float_by_index(fl_5, i, msg->payload); // Log value 5 + i += put_float_by_index(fl_6, i, msg->payload); // Log value 6 return mavlink_finalize_message(msg, system_id, component_id, i); } +/** + * @brief Pack a data_log message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param fl_1 Log value 1 + * @param fl_2 Log value 2 + * @param fl_3 Log value 3 + * @param fl_4 Log value 4 + * @param fl_5 Log value 5 + * @param fl_6 Log value 6 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_data_log_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float fl_1, float fl_2, float fl_3, float fl_4, float fl_5, float fl_6) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_DATA_LOG; + + i += put_float_by_index(fl_1, i, msg->payload); // Log value 1 + i += put_float_by_index(fl_2, i, msg->payload); // Log value 2 + i += put_float_by_index(fl_3, i, msg->payload); // Log value 3 + i += put_float_by_index(fl_4, i, msg->payload); // Log value 4 + i += put_float_by_index(fl_5, i, msg->payload); // Log value 5 + i += put_float_by_index(fl_6, i, msg->payload); // Log value 6 + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a data_log struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param data_log C-struct to read the message contents from + */ static inline uint16_t mavlink_msg_data_log_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data_log_t* data_log) { return mavlink_msg_data_log_pack(system_id, component_id, msg, data_log->fl_1, data_log->fl_2, data_log->fl_3, data_log->fl_4, data_log->fl_5, data_log->fl_6); } +/** + * @brief Send a data_log message + * @param chan MAVLink channel to send the message + * + * @param fl_1 Log value 1 + * @param fl_2 Log value 2 + * @param fl_3 Log value 3 + * @param fl_4 Log value 4 + * @param fl_5 Log value 5 + * @param fl_6 Log value 6 + */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS static inline void mavlink_msg_data_log_send(mavlink_channel_t chan, float fl_1, float fl_2, float fl_3, float fl_4, float fl_5, float fl_6) { mavlink_message_t msg; - mavlink_msg_data_log_pack(mavlink_system.sysid, mavlink_system.compid, &msg, fl_1, fl_2, fl_3, fl_4, fl_5, fl_6); + mavlink_msg_data_log_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, fl_1, fl_2, fl_3, fl_4, fl_5, fl_6); mavlink_send_uart(chan, &msg); } @@ -148,6 +199,12 @@ static inline float mavlink_msg_data_log_get_fl_6(const mavlink_message_t* msg) return (float)r.f; } +/** + * @brief Decode a data_log message into a struct + * + * @param msg The message to decode + * @param data_log C-struct to decode the message contents into + */ static inline void mavlink_msg_data_log_decode(const mavlink_message_t* msg, mavlink_data_log_t* data_log) { data_log->fl_1 = mavlink_msg_data_log_get_fl_1(msg); diff --git a/libraries/GCS_MAVLink/include/slugs/mavlink_msg_diagnostic.h b/libraries/GCS_MAVLink/include/slugs/mavlink_msg_diagnostic.h index e13e09d03f..f3798f59bb 100644 --- a/libraries/GCS_MAVLink/include/slugs/mavlink_msg_diagnostic.h +++ b/libraries/GCS_MAVLink/include/slugs/mavlink_msg_diagnostic.h @@ -16,7 +16,10 @@ typedef struct __mavlink_diagnostic_t /** - * @brief Send a diagnostic message + * @brief Pack a diagnostic message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into * * @param diagFl1 Diagnostic float 1 * @param diagFl2 Diagnostic float 2 @@ -31,43 +34,75 @@ static inline uint16_t mavlink_msg_diagnostic_pack(uint8_t system_id, uint8_t co uint16_t i = 0; msg->msgid = MAVLINK_MSG_ID_DIAGNOSTIC; - i += put_float_by_index(diagFl1, i, msg->payload); //Diagnostic float 1 - i += put_float_by_index(diagFl2, i, msg->payload); //Diagnostic float 2 - i += put_float_by_index(diagFl3, i, msg->payload); //Diagnostic float 3 - i += put_int16_t_by_index(diagSh1, i, msg->payload); //Diagnostic short 1 - i += put_int16_t_by_index(diagSh2, i, msg->payload); //Diagnostic short 2 - i += put_int16_t_by_index(diagSh3, i, msg->payload); //Diagnostic short 3 + i += put_float_by_index(diagFl1, i, msg->payload); // Diagnostic float 1 + i += put_float_by_index(diagFl2, i, msg->payload); // Diagnostic float 2 + i += put_float_by_index(diagFl3, i, msg->payload); // Diagnostic float 3 + i += put_int16_t_by_index(diagSh1, i, msg->payload); // Diagnostic short 1 + i += put_int16_t_by_index(diagSh2, i, msg->payload); // Diagnostic short 2 + i += put_int16_t_by_index(diagSh3, i, msg->payload); // Diagnostic short 3 return mavlink_finalize_message(msg, system_id, component_id, i); } -static inline uint16_t mavlink_msg_diagnostic_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, float diagFl1, float diagFl2, float diagFl3, int16_t diagSh1, int16_t diagSh2, int16_t diagSh3) +/** + * @brief Pack a diagnostic message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param diagFl1 Diagnostic float 1 + * @param diagFl2 Diagnostic float 2 + * @param diagFl3 Diagnostic float 3 + * @param diagSh1 Diagnostic short 1 + * @param diagSh2 Diagnostic short 2 + * @param diagSh3 Diagnostic short 3 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_diagnostic_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float diagFl1, float diagFl2, float diagFl3, int16_t diagSh1, int16_t diagSh2, int16_t diagSh3) { uint16_t i = 0; msg->msgid = MAVLINK_MSG_ID_DIAGNOSTIC; - i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the diagnostic - i += put_float_by_index(diagFl1, i, msg->payload); //Diagnostic float 1 - i += put_float_by_index(diagFl2, i, msg->payload); //Diagnostic float 2 - i += put_float_by_index(diagFl3, i, msg->payload); //Diagnostic float 3 - i += put_int16_t_by_index(diagSh1, i, msg->payload); //Diagnostic short 1 - i += put_int16_t_by_index(diagSh2, i, msg->payload); //Diagnostic short 2 - i += put_int16_t_by_index(diagSh3, i, msg->payload); //Diagnostic short 3 + i += put_float_by_index(diagFl1, i, msg->payload); // Diagnostic float 1 + i += put_float_by_index(diagFl2, i, msg->payload); // Diagnostic float 2 + i += put_float_by_index(diagFl3, i, msg->payload); // Diagnostic float 3 + i += put_int16_t_by_index(diagSh1, i, msg->payload); // Diagnostic short 1 + i += put_int16_t_by_index(diagSh2, i, msg->payload); // Diagnostic short 2 + i += put_int16_t_by_index(diagSh3, i, msg->payload); // Diagnostic short 3 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); } +/** + * @brief Encode a diagnostic struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param diagnostic C-struct to read the message contents from + */ static inline uint16_t mavlink_msg_diagnostic_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_diagnostic_t* diagnostic) { return mavlink_msg_diagnostic_pack(system_id, component_id, msg, diagnostic->diagFl1, diagnostic->diagFl2, diagnostic->diagFl3, diagnostic->diagSh1, diagnostic->diagSh2, diagnostic->diagSh3); } +/** + * @brief Send a diagnostic message + * @param chan MAVLink channel to send the message + * + * @param diagFl1 Diagnostic float 1 + * @param diagFl2 Diagnostic float 2 + * @param diagFl3 Diagnostic float 3 + * @param diagSh1 Diagnostic short 1 + * @param diagSh2 Diagnostic short 2 + * @param diagSh3 Diagnostic short 3 + */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS static inline void mavlink_msg_diagnostic_send(mavlink_channel_t chan, float diagFl1, float diagFl2, float diagFl3, int16_t diagSh1, int16_t diagSh2, int16_t diagSh3) { mavlink_message_t msg; - mavlink_msg_diagnostic_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, diagFl1, diagFl2, diagFl3, diagSh1, diagSh2, diagSh3); + mavlink_msg_diagnostic_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, diagFl1, diagFl2, diagFl3, diagSh1, diagSh2, diagSh3); mavlink_send_uart(chan, &msg); } @@ -158,6 +193,12 @@ static inline int16_t mavlink_msg_diagnostic_get_diagSh3(const mavlink_message_t return (int16_t)r.s; } +/** + * @brief Decode a diagnostic message into a struct + * + * @param msg The message to decode + * @param diagnostic C-struct to decode the message contents into + */ static inline void mavlink_msg_diagnostic_decode(const mavlink_message_t* msg, mavlink_diagnostic_t* diagnostic) { diagnostic->diagFl1 = mavlink_msg_diagnostic_get_diagFl1(msg); diff --git a/libraries/GCS_MAVLink/include/slugs/mavlink_msg_gps_date_time.h b/libraries/GCS_MAVLink/include/slugs/mavlink_msg_gps_date_time.h index 646920fb88..199cbb9ec2 100644 --- a/libraries/GCS_MAVLink/include/slugs/mavlink_msg_gps_date_time.h +++ b/libraries/GCS_MAVLink/include/slugs/mavlink_msg_gps_date_time.h @@ -17,7 +17,10 @@ typedef struct __mavlink_gps_date_time_t /** - * @brief Send a gps_date_time message + * @brief Pack a gps_date_time message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into * * @param year Year reported by Gps * @param month Month reported by Gps @@ -33,28 +36,79 @@ static inline uint16_t mavlink_msg_gps_date_time_pack(uint8_t system_id, uint8_t uint16_t i = 0; msg->msgid = MAVLINK_MSG_ID_GPS_DATE_TIME; - i += put_uint8_t_by_index(year, i, msg->payload); //Year reported by Gps - i += put_uint8_t_by_index(month, i, msg->payload); //Month reported by Gps - i += put_uint8_t_by_index(day, i, msg->payload); //Day reported by Gps - i += put_uint8_t_by_index(hour, i, msg->payload); //Hour reported by Gps - i += put_uint8_t_by_index(min, i, msg->payload); //Min reported by Gps - i += put_uint8_t_by_index(sec, i, msg->payload); //Sec reported by Gps - i += put_uint8_t_by_index(visSat, i, msg->payload); //Visible sattelites reported by Gps + i += put_uint8_t_by_index(year, i, msg->payload); // Year reported by Gps + i += put_uint8_t_by_index(month, i, msg->payload); // Month reported by Gps + i += put_uint8_t_by_index(day, i, msg->payload); // Day reported by Gps + i += put_uint8_t_by_index(hour, i, msg->payload); // Hour reported by Gps + i += put_uint8_t_by_index(min, i, msg->payload); // Min reported by Gps + i += put_uint8_t_by_index(sec, i, msg->payload); // Sec reported by Gps + i += put_uint8_t_by_index(visSat, i, msg->payload); // Visible sattelites reported by Gps return mavlink_finalize_message(msg, system_id, component_id, i); } +/** + * @brief Pack a gps_date_time message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param year Year reported by Gps + * @param month Month reported by Gps + * @param day Day reported by Gps + * @param hour Hour reported by Gps + * @param min Min reported by Gps + * @param sec Sec reported by Gps + * @param visSat Visible sattelites reported by Gps + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_date_time_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t year, uint8_t month, uint8_t day, uint8_t hour, uint8_t min, uint8_t sec, uint8_t visSat) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_GPS_DATE_TIME; + + i += put_uint8_t_by_index(year, i, msg->payload); // Year reported by Gps + i += put_uint8_t_by_index(month, i, msg->payload); // Month reported by Gps + i += put_uint8_t_by_index(day, i, msg->payload); // Day reported by Gps + i += put_uint8_t_by_index(hour, i, msg->payload); // Hour reported by Gps + i += put_uint8_t_by_index(min, i, msg->payload); // Min reported by Gps + i += put_uint8_t_by_index(sec, i, msg->payload); // Sec reported by Gps + i += put_uint8_t_by_index(visSat, i, msg->payload); // Visible sattelites reported by Gps + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a gps_date_time struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param gps_date_time C-struct to read the message contents from + */ static inline uint16_t mavlink_msg_gps_date_time_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_date_time_t* gps_date_time) { return mavlink_msg_gps_date_time_pack(system_id, component_id, msg, gps_date_time->year, gps_date_time->month, gps_date_time->day, gps_date_time->hour, gps_date_time->min, gps_date_time->sec, gps_date_time->visSat); } +/** + * @brief Send a gps_date_time message + * @param chan MAVLink channel to send the message + * + * @param year Year reported by Gps + * @param month Month reported by Gps + * @param day Day reported by Gps + * @param hour Hour reported by Gps + * @param min Min reported by Gps + * @param sec Sec reported by Gps + * @param visSat Visible sattelites reported by Gps + */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS static inline void mavlink_msg_gps_date_time_send(mavlink_channel_t chan, uint8_t year, uint8_t month, uint8_t day, uint8_t hour, uint8_t min, uint8_t sec, uint8_t visSat) { mavlink_message_t msg; - mavlink_msg_gps_date_time_pack(mavlink_system.sysid, mavlink_system.compid, &msg, year, month, day, hour, min, sec, visSat); + mavlink_msg_gps_date_time_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, year, month, day, hour, min, sec, visSat); mavlink_send_uart(chan, &msg); } @@ -131,6 +185,12 @@ static inline uint8_t mavlink_msg_gps_date_time_get_visSat(const mavlink_message return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; } +/** + * @brief Decode a gps_date_time message into a struct + * + * @param msg The message to decode + * @param gps_date_time C-struct to decode the message contents into + */ static inline void mavlink_msg_gps_date_time_decode(const mavlink_message_t* msg, mavlink_gps_date_time_t* gps_date_time) { gps_date_time->year = mavlink_msg_gps_date_time_get_year(msg); diff --git a/libraries/GCS_MAVLink/include/slugs/mavlink_msg_mid_lvl_cmds.h b/libraries/GCS_MAVLink/include/slugs/mavlink_msg_mid_lvl_cmds.h index 0ae94b097b..a0d78b1ceb 100644 --- a/libraries/GCS_MAVLink/include/slugs/mavlink_msg_mid_lvl_cmds.h +++ b/libraries/GCS_MAVLink/include/slugs/mavlink_msg_mid_lvl_cmds.h @@ -14,7 +14,10 @@ typedef struct __mavlink_mid_lvl_cmds_t /** - * @brief Send a mid_lvl_cmds message + * @brief Pack a mid_lvl_cmds message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into * * @param target The system setting the commands * @param hCommand Commanded Airspeed @@ -27,25 +30,67 @@ static inline uint16_t mavlink_msg_mid_lvl_cmds_pack(uint8_t system_id, uint8_t uint16_t i = 0; msg->msgid = MAVLINK_MSG_ID_MID_LVL_CMDS; - i += put_uint8_t_by_index(target, i, msg->payload); //The system setting the commands - i += put_float_by_index(hCommand, i, msg->payload); //Commanded Airspeed - i += put_float_by_index(uCommand, i, msg->payload); //Log value 2 - i += put_float_by_index(rCommand, i, msg->payload); //Log value 3 + i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the commands + i += put_float_by_index(hCommand, i, msg->payload); // Commanded Airspeed + i += put_float_by_index(uCommand, i, msg->payload); // Log value 2 + i += put_float_by_index(rCommand, i, msg->payload); // Log value 3 return mavlink_finalize_message(msg, system_id, component_id, i); } +/** + * @brief Pack a mid_lvl_cmds message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target The system setting the commands + * @param hCommand Commanded Airspeed + * @param uCommand Log value 2 + * @param rCommand Log value 3 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mid_lvl_cmds_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, float hCommand, float uCommand, float rCommand) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_MID_LVL_CMDS; + + i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the commands + i += put_float_by_index(hCommand, i, msg->payload); // Commanded Airspeed + i += put_float_by_index(uCommand, i, msg->payload); // Log value 2 + i += put_float_by_index(rCommand, i, msg->payload); // Log value 3 + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a mid_lvl_cmds struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mid_lvl_cmds C-struct to read the message contents from + */ static inline uint16_t mavlink_msg_mid_lvl_cmds_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mid_lvl_cmds_t* mid_lvl_cmds) { return mavlink_msg_mid_lvl_cmds_pack(system_id, component_id, msg, mid_lvl_cmds->target, mid_lvl_cmds->hCommand, mid_lvl_cmds->uCommand, mid_lvl_cmds->rCommand); } +/** + * @brief Send a mid_lvl_cmds message + * @param chan MAVLink channel to send the message + * + * @param target The system setting the commands + * @param hCommand Commanded Airspeed + * @param uCommand Log value 2 + * @param rCommand Log value 3 + */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS static inline void mavlink_msg_mid_lvl_cmds_send(mavlink_channel_t chan, uint8_t target, float hCommand, float uCommand, float rCommand) { mavlink_message_t msg; - mavlink_msg_mid_lvl_cmds_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, hCommand, uCommand, rCommand); + mavlink_msg_mid_lvl_cmds_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, hCommand, uCommand, rCommand); mavlink_send_uart(chan, &msg); } @@ -107,6 +152,12 @@ static inline float mavlink_msg_mid_lvl_cmds_get_rCommand(const mavlink_message_ return (float)r.f; } +/** + * @brief Decode a mid_lvl_cmds message into a struct + * + * @param msg The message to decode + * @param mid_lvl_cmds C-struct to decode the message contents into + */ static inline void mavlink_msg_mid_lvl_cmds_decode(const mavlink_message_t* msg, mavlink_mid_lvl_cmds_t* mid_lvl_cmds) { mid_lvl_cmds->target = mavlink_msg_mid_lvl_cmds_get_target(msg); diff --git a/libraries/GCS_MAVLink/include/slugs/mavlink_msg_sensor_bias.h b/libraries/GCS_MAVLink/include/slugs/mavlink_msg_sensor_bias.h index bc3d3d65f5..8b40bdd67a 100644 --- a/libraries/GCS_MAVLink/include/slugs/mavlink_msg_sensor_bias.h +++ b/libraries/GCS_MAVLink/include/slugs/mavlink_msg_sensor_bias.h @@ -16,7 +16,10 @@ typedef struct __mavlink_sensor_bias_t /** - * @brief Send a sensor_bias message + * @brief Pack a sensor_bias message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into * * @param axBias Accelerometer X bias (m/s) * @param ayBias Accelerometer Y bias (m/s) @@ -31,43 +34,75 @@ static inline uint16_t mavlink_msg_sensor_bias_pack(uint8_t system_id, uint8_t c uint16_t i = 0; msg->msgid = MAVLINK_MSG_ID_SENSOR_BIAS; - i += put_float_by_index(axBias, i, msg->payload); //Accelerometer X bias (m/s) - i += put_float_by_index(ayBias, i, msg->payload); //Accelerometer Y bias (m/s) - i += put_float_by_index(azBias, i, msg->payload); //Accelerometer Z bias (m/s) - i += put_float_by_index(gxBias, i, msg->payload); //Gyro X bias (rad/s) - i += put_float_by_index(gyBias, i, msg->payload); //Gyro Y bias (rad/s) - i += put_float_by_index(gzBias, i, msg->payload); //Gyro Z bias (rad/s) + i += put_float_by_index(axBias, i, msg->payload); // Accelerometer X bias (m/s) + i += put_float_by_index(ayBias, i, msg->payload); // Accelerometer Y bias (m/s) + i += put_float_by_index(azBias, i, msg->payload); // Accelerometer Z bias (m/s) + i += put_float_by_index(gxBias, i, msg->payload); // Gyro X bias (rad/s) + i += put_float_by_index(gyBias, i, msg->payload); // Gyro Y bias (rad/s) + i += put_float_by_index(gzBias, i, msg->payload); // Gyro Z bias (rad/s) return mavlink_finalize_message(msg, system_id, component_id, i); } -static inline uint16_t mavlink_msg_sensor_bias_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, float axBias, float ayBias, float azBias, float gxBias, float gyBias, float gzBias) +/** + * @brief Pack a sensor_bias message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param axBias Accelerometer X bias (m/s) + * @param ayBias Accelerometer Y bias (m/s) + * @param azBias Accelerometer Z bias (m/s) + * @param gxBias Gyro X bias (rad/s) + * @param gyBias Gyro Y bias (rad/s) + * @param gzBias Gyro Z bias (rad/s) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_sensor_bias_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float axBias, float ayBias, float azBias, float gxBias, float gyBias, float gzBias) { uint16_t i = 0; msg->msgid = MAVLINK_MSG_ID_SENSOR_BIAS; - i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the biases - i += put_float_by_index(axBias, i, msg->payload); //Accelerometer X bias (m/s) - i += put_float_by_index(ayBias, i, msg->payload); //Accelerometer Y bias (m/s) - i += put_float_by_index(azBias, i, msg->payload); //Accelerometer Z bias (m/s) - i += put_float_by_index(gxBias, i, msg->payload); //Gyro X bias (rad/s) - i += put_float_by_index(gyBias, i, msg->payload); //Gyro Y bias (rad/s) - i += put_float_by_index(gzBias, i, msg->payload); //Gyro Z bias (rad/s) + i += put_float_by_index(axBias, i, msg->payload); // Accelerometer X bias (m/s) + i += put_float_by_index(ayBias, i, msg->payload); // Accelerometer Y bias (m/s) + i += put_float_by_index(azBias, i, msg->payload); // Accelerometer Z bias (m/s) + i += put_float_by_index(gxBias, i, msg->payload); // Gyro X bias (rad/s) + i += put_float_by_index(gyBias, i, msg->payload); // Gyro Y bias (rad/s) + i += put_float_by_index(gzBias, i, msg->payload); // Gyro Z bias (rad/s) return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); } +/** + * @brief Encode a sensor_bias struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param sensor_bias C-struct to read the message contents from + */ static inline uint16_t mavlink_msg_sensor_bias_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensor_bias_t* sensor_bias) { return mavlink_msg_sensor_bias_pack(system_id, component_id, msg, sensor_bias->axBias, sensor_bias->ayBias, sensor_bias->azBias, sensor_bias->gxBias, sensor_bias->gyBias, sensor_bias->gzBias); } +/** + * @brief Send a sensor_bias message + * @param chan MAVLink channel to send the message + * + * @param axBias Accelerometer X bias (m/s) + * @param ayBias Accelerometer Y bias (m/s) + * @param azBias Accelerometer Z bias (m/s) + * @param gxBias Gyro X bias (rad/s) + * @param gyBias Gyro Y bias (rad/s) + * @param gzBias Gyro Z bias (rad/s) + */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS static inline void mavlink_msg_sensor_bias_send(mavlink_channel_t chan, float axBias, float ayBias, float azBias, float gxBias, float gyBias, float gzBias) { mavlink_message_t msg; - mavlink_msg_sensor_bias_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, axBias, ayBias, azBias, gxBias, gyBias, gzBias); + mavlink_msg_sensor_bias_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, axBias, ayBias, azBias, gxBias, gyBias, gzBias); mavlink_send_uart(chan, &msg); } @@ -164,6 +199,12 @@ static inline float mavlink_msg_sensor_bias_get_gzBias(const mavlink_message_t* return (float)r.f; } +/** + * @brief Decode a sensor_bias message into a struct + * + * @param msg The message to decode + * @param sensor_bias C-struct to decode the message contents into + */ static inline void mavlink_msg_sensor_bias_decode(const mavlink_message_t* msg, mavlink_sensor_bias_t* sensor_bias) { sensor_bias->axBias = mavlink_msg_sensor_bias_get_axBias(msg); diff --git a/libraries/GCS_MAVLink/include/slugs/mavlink_msg_slugs_action.h b/libraries/GCS_MAVLink/include/slugs/mavlink_msg_slugs_action.h index 7a6e38286d..0664166567 100644 --- a/libraries/GCS_MAVLink/include/slugs/mavlink_msg_slugs_action.h +++ b/libraries/GCS_MAVLink/include/slugs/mavlink_msg_slugs_action.h @@ -13,7 +13,10 @@ typedef struct __mavlink_slugs_action_t /** - * @brief Send a slugs_action message + * @brief Pack a slugs_action message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into * * @param target The system reporting the action * @param actionId Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names @@ -25,24 +28,63 @@ static inline uint16_t mavlink_msg_slugs_action_pack(uint8_t system_id, uint8_t uint16_t i = 0; msg->msgid = MAVLINK_MSG_ID_SLUGS_ACTION; - i += put_uint8_t_by_index(target, i, msg->payload); //The system reporting the action - i += put_uint8_t_by_index(actionId, i, msg->payload); //Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names - i += put_uint16_t_by_index(actionVal, i, msg->payload); //Value associated with the action + i += put_uint8_t_by_index(target, i, msg->payload); // The system reporting the action + i += put_uint8_t_by_index(actionId, i, msg->payload); // Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names + i += put_uint16_t_by_index(actionVal, i, msg->payload); // Value associated with the action return mavlink_finalize_message(msg, system_id, component_id, i); } +/** + * @brief Pack a slugs_action message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target The system reporting the action + * @param actionId Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names + * @param actionVal Value associated with the action + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_slugs_action_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, uint8_t actionId, uint16_t actionVal) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SLUGS_ACTION; + + i += put_uint8_t_by_index(target, i, msg->payload); // The system reporting the action + i += put_uint8_t_by_index(actionId, i, msg->payload); // Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names + i += put_uint16_t_by_index(actionVal, i, msg->payload); // Value associated with the action + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a slugs_action struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param slugs_action C-struct to read the message contents from + */ static inline uint16_t mavlink_msg_slugs_action_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_slugs_action_t* slugs_action) { return mavlink_msg_slugs_action_pack(system_id, component_id, msg, slugs_action->target, slugs_action->actionId, slugs_action->actionVal); } +/** + * @brief Send a slugs_action message + * @param chan MAVLink channel to send the message + * + * @param target The system reporting the action + * @param actionId Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names + * @param actionVal Value associated with the action + */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS static inline void mavlink_msg_slugs_action_send(mavlink_channel_t chan, uint8_t target, uint8_t actionId, uint16_t actionVal) { mavlink_message_t msg; - mavlink_msg_slugs_action_pack(mavlink_system.sysid, mavlink_system.compid, &msg, target, actionId, actionVal); + mavlink_msg_slugs_action_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, actionId, actionVal); mavlink_send_uart(chan, &msg); } @@ -82,6 +124,12 @@ static inline uint16_t mavlink_msg_slugs_action_get_actionVal(const mavlink_mess return (uint16_t)r.s; } +/** + * @brief Decode a slugs_action message into a struct + * + * @param msg The message to decode + * @param slugs_action C-struct to decode the message contents into + */ static inline void mavlink_msg_slugs_action_decode(const mavlink_message_t* msg, mavlink_slugs_action_t* slugs_action) { slugs_action->target = mavlink_msg_slugs_action_get_target(msg); diff --git a/libraries/GCS_MAVLink/include/slugs/mavlink_msg_slugs_navigation.h b/libraries/GCS_MAVLink/include/slugs/mavlink_msg_slugs_navigation.h index f4158f8fcf..f1a54cb3e4 100644 --- a/libraries/GCS_MAVLink/include/slugs/mavlink_msg_slugs_navigation.h +++ b/libraries/GCS_MAVLink/include/slugs/mavlink_msg_slugs_navigation.h @@ -19,7 +19,10 @@ typedef struct __mavlink_slugs_navigation_t /** - * @brief Send a slugs_navigation message + * @brief Pack a slugs_navigation message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into * * @param u_m Measured Airspeed prior to the Nav Filter * @param phi_c Commanded Roll @@ -37,30 +40,87 @@ static inline uint16_t mavlink_msg_slugs_navigation_pack(uint8_t system_id, uint uint16_t i = 0; msg->msgid = MAVLINK_MSG_ID_SLUGS_NAVIGATION; - i += put_float_by_index(u_m, i, msg->payload); //Measured Airspeed prior to the Nav Filter - i += put_float_by_index(phi_c, i, msg->payload); //Commanded Roll - i += put_float_by_index(theta_c, i, msg->payload); //Commanded Pitch - i += put_float_by_index(psiDot_c, i, msg->payload); //Commanded Turn rate - i += put_float_by_index(ay_body, i, msg->payload); //Y component of the body acceleration - i += put_float_by_index(totalDist, i, msg->payload); //Total Distance to Run on this leg of Navigation - i += put_float_by_index(dist2Go, i, msg->payload); //Remaining distance to Run on this leg of Navigation - i += put_uint8_t_by_index(fromWP, i, msg->payload); //Origin WP - i += put_uint8_t_by_index(toWP, i, msg->payload); //Destination WP + i += put_float_by_index(u_m, i, msg->payload); // Measured Airspeed prior to the Nav Filter + i += put_float_by_index(phi_c, i, msg->payload); // Commanded Roll + i += put_float_by_index(theta_c, i, msg->payload); // Commanded Pitch + i += put_float_by_index(psiDot_c, i, msg->payload); // Commanded Turn rate + i += put_float_by_index(ay_body, i, msg->payload); // Y component of the body acceleration + i += put_float_by_index(totalDist, i, msg->payload); // Total Distance to Run on this leg of Navigation + i += put_float_by_index(dist2Go, i, msg->payload); // Remaining distance to Run on this leg of Navigation + i += put_uint8_t_by_index(fromWP, i, msg->payload); // Origin WP + i += put_uint8_t_by_index(toWP, i, msg->payload); // Destination WP return mavlink_finalize_message(msg, system_id, component_id, i); } +/** + * @brief Pack a slugs_navigation message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param u_m Measured Airspeed prior to the Nav Filter + * @param phi_c Commanded Roll + * @param theta_c Commanded Pitch + * @param psiDot_c Commanded Turn rate + * @param ay_body Y component of the body acceleration + * @param totalDist Total Distance to Run on this leg of Navigation + * @param dist2Go Remaining distance to Run on this leg of Navigation + * @param fromWP Origin WP + * @param toWP Destination WP + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_slugs_navigation_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float u_m, float phi_c, float theta_c, float psiDot_c, float ay_body, float totalDist, float dist2Go, uint8_t fromWP, uint8_t toWP) +{ + uint16_t i = 0; + msg->msgid = MAVLINK_MSG_ID_SLUGS_NAVIGATION; + + i += put_float_by_index(u_m, i, msg->payload); // Measured Airspeed prior to the Nav Filter + i += put_float_by_index(phi_c, i, msg->payload); // Commanded Roll + i += put_float_by_index(theta_c, i, msg->payload); // Commanded Pitch + i += put_float_by_index(psiDot_c, i, msg->payload); // Commanded Turn rate + i += put_float_by_index(ay_body, i, msg->payload); // Y component of the body acceleration + i += put_float_by_index(totalDist, i, msg->payload); // Total Distance to Run on this leg of Navigation + i += put_float_by_index(dist2Go, i, msg->payload); // Remaining distance to Run on this leg of Navigation + i += put_uint8_t_by_index(fromWP, i, msg->payload); // Origin WP + i += put_uint8_t_by_index(toWP, i, msg->payload); // Destination WP + + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); +} + +/** + * @brief Encode a slugs_navigation struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param slugs_navigation C-struct to read the message contents from + */ static inline uint16_t mavlink_msg_slugs_navigation_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_slugs_navigation_t* slugs_navigation) { return mavlink_msg_slugs_navigation_pack(system_id, component_id, msg, slugs_navigation->u_m, slugs_navigation->phi_c, slugs_navigation->theta_c, slugs_navigation->psiDot_c, slugs_navigation->ay_body, slugs_navigation->totalDist, slugs_navigation->dist2Go, slugs_navigation->fromWP, slugs_navigation->toWP); } +/** + * @brief Send a slugs_navigation message + * @param chan MAVLink channel to send the message + * + * @param u_m Measured Airspeed prior to the Nav Filter + * @param phi_c Commanded Roll + * @param theta_c Commanded Pitch + * @param psiDot_c Commanded Turn rate + * @param ay_body Y component of the body acceleration + * @param totalDist Total Distance to Run on this leg of Navigation + * @param dist2Go Remaining distance to Run on this leg of Navigation + * @param fromWP Origin WP + * @param toWP Destination WP + */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS static inline void mavlink_msg_slugs_navigation_send(mavlink_channel_t chan, float u_m, float phi_c, float theta_c, float psiDot_c, float ay_body, float totalDist, float dist2Go, uint8_t fromWP, uint8_t toWP) { mavlink_message_t msg; - mavlink_msg_slugs_navigation_pack(mavlink_system.sysid, mavlink_system.compid, &msg, u_m, phi_c, theta_c, psiDot_c, ay_body, totalDist, dist2Go, fromWP, toWP); + mavlink_msg_slugs_navigation_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, u_m, phi_c, theta_c, psiDot_c, ay_body, totalDist, dist2Go, fromWP, toWP); mavlink_send_uart(chan, &msg); } @@ -192,6 +252,12 @@ static inline uint8_t mavlink_msg_slugs_navigation_get_toWP(const mavlink_messag return (uint8_t)(msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t))[0]; } +/** + * @brief Decode a slugs_navigation message into a struct + * + * @param msg The message to decode + * @param slugs_navigation C-struct to decode the message contents into + */ static inline void mavlink_msg_slugs_navigation_decode(const mavlink_message_t* msg, mavlink_slugs_navigation_t* slugs_navigation) { slugs_navigation->u_m = mavlink_msg_slugs_navigation_get_u_m(msg); diff --git a/libraries/GCS_MAVLink/include/slugs/slugs.h b/libraries/GCS_MAVLink/include/slugs/slugs.h index 26e8d5a85f..84bc1405f4 100644 --- a/libraries/GCS_MAVLink/include/slugs/slugs.h +++ b/libraries/GCS_MAVLink/include/slugs/slugs.h @@ -1,7 +1,7 @@ /** @file * @brief MAVLink comm protocol. * @see http://pixhawk.ethz.ch/software/mavlink - * Generated on Thursday, December 2 2010, 10:44 UTC + * Generated on Saturday, April 16 2011, 04:02 UTC */ #ifndef SLUGS_H #define SLUGS_H @@ -17,6 +17,17 @@ extern "C" { #include "../common/common.h" +// MAVLINK VERSION + +#ifndef MAVLINK_VERSION +#define MAVLINK_VERSION 0 +#endif + +#if (MAVLINK_VERSION == 0) +#undef MAVLINK_VERSION +#define MAVLINK_VERSION 0 +#endif + // ENUM DEFINITIONS @@ -26,16 +37,19 @@ extern "C" { #include "./mavlink_msg_air_data.h" #include "./mavlink_msg_sensor_bias.h" #include "./mavlink_msg_diagnostic.h" -#include "./mavlink_msg_pilot_console.h" -#include "./mavlink_msg_pwm_commands.h" #include "./mavlink_msg_slugs_navigation.h" #include "./mavlink_msg_data_log.h" -#include "./mavlink_msg_filtered_data.h" #include "./mavlink_msg_gps_date_time.h" #include "./mavlink_msg_mid_lvl_cmds.h" #include "./mavlink_msg_ctrl_srfc_pt.h" -#include "./mavlink_msg_pid.h" #include "./mavlink_msg_slugs_action.h" + + +// MESSAGE LENGTHS + +#undef MAVLINK_MESSAGE_LENGTHS +#define MAVLINK_MESSAGE_LENGTHS { 3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 0, 0, 0, 0, 0, 5, 5, 26, 16, 36, 5, 6, 0, 0, 21, 0, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 4, 10, 24, 18, 0, 0, 30, 24, 0, 7, 13, 3, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51 } + #ifdef __cplusplus } #endif diff --git a/libraries/GCS_MAVLink/include/ualberta/mavlink.h b/libraries/GCS_MAVLink/include/ualberta/mavlink.h index 616e9ecf7e..172cc2857a 100644 --- a/libraries/GCS_MAVLink/include/ualberta/mavlink.h +++ b/libraries/GCS_MAVLink/include/ualberta/mavlink.h @@ -1,7 +1,7 @@ /** @file * @brief MAVLink comm protocol. * @see http://pixhawk.ethz.ch/software/mavlink - * Generated on Tuesday, February 15 2011, 15:58 UTC + * Generated on Saturday, April 16 2011, 04:02 UTC */ #ifndef MAVLINK_H #define MAVLINK_H diff --git a/libraries/GCS_MAVLink/include/ualberta/ualberta.h b/libraries/GCS_MAVLink/include/ualberta/ualberta.h index d909935eec..1583d64fb5 100644 --- a/libraries/GCS_MAVLink/include/ualberta/ualberta.h +++ b/libraries/GCS_MAVLink/include/ualberta/ualberta.h @@ -1,7 +1,7 @@ /** @file * @brief MAVLink comm protocol. * @see http://pixhawk.ethz.ch/software/mavlink - * Generated on Tuesday, February 15 2011, 15:58 UTC + * Generated on Saturday, April 16 2011, 04:02 UTC */ #ifndef UALBERTA_H #define UALBERTA_H @@ -36,6 +36,13 @@ extern "C" { #include "./mavlink_msg_nav_filter_bias.h" #include "./mavlink_msg_request_rc_channels.h" #include "./mavlink_msg_radio_calibration.h" + + +// MESSAGE LENGTHS + +#undef MAVLINK_MESSAGE_LENGTHS +#define MAVLINK_MESSAGE_LENGTHS { 3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 0, 0, 0, 0, 0, 5, 5, 26, 16, 36, 5, 6, 0, 0, 21, 0, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 32, 1, 84, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51 } + #ifdef __cplusplus } #endif diff --git a/libraries/GCS_MAVLink/message_definitions/common.xml b/libraries/GCS_MAVLink/message_definitions/common.xml index bd912c7129..2a5db5f9c5 100644 --- a/libraries/GCS_MAVLink/message_definitions/common.xml +++ b/libraries/GCS_MAVLink/message_definitions/common.xml @@ -79,17 +79,7 @@ Longitude Altitude - - Set the location the system should be heading towards (camera heads or - rotary wing aircraft). - Empty - Empty - Empty - Empty - Latitude - Longitude - Altitude - + Control autonomous path planning on the MAV. 0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning @@ -260,6 +250,21 @@ Empty Empty + + + Sets the region of interest (ROI) for a sensor set or the + vehicle itself. This can then be used by the vehicles control + system to control the vehicle attitude and the attitude of various + devices such as cameras. + Region of interest mode. (see MAV_ROI enum) + Waypoint index/ target ID. (see MAV_ROI enum) + ROI index (allows a vehicle to manage multiple cameras etc.) + Empty + x the location of the fixed ROI (see MAV_FRAME) + y + z + + NOP - This command is only used to mark the upper limit of the DO commands in the enumeration Empty @@ -306,6 +311,19 @@ Dependent on the autopilot Dependent on the autopilot + + + The ROI (region of interest) for the vehicle. This can be + be used by the vehicle for camera/vehicle attitude alignment (see + MAV_CMD_DO_SET_ROI). + + No region of interest. + Point toward next waypoint. + Point toward given waypoint. + Point toward fixed location. + Point toward target of given id. + + @@ -468,14 +486,23 @@ NOT the global position estimate of the sytem, but rather a RAW sensor value. Se - The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, unscaled ADC values. + The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Absolute pressure (raw) + Differential pressure 1 (raw) + Differential pressure 2 (raw) + Raw Temperature measurement (raw) + + + + The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field. Timestamp (microseconds since UNIX epoch or microseconds since system boot) Absolute pressure (hectopascal) - Differential pressure 1 (hectopascal) - Differential pressure 2 (hectopascal) - Raw Temperature measurement (0.01 degrees celsius per tick is default unit) + Differential pressure 1 (hectopascal) + Temperature measurement (0.01 degrees celsius) + The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right). Timestamp (microseconds since UNIX epoch or microseconds since system boot) @@ -498,6 +525,7 @@ NOT the global position estimate of the sytem, but rather a RAW sensor value. Se Z Speed + The filtered global position (e.g. fused GPS and accelerometers). Coordinate frame is right-handed, Z-axis up (GPS frame) Timestamp (microseconds since unix epoch) @@ -645,9 +673,9 @@ NOT the global position estimate of the sytem, but rather a RAW sensor value. Se As local waypoints exist, the global waypoint reference allows to transform between the local coordinate frame and the global (GPS) coordinate frame. This can be necessary when e.g. in- and outdoor settings are connected and the MAV should move from in- to outdoor. System ID Component ID - global position * 1E7 - global position * 1E7 - global position * 1000 + global position * 1E7 + global position * 1E7 + global position * 1000 diff --git a/libraries/GCS_MAVLink/message_definitions/slugs.xml b/libraries/GCS_MAVLink/message_definitions/slugs.xml index d51fd46122..6de0697fef 100644 --- a/libraries/GCS_MAVLink/message_definitions/slugs.xml +++ b/libraries/GCS_MAVLink/message_definitions/slugs.xml @@ -69,29 +69,6 @@ Diagnostic short 2 Diagnostic short 3 - - - Pilot console PWM messges. - Pilot's console throttle command - Pilot's console left aileron command - Pilot's console right aileron command - Pilot's console rudder command - Pilot's console elevator command - - - - PWM Commands from the AP to the control surfaces. - AutoPilot's throttle command - AutoPilot's left aileron command - AutoPilot's right aileron command - AutoPilot's rudder command - AutoPilot's left elevator command - AutoPilot's right elevator command - AutoPilot's left flap command - AutoPilot's right flap command - AutoPilot's aux1 command - AutoPilot's aux2 command - Data used in the navigation algorithm. @@ -116,19 +93,6 @@ Log value 6 - - Measured value from the IMU in units after sensor calibration and temperature compensation. Note that this IS NOT the output of the attitude filter, for that see messages 30 and 33. - Accelerometer X value (m/s^2) - Accelerometer Y value (m/s^2) - Accelerometer Z value (m/s^2) - Gyro X value (rad/s) - Gyro Y value (rad/s) - Gyro Z value (rad/s) - Magnetometer X (normalized to 1) - Magnetometer Y (normalized to 1) - Magnetometer Z (normalized to 1) - - Pilot console PWM messges. Year reported by Gps @@ -166,14 +130,6 @@ This message configures the Selective Passthrough mode. it allows to select whic Bitfield containing the PT configuration - - Configure a PID loop. - The system setting the PID values - Proportional gain - Integral gain - Derivative gain - PID loop index - Action messages focused on the SLUGS AP. diff --git a/libraries/GCS_MAVLink/sync b/libraries/GCS_MAVLink/sync index 4d813794c1..1d94af457c 100755 --- a/libraries/GCS_MAVLink/sync +++ b/libraries/GCS_MAVLink/sync @@ -1,7 +1,11 @@ #!/bin/sh +branch="roi" +# temporarily using roi branch instead of master +# this branch will be deleted soon so switch it back +# to master then trap exit ERR rm -rf _tmp -git clone git://github.com/pixhawk/mavlink.git -b dev _tmp +git clone git://github.com/pixhawk/mavlink.git -b roi _tmp rm -rf _tmp/.git rsync -av _tmp/* . rm -rf _tmp