MAVLink: imported updated generated mavlink C code

no functionality changes
This commit is contained in:
Andrew Tridgell 2012-07-20 11:38:04 +10:00
parent f46e8468c4
commit 151a50b6af
19 changed files with 25 additions and 150 deletions

File diff suppressed because one or more lines are too long

View File

@ -882,65 +882,6 @@ static void mavlink_test_radio(uint8_t system_id, uint8_t component_id, mavlink_
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_limits_status(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_limits_status_t packet_in = {
5,
963497516,
963497724,
963497932,
963498140,
18119,
254,
65,
132,
};
mavlink_limits_status_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.limits_state = packet_in.limits_state;
packet1.last_trigger = packet_in.last_trigger;
packet1.last_action = packet_in.last_action;
packet1.last_recovery = packet_in.last_recovery;
packet1.last_clear = packet_in.last_clear;
packet1.breach_count = packet_in.breach_count;
packet1.mods_enabled = packet_in.mods_enabled;
packet1.mods_required = packet_in.mods_required;
packet1.mods_triggered = packet_in.mods_triggered;
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_limits_status_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_limits_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_limits_status_pack(system_id, component_id, &msg , packet1.limits_state , packet1.last_trigger , packet1.last_action , packet1.last_recovery , packet1.last_clear , packet1.breach_count , packet1.mods_enabled , packet1.mods_required , packet1.mods_triggered );
mavlink_msg_limits_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_limits_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.limits_state , packet1.last_trigger , packet1.last_action , packet1.last_recovery , packet1.last_clear , packet1.breach_count , packet1.mods_enabled , packet1.mods_required , packet1.mods_triggered );
mavlink_msg_limits_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_limits_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_limits_status_send(MAVLINK_COMM_1 , packet1.limits_state , packet1.last_trigger , packet1.last_action , packet1.last_recovery , packet1.last_clear , packet1.breach_count , packet1.mods_enabled , packet1.mods_required , packet1.mods_triggered );
mavlink_msg_limits_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_ardupilotmega(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_test_sensor_offsets(system_id, component_id, last_msg);
@ -959,7 +900,6 @@ static void mavlink_test_ardupilotmega(uint8_t system_id, uint8_t component_id,
mavlink_test_simstate(system_id, component_id, last_msg);
mavlink_test_hwstatus(system_id, component_id, last_msg);
mavlink_test_radio(system_id, component_id, last_msg);
mavlink_test_limits_status(system_id, component_id, last_msg);
}
#ifdef __cplusplus

View File

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Sat Jun 23 19:58:45 2012"
#define MAVLINK_BUILD_DATE "Fri Jul 20 11:32:17 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "0.9"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101

0
libraries/GCS_MAVLink/include/mavlink/v0.9/checksum.h Executable file → Normal file
View File

View File

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Sat Jun 23 19:58:45 2012"
#define MAVLINK_BUILD_DATE "Fri Jul 20 11:32:17 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "0.9"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101

View File

@ -131,13 +131,12 @@ MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint
_mavlink_send_uart(chan, (const char *)ck, 2);
MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length);
}
#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief re-send a message over a uart channel
* this is more stack efficient than re-marshalling the message
*/
MAVLINK_HELPER void mavlink_uart_resend(mavlink_channel_t chan, const mavlink_message_t *msg)
MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg)
{
uint8_t ck[2];
@ -150,7 +149,7 @@ MAVLINK_HELPER void mavlink_uart_resend(mavlink_channel_t chan, const mavlink_me
_mavlink_send_uart(chan, (const char *)ck, 2);
MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len);
}
#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Pack a message to send it over a serial byte stream

View File

2
libraries/GCS_MAVLink/include/mavlink/v0.9/protocol.h Executable file → Normal file
View File

@ -60,7 +60,6 @@ MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t
MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length);
#endif // MAVLINK_CRC_EXTRA
MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg);
MAVLINK_HELPER void mavlink_uart_resend(mavlink_channel_t chan, const mavlink_message_t *msg);
MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg);
MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c);
MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status);
@ -68,6 +67,7 @@ MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t
uint8_t* r_bit_index, uint8_t* buffer);
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len);
MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg);
#endif
/**

View File

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Sat Jun 23 19:58:45 2012"
#define MAVLINK_BUILD_DATE "Fri Jul 20 11:32:18 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101

0
libraries/GCS_MAVLink/include/mavlink/v1.0/checksum.h Executable file → Normal file
View File

View File

@ -4,7 +4,7 @@
typedef struct __mavlink_scaled_pressure_t
{
uint32_t time_boot_ms; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
uint32_t time_boot_ms; ///< Timestamp (milliseconds 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)
@ -32,7 +32,7 @@ typedef struct __mavlink_scaled_pressure_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param press_abs Absolute pressure (hectopascal)
* @param press_diff Differential pressure 1 (hectopascal)
* @param temperature Temperature measurement (0.01 degrees celsius)
@ -69,7 +69,7 @@ static inline uint16_t mavlink_msg_scaled_pressure_pack(uint8_t system_id, uint8
* @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 time_boot_ms Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param press_abs Absolute pressure (hectopascal)
* @param press_diff Differential pressure 1 (hectopascal)
* @param temperature Temperature measurement (0.01 degrees celsius)
@ -118,7 +118,7 @@ static inline uint16_t mavlink_msg_scaled_pressure_encode(uint8_t system_id, uin
* @brief Send a scaled_pressure message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param press_abs Absolute pressure (hectopascal)
* @param press_diff Differential pressure 1 (hectopascal)
* @param temperature Temperature measurement (0.01 degrees celsius)
@ -154,7 +154,7 @@ static inline void mavlink_msg_scaled_pressure_send(mavlink_channel_t chan, uint
/**
* @brief Get field time_boot_ms from scaled_pressure message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @return Timestamp (milliseconds since system boot)
*/
static inline uint32_t mavlink_msg_scaled_pressure_get_time_boot_ms(const mavlink_message_t* msg)
{

View File

@ -4,7 +4,7 @@
typedef struct __mavlink_servo_output_raw_t
{
uint32_t time_usec; ///< Timestamp (since UNIX epoch or microseconds since system boot)
uint32_t time_usec; ///< Timestamp (microseconds since system boot)
uint16_t servo1_raw; ///< Servo output 1 value, in microseconds
uint16_t servo2_raw; ///< Servo output 2 value, in microseconds
uint16_t servo3_raw; ///< Servo output 3 value, in microseconds
@ -44,7 +44,7 @@ typedef struct __mavlink_servo_output_raw_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (since UNIX epoch or microseconds since system boot)
* @param time_usec Timestamp (microseconds since system boot)
* @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
* @param servo1_raw Servo output 1 value, in microseconds
* @param servo2_raw Servo output 2 value, in microseconds
@ -99,7 +99,7 @@ static inline uint16_t mavlink_msg_servo_output_raw_pack(uint8_t system_id, uint
* @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 time_usec Timestamp (since UNIX epoch or microseconds since system boot)
* @param time_usec Timestamp (microseconds since system boot)
* @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
* @param servo1_raw Servo output 1 value, in microseconds
* @param servo2_raw Servo output 2 value, in microseconds
@ -166,7 +166,7 @@ static inline uint16_t mavlink_msg_servo_output_raw_encode(uint8_t system_id, ui
* @brief Send a servo_output_raw message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (since UNIX epoch or microseconds since system boot)
* @param time_usec Timestamp (microseconds since system boot)
* @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
* @param servo1_raw Servo output 1 value, in microseconds
* @param servo2_raw Servo output 2 value, in microseconds
@ -220,7 +220,7 @@ static inline void mavlink_msg_servo_output_raw_send(mavlink_channel_t chan, uin
/**
* @brief Get field time_usec from servo_output_raw message
*
* @return Timestamp (since UNIX epoch or microseconds since system boot)
* @return Timestamp (microseconds since system boot)
*/
static inline uint32_t mavlink_msg_servo_output_raw_get_time_usec(const mavlink_message_t* msg)
{

View File

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Sat Jun 23 19:58:45 2012"
#define MAVLINK_BUILD_DATE "Fri Jul 20 11:32:18 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101

View File

@ -131,13 +131,12 @@ MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint
_mavlink_send_uart(chan, (const char *)ck, 2);
MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length);
}
#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief re-send a message over a uart channel
* this is more stack efficient than re-marshalling the message
*/
MAVLINK_HELPER void mavlink_uart_resend(mavlink_channel_t chan, const mavlink_message_t *msg)
MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg)
{
uint8_t ck[2];
@ -150,7 +149,7 @@ MAVLINK_HELPER void mavlink_uart_resend(mavlink_channel_t chan, const mavlink_me
_mavlink_send_uart(chan, (const char *)ck, 2);
MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len);
}
#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
/**
* @brief Pack a message to send it over a serial byte stream

View File

2
libraries/GCS_MAVLink/include/mavlink/v1.0/protocol.h Executable file → Normal file
View File

@ -60,7 +60,6 @@ MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t
MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length);
#endif // MAVLINK_CRC_EXTRA
MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg);
MAVLINK_HELPER void mavlink_uart_resend(mavlink_channel_t chan, const mavlink_message_t *msg);
MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg);
MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c);
MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status);
@ -68,6 +67,7 @@ MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t
uint8_t* r_bit_index, uint8_t* buffer);
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len);
MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg);
#endif
/**

View File

@ -93,26 +93,7 @@
<description>Breached fence boundary</description>
</entry>
</enum>
<!-- AP_Limits Enums -->
<enum name="LIMITS_STATE">
<entry name="LIMITS_INIT" value="0"> <description> pre-initialization</description></entry>
<entry name="LIMITS_DISABLED" value="1"> <description> disabled</description></entry>
<entry name="LIMITS_ENABLED" value="2"> <description> checking limits</description></entry>
<entry name="LIMITS_TRIGGERED" value="3"> <description> a limit has been breached</description></entry>
<entry name="LIMITS_RECOVERING" value="4"> <description> taking action eg. RTL</description></entry>
<entry name="LIMITS_RECOVERED" value="5"> <description> we're no longer in breach of a limit</description></entry>
</enum>
<!-- AP_Limits Modules - power of 2 (1,2,4,8,16,32 etc) so we can send as bitfield -->
<enum name="LIMIT_MODULE">
<entry name="LIMIT_GPSLOCK" value="1"> <description> pre-initialization</description></entry>
<entry name="LIMIT_GEOFENCE" value="2"> <description> disabled</description></entry>
<entry name="LIMIT_ALTITUDE" value="4"> <description> checking limits</description></entry>
</enum>
</enums>
<messages>
<message id="150" name="SENSOR_OFFSETS">
@ -285,21 +266,5 @@
<field type="uint16_t" name="rxerrors">receive errors</field>
<field type="uint16_t" name="fixed">count of error corrected packets</field>
</message>
<!-- AP_Limits messages -->
<message name="LIMITS_STATUS" id="169">
<description>Status of AP_Limits. Sent in extended
status stream when AP_Limits is enabled</description>
<field name="limits_state" type="uint8_t">state of AP_Limits, (see enum LimitState, LIMITS_STATE)</field>
<field name="last_trigger" type="uint32_t">time of last breach in milliseconds since boot</field>
<field name="last_action" type="uint32_t">time of last recovery action in milliseconds since boot</field>
<field name="last_recovery" type="uint32_t">time of last successful recovery in milliseconds since boot</field>
<field name="last_clear" type="uint32_t">time of last all-clear in milliseconds since boot</field>
<field name="breach_count" type="uint16_t">number of fence breaches</field>
<field name="mods_enabled" type="uint8_t">AP_Limit_Module bitfield of enabled modules, (see enum moduleid or LIMIT_MODULE)</field>
<field name="mods_required" type="uint8_t">AP_Limit_Module bitfield of required modules, (see enum moduleid or LIMIT_MODULE)</field>
<field name="mods_triggered" type="uint8_t">AP_Limit_Module bitfield of triggered modules, (see enum moduleid or LIMIT_MODULE)</field>
</message>
</messages>
</mavlink>

View File

@ -1018,7 +1018,7 @@
</message>
<message id="29" name="SCALED_PRESSURE">
<description>The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field.</description>
<field type="uint32_t" name="time_boot_ms">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
<field type="float" name="press_abs">Absolute pressure (hectopascal)</field>
<field type="float" name="press_diff">Differential pressure 1 (hectopascal)</field>
<field type="int16_t" name="temperature">Temperature measurement (0.01 degrees celsius)</field>
@ -1097,7 +1097,7 @@
</message>
<message id="36" name="SERVO_OUTPUT_RAW">
<description>The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%.</description>
<field type="uint32_t" name="time_usec">Timestamp (since UNIX epoch or microseconds since system boot)</field>
<field type="uint32_t" name="time_usec">Timestamp (microseconds since system boot)</field>
<field type="uint8_t" name="port">Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.</field>
<field type="uint16_t" name="servo1_raw">Servo output 1 value, in microseconds</field>
<field type="uint16_t" name="servo2_raw">Servo output 2 value, in microseconds</field>