Mavlink update

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1555 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
mich146@hotmail.com 2011-01-25 00:31:38 +00:00
parent c18fd76449
commit 000eaf6a68
9 changed files with 309 additions and 29 deletions

View File

@ -1,7 +1,7 @@
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Friday, January 7 2011, 10:04 UTC
* Generated on Sunday, January 23 2011, 16:32 UTC
*/
#ifndef COMMON_H
#define COMMON_H
@ -78,6 +78,8 @@ extern "C" {
#include "./mavlink_msg_gps_local_origin_set.h"
#include "./mavlink_msg_airspeed.h"
#include "./mavlink_msg_global_position_int.h"
#include "./mavlink_msg_named_value_float.h"
#include "./mavlink_msg_named_value_int.h"
#include "./mavlink_msg_statustext.h"
#include "./mavlink_msg_debug.h"
#ifdef __cplusplus

View File

@ -1,7 +1,7 @@
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Friday, January 7 2011, 10:04 UTC
* Generated on Sunday, January 23 2011, 16:32 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H

View File

@ -0,0 +1,126 @@
// MESSAGE NAMED_VALUE_FLOAT PACKING
#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT 252
typedef struct __mavlink_named_value_float_t
{
char name[10]; ///< Name of the debug variable
float value; ///< Floating point value
} mavlink_named_value_float_t;
#define MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN 10
/**
* @brief Pack a named_value_float 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 name Name of the debug variable
* @param value Floating point value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_named_value_float_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const char* name, float value)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT;
i += put_array_by_index((const int8_t*)name, sizeof(char)*10, i, msg->payload); // Name of the debug variable
i += put_float_by_index(value, i, msg->payload); // Floating point value
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a named_value_float 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 name Name of the debug variable
* @param value Floating point value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_named_value_float_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const char* name, float value)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT;
i += put_array_by_index((const int8_t*)name, sizeof(char)*10, i, msg->payload); // Name of the debug variable
i += put_float_by_index(value, i, msg->payload); // Floating point value
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a named_value_float 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 named_value_float C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_named_value_float_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_float_t* named_value_float)
{
return mavlink_msg_named_value_float_pack(system_id, component_id, msg, named_value_float->name, named_value_float->value);
}
/**
* @brief Send a named_value_float message
* @param chan MAVLink channel to send the message
*
* @param name Name of the debug variable
* @param value Floating point value
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_named_value_float_send(mavlink_channel_t chan, const char* name, float value)
{
mavlink_message_t msg;
mavlink_msg_named_value_float_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, name, value);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE NAMED_VALUE_FLOAT UNPACKING
/**
* @brief Get field name from named_value_float message
*
* @return Name of the debug variable
*/
static inline uint16_t mavlink_msg_named_value_float_get_name(const mavlink_message_t* msg, char* r_data)
{
memcpy(r_data, msg->payload, sizeof(char)*10);
return sizeof(char)*10;
}
/**
* @brief Get field value from named_value_float message
*
* @return Floating point value
*/
static inline float mavlink_msg_named_value_float_get_value(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(char)*10)[0];
r.b[2] = (msg->payload+sizeof(char)*10)[1];
r.b[1] = (msg->payload+sizeof(char)*10)[2];
r.b[0] = (msg->payload+sizeof(char)*10)[3];
return (float)r.f;
}
/**
* @brief Decode a named_value_float message into a struct
*
* @param msg The message to decode
* @param named_value_float C-struct to decode the message contents into
*/
static inline void mavlink_msg_named_value_float_decode(const mavlink_message_t* msg, mavlink_named_value_float_t* named_value_float)
{
mavlink_msg_named_value_float_get_name(msg, named_value_float->name);
named_value_float->value = mavlink_msg_named_value_float_get_value(msg);
}

View File

@ -0,0 +1,126 @@
// MESSAGE NAMED_VALUE_INT PACKING
#define MAVLINK_MSG_ID_NAMED_VALUE_INT 253
typedef struct __mavlink_named_value_int_t
{
char name[10]; ///< Name of the debug variable
int32_t value; ///< Signed integer value
} mavlink_named_value_int_t;
#define MAVLINK_MSG_NAMED_VALUE_INT_FIELD_NAME_LEN 10
/**
* @brief Pack a named_value_int 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 name Name of the debug variable
* @param value Signed integer value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_named_value_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const char* name, int32_t value)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT;
i += put_array_by_index((const int8_t*)name, sizeof(char)*10, i, msg->payload); // Name of the debug variable
i += put_int32_t_by_index(value, i, msg->payload); // Signed integer value
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a named_value_int 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 name Name of the debug variable
* @param value Signed integer value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_named_value_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const char* name, int32_t value)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT;
i += put_array_by_index((const int8_t*)name, sizeof(char)*10, i, msg->payload); // Name of the debug variable
i += put_int32_t_by_index(value, i, msg->payload); // Signed integer value
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a named_value_int 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 named_value_int C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_named_value_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_int_t* named_value_int)
{
return mavlink_msg_named_value_int_pack(system_id, component_id, msg, named_value_int->name, named_value_int->value);
}
/**
* @brief Send a named_value_int message
* @param chan MAVLink channel to send the message
*
* @param name Name of the debug variable
* @param value Signed integer value
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_named_value_int_send(mavlink_channel_t chan, const char* name, int32_t value)
{
mavlink_message_t msg;
mavlink_msg_named_value_int_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, name, value);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE NAMED_VALUE_INT UNPACKING
/**
* @brief Get field name from named_value_int message
*
* @return Name of the debug variable
*/
static inline uint16_t mavlink_msg_named_value_int_get_name(const mavlink_message_t* msg, char* r_data)
{
memcpy(r_data, msg->payload, sizeof(char)*10);
return sizeof(char)*10;
}
/**
* @brief Get field value from named_value_int message
*
* @return Signed integer value
*/
static inline int32_t mavlink_msg_named_value_int_get_value(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(char)*10)[0];
r.b[2] = (msg->payload+sizeof(char)*10)[1];
r.b[1] = (msg->payload+sizeof(char)*10)[2];
r.b[0] = (msg->payload+sizeof(char)*10)[3];
return (int32_t)r.i;
}
/**
* @brief Decode a named_value_int message into a struct
*
* @param msg The message to decode
* @param named_value_int C-struct to decode the message contents into
*/
static inline void mavlink_msg_named_value_int_decode(const mavlink_message_t* msg, mavlink_named_value_int_t* named_value_int)
{
mavlink_msg_named_value_int_get_name(msg, named_value_int->name);
named_value_int->value = mavlink_msg_named_value_int_get_value(msg);
}

View File

@ -5,10 +5,10 @@
typedef struct __mavlink_raw_pressure_t
{
uint64_t usec; ///< Timestamp (microseconds since UNIX epoch)
int16_t press_abs; ///< Absolute pressure (hectopascal)
uint16_t press_abs; ///< Absolute pressure (hectopascal)
int16_t press_diff1; ///< Differential pressure 1 (hectopascal)
int16_t press_diff2; ///< Differential pressure 2 (hectopascal)
int16_t temperature; ///< Raw Temperature measurement
int16_t temperature; ///< Raw Temperature measurement (0.01 degrees celsius per tick is default unit)
} mavlink_raw_pressure_t;
@ -24,19 +24,19 @@ typedef struct __mavlink_raw_pressure_t
* @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
* @param temperature Raw Temperature measurement (0.01 degrees celsius per tick is default unit)
* @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, int16_t press_abs, int16_t press_diff1, int16_t 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, uint16_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)
i += put_int16_t_by_index(press_abs, i, msg->payload); // Absolute pressure (hectopascal)
i += put_uint16_t_by_index(press_abs, i, msg->payload); // Absolute pressure (hectopascal)
i += put_int16_t_by_index(press_diff1, i, msg->payload); // Differential pressure 1 (hectopascal)
i += put_int16_t_by_index(press_diff2, i, msg->payload); // Differential pressure 2 (hectopascal)
i += put_int16_t_by_index(temperature, i, msg->payload); // Raw Temperature measurement
i += put_int16_t_by_index(temperature, i, msg->payload); // Raw Temperature measurement (0.01 degrees celsius per tick is default unit)
return mavlink_finalize_message(msg, system_id, component_id, i);
}
@ -51,19 +51,19 @@ static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t
* @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
* @param temperature Raw Temperature measurement (0.01 degrees celsius per tick is default unit)
* @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, int16_t press_abs, int16_t press_diff1, int16_t 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, uint16_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)
i += put_int16_t_by_index(press_abs, i, msg->payload); // Absolute pressure (hectopascal)
i += put_uint16_t_by_index(press_abs, i, msg->payload); // Absolute pressure (hectopascal)
i += put_int16_t_by_index(press_diff1, i, msg->payload); // Differential pressure 1 (hectopascal)
i += put_int16_t_by_index(press_diff2, i, msg->payload); // Differential pressure 2 (hectopascal)
i += put_int16_t_by_index(temperature, i, msg->payload); // Raw Temperature measurement
i += put_int16_t_by_index(temperature, i, msg->payload); // Raw Temperature measurement (0.01 degrees celsius per tick is default unit)
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
@ -89,11 +89,11 @@ static inline uint16_t mavlink_msg_raw_pressure_encode(uint8_t system_id, uint8_
* @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
* @param temperature Raw Temperature measurement (0.01 degrees celsius per tick is default unit)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
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)
static inline void mavlink_msg_raw_pressure_send(mavlink_channel_t chan, uint64_t usec, uint16_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);
@ -127,12 +127,12 @@ static inline uint64_t mavlink_msg_raw_pressure_get_usec(const mavlink_message_t
*
* @return Absolute pressure (hectopascal)
*/
static inline int16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg)
static inline uint16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg)
{
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;
return (uint16_t)r.s;
}
/**
@ -143,8 +143,8 @@ static inline int16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_messa
static inline int16_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t* msg)
{
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];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint16_t))[0];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint16_t))[1];
return (int16_t)r.s;
}
@ -156,21 +156,21 @@ static inline int16_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_mes
static inline int16_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t* msg)
{
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];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint16_t)+sizeof(int16_t))[0];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint16_t)+sizeof(int16_t))[1];
return (int16_t)r.s;
}
/**
* @brief Get field temperature from raw_pressure message
*
* @return Raw Temperature measurement
* @return Raw Temperature measurement (0.01 degrees celsius per tick is default unit)
*/
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(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];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
return (int16_t)r.s;
}

View File

@ -46,6 +46,7 @@ enum MAV_ACTION {
MAV_ACTION_VIDEO_START = 32,
MAV_ACTION_VIDEO_STOP = 33,
MAV_ACTION_RESET_MAP = 34,
MAV_ACTION_RESET_PLAN = 35,
MAV_ACTION_NB ///< Number of MAV actions
};
@ -113,7 +114,10 @@ enum MAV_COMPONENT {
MAV_COMP_ID_PATHPLANNER,
MAV_COMP_ID_AIRSLAM,
MAV_COMP_ID_MAPPER,
MAV_COMP_ID_IMU = 200
MAV_COMP_ID_IMU = 200,
MAV_COMP_ID_UDP_BRIDGE = 240,
MAV_COMP_ID_UART_BRIDGE = 241,
MAV_COMP_ID_SYSTEM_CONTROL = 250
};
enum MAV_FRAME

View File

@ -1,7 +1,7 @@
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Friday, January 7 2011, 10:04 UTC
* Generated on Friday, January 14 2011, 17:41 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H

View File

@ -1,7 +1,7 @@
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Friday, January 7 2011, 10:04 UTC
* Generated on Friday, January 14 2011, 17:41 UTC
*/
#ifndef PIXHAWK_H
#define PIXHAWK_H

View File

@ -99,10 +99,10 @@
<message name="RAW_PRESSURE" id="29">
<description>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.</description>
<field name="usec" type="uint64_t">Timestamp (microseconds since UNIX epoch)</field>
<field name="press_abs" type="int16_t">Absolute pressure (hectopascal)</field>
<field name="press_abs" type="uint16_t">Absolute pressure (hectopascal)</field>
<field name="press_diff1" type="int16_t">Differential pressure 1 (hectopascal)</field>
<field name="press_diff2" type="int16_t">Differential pressure 2 (hectopascal)</field>
<field name="temperature" type="int16_t">Raw Temperature measurement </field>
<field name="temperature" type="int16_t">Raw Temperature measurement (0.01 degrees celsius per tick is default unit)</field>
</message>
<message name="ATTITUDE" id="30">
@ -423,16 +423,38 @@ NOT the global position estimate of the sytem, but rather a RAW sensor value. Se
<field name="vy" type="int16_t">Ground Y Speed, expressed as m/s * 100</field>
<field name="vz" type="int16_t">Ground Z Speed, expressed as m/s * 100</field>
</message>
<!-- MESSAGE IDs 80 - 250: Space for custom messages in individual projectname_messages.xml files -->
<message name="NAMED_VALUE_FLOAT" id="252">
<description>Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.</description>
<field name="name" type="char[10]">Name of the debug variable</field>
<field name="value" type="float">Floating point value</field>
</message>
<message name="NAMED_VALUE_INT" id="253">
<description>Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.</description>
<field name="name" type="char[10]">Name of the debug variable</field>
<field name="value" type="int32_t">Signed integer value</field>
</message>
<message name="STATUSTEXT" id= "254">
<description>Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz).</description>
<field name="severity" type="uint8_t">Severity of status, 0 = info message, 255 = critical fault</field>
<field name="text" type="array[50]">Status text message, without null termination character</field>
</message>
<message name="DEBUG" id="255">
<description>Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N.</description>
<field name="ind" type="uint8_t">index of debug variable</field>