Commit 05143aa7 authored by LM's avatar LM

Updated bundled MAVLink version to latest v10 draft

parent 20c26218
This diff is collapsed.
......@@ -4,20 +4,20 @@
typedef struct __mavlink_command_ack_t
{
float command; ///< Current airspeed in m/s
float result; ///< 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
uint16_t command; ///< Command ID, as defined by MAV_CMD enum.
uint8_t result; ///< 1: Command ACCEPTED and EXECUTED, 1: Command TEMPORARY REJECTED/DENIED, 2: Command PERMANENTLY DENIED, 3: Command UNKNOWN/UNSUPPORTED, 4: Command executed, but failed
} mavlink_command_ack_t;
#define MAVLINK_MSG_ID_COMMAND_ACK_LEN 8
#define MAVLINK_MSG_ID_77_LEN 8
#define MAVLINK_MSG_ID_COMMAND_ACK_LEN 3
#define MAVLINK_MSG_ID_77_LEN 3
#define MAVLINK_MESSAGE_INFO_COMMAND_ACK { \
"COMMAND_ACK", \
2, \
{ { "command", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_ack_t, command) }, \
{ "result", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_ack_t, result) }, \
{ { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_command_ack_t, command) }, \
{ "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_ack_t, result) }, \
} \
}
......@@ -28,29 +28,29 @@ typedef struct __mavlink_command_ack_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param command Current airspeed in m/s
* @param result 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
* @param command Command ID, as defined by MAV_CMD enum.
* @param result 1: Command ACCEPTED and EXECUTED, 1: Command TEMPORARY REJECTED/DENIED, 2: Command PERMANENTLY DENIED, 3: Command UNKNOWN/UNSUPPORTED, 4: Command executed, but failed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float command, float result)
uint16_t command, uint8_t result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_float(buf, 0, command);
_mav_put_float(buf, 4, result);
char buf[3];
_mav_put_uint16_t(buf, 0, command);
_mav_put_uint8_t(buf, 2, result);
memcpy(_MAV_PAYLOAD(msg), buf, 8);
memcpy(_MAV_PAYLOAD(msg), buf, 3);
#else
mavlink_command_ack_t packet;
packet.command = command;
packet.result = result;
memcpy(_MAV_PAYLOAD(msg), &packet, 8);
memcpy(_MAV_PAYLOAD(msg), &packet, 3);
#endif
msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK;
return mavlink_finalize_message(msg, system_id, component_id, 8, 8);
return mavlink_finalize_message(msg, system_id, component_id, 3, 143);
}
/**
......@@ -59,30 +59,30 @@ static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t c
* @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 command Current airspeed in m/s
* @param result 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
* @param command Command ID, as defined by MAV_CMD enum.
* @param result 1: Command ACCEPTED and EXECUTED, 1: Command TEMPORARY REJECTED/DENIED, 2: Command PERMANENTLY DENIED, 3: Command UNKNOWN/UNSUPPORTED, 4: Command executed, but failed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float command,float result)
uint16_t command,uint8_t result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_float(buf, 0, command);
_mav_put_float(buf, 4, result);
char buf[3];
_mav_put_uint16_t(buf, 0, command);
_mav_put_uint8_t(buf, 2, result);
memcpy(_MAV_PAYLOAD(msg), buf, 8);
memcpy(_MAV_PAYLOAD(msg), buf, 3);
#else
mavlink_command_ack_t packet;
packet.command = command;
packet.result = result;
memcpy(_MAV_PAYLOAD(msg), &packet, 8);
memcpy(_MAV_PAYLOAD(msg), &packet, 3);
#endif
msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8, 8);
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 143);
}
/**
......@@ -102,25 +102,25 @@ static inline uint16_t mavlink_msg_command_ack_encode(uint8_t system_id, uint8_t
* @brief Send a command_ack message
* @param chan MAVLink channel to send the message
*
* @param command Current airspeed in m/s
* @param result 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
* @param command Command ID, as defined by MAV_CMD enum.
* @param result 1: Command ACCEPTED and EXECUTED, 1: Command TEMPORARY REJECTED/DENIED, 2: Command PERMANENTLY DENIED, 3: Command UNKNOWN/UNSUPPORTED, 4: Command executed, but failed
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, float command, float result)
static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, uint16_t command, uint8_t result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_float(buf, 0, command);
_mav_put_float(buf, 4, result);
char buf[3];
_mav_put_uint16_t(buf, 0, command);
_mav_put_uint8_t(buf, 2, result);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, 8, 8);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, 3, 143);
#else
mavlink_command_ack_t packet;
packet.command = command;
packet.result = result;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)&packet, 8, 8);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)&packet, 3, 143);
#endif
}
......@@ -132,21 +132,21 @@ static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, float co
/**
* @brief Get field command from command_ack message
*
* @return Current airspeed in m/s
* @return Command ID, as defined by MAV_CMD enum.
*/
static inline float mavlink_msg_command_ack_get_command(const mavlink_message_t* msg)
static inline uint16_t mavlink_msg_command_ack_get_command(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Get field result from command_ack message
*
* @return 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
* @return 1: Command ACCEPTED and EXECUTED, 1: Command TEMPORARY REJECTED/DENIED, 2: Command PERMANENTLY DENIED, 3: Command UNKNOWN/UNSUPPORTED, 4: Command executed, but failed
*/
static inline float mavlink_msg_command_ack_get_result(const mavlink_message_t* msg)
static inline uint8_t mavlink_msg_command_ack_get_result(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
return _MAV_RETURN_uint8_t(msg, 2);
}
/**
......@@ -161,6 +161,6 @@ static inline void mavlink_msg_command_ack_decode(const mavlink_message_t* msg,
command_ack->command = mavlink_msg_command_ack_get_command(msg);
command_ack->result = mavlink_msg_command_ack_get_result(msg);
#else
memcpy(command_ack, _MAV_PAYLOAD(msg), 8);
memcpy(command_ack, _MAV_PAYLOAD(msg), 3);
#endif
}
// MESSAGE GLOBAL_VISION_POSITION_ESTIMATE PACKING
#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE 101
typedef struct __mavlink_global_vision_position_estimate_t
{
uint64_t usec; ///< Timestamp (milliseconds)
float x; ///< Global X position
float y; ///< Global Y position
float z; ///< Global Z position
float roll; ///< Roll angle in rad
float pitch; ///< Pitch angle in rad
float yaw; ///< Yaw angle in rad
} mavlink_global_vision_position_estimate_t;
#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN 32
#define MAVLINK_MSG_ID_101_LEN 32
#define MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE { \
"GLOBAL_VISION_POSITION_ESTIMATE", \
7, \
{ { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_vision_position_estimate_t, usec) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_global_vision_position_estimate_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_global_vision_position_estimate_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_global_vision_position_estimate_t, z) }, \
{ "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_global_vision_position_estimate_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_vision_position_estimate_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_vision_position_estimate_t, yaw) }, \
} \
}
/**
* @brief Pack a global_vision_position_estimate 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 (milliseconds)
* @param x Global X position
* @param y Global Y position
* @param z Global Z position
* @param roll Roll angle in rad
* @param pitch Pitch angle in rad
* @param yaw Yaw angle in rad
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_vision_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, x);
_mav_put_float(buf, 12, y);
_mav_put_float(buf, 16, z);
_mav_put_float(buf, 20, roll);
_mav_put_float(buf, 24, pitch);
_mav_put_float(buf, 28, yaw);
memcpy(_MAV_PAYLOAD(msg), buf, 32);
#else
mavlink_global_vision_position_estimate_t packet;
packet.usec = usec;
packet.x = x;
packet.y = y;
packet.z = z;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
memcpy(_MAV_PAYLOAD(msg), &packet, 32);
#endif
msg->msgid = MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE;
return mavlink_finalize_message(msg, system_id, component_id, 32, 102);
}
/**
* @brief Pack a global_vision_position_estimate message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (milliseconds)
* @param x Global X position
* @param y Global Y position
* @param z Global Z position
* @param roll Roll angle in rad
* @param pitch Pitch angle in rad
* @param yaw Yaw angle in rad
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t usec,float x,float y,float z,float roll,float pitch,float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, x);
_mav_put_float(buf, 12, y);
_mav_put_float(buf, 16, z);
_mav_put_float(buf, 20, roll);
_mav_put_float(buf, 24, pitch);
_mav_put_float(buf, 28, yaw);
memcpy(_MAV_PAYLOAD(msg), buf, 32);
#else
mavlink_global_vision_position_estimate_t packet;
packet.usec = usec;
packet.x = x;
packet.y = y;
packet.z = z;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
memcpy(_MAV_PAYLOAD(msg), &packet, 32);
#endif
msg->msgid = MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 102);
}
/**
* @brief Encode a global_vision_position_estimate 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 global_vision_position_estimate C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_global_vision_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_vision_position_estimate_t* global_vision_position_estimate)
{
return mavlink_msg_global_vision_position_estimate_pack(system_id, component_id, msg, global_vision_position_estimate->usec, global_vision_position_estimate->x, global_vision_position_estimate->y, global_vision_position_estimate->z, global_vision_position_estimate->roll, global_vision_position_estimate->pitch, global_vision_position_estimate->yaw);
}
/**
* @brief Send a global_vision_position_estimate message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (milliseconds)
* @param x Global X position
* @param y Global Y position
* @param z Global Z position
* @param roll Roll angle in rad
* @param pitch Pitch angle in rad
* @param yaw Yaw angle in rad
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_global_vision_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, x);
_mav_put_float(buf, 12, y);
_mav_put_float(buf, 16, z);
_mav_put_float(buf, 20, roll);
_mav_put_float(buf, 24, pitch);
_mav_put_float(buf, 28, yaw);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, 32, 102);
#else
mavlink_global_vision_position_estimate_t packet;
packet.usec = usec;
packet.x = x;
packet.y = y;
packet.z = z;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)&packet, 32, 102);
#endif
}
#endif
// MESSAGE GLOBAL_VISION_POSITION_ESTIMATE UNPACKING
/**
* @brief Get field usec from global_vision_position_estimate message
*
* @return Timestamp (milliseconds)
*/
static inline uint64_t mavlink_msg_global_vision_position_estimate_get_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field x from global_vision_position_estimate message
*
* @return Global X position
*/
static inline float mavlink_msg_global_vision_position_estimate_get_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field y from global_vision_position_estimate message
*
* @return Global Y position
*/
static inline float mavlink_msg_global_vision_position_estimate_get_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field z from global_vision_position_estimate message
*
* @return Global Z position
*/
static inline float mavlink_msg_global_vision_position_estimate_get_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field roll from global_vision_position_estimate message
*
* @return Roll angle in rad
*/
static inline float mavlink_msg_global_vision_position_estimate_get_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field pitch from global_vision_position_estimate message
*
* @return Pitch angle in rad
*/
static inline float mavlink_msg_global_vision_position_estimate_get_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field yaw from global_vision_position_estimate message
*
* @return Yaw angle in rad
*/
static inline float mavlink_msg_global_vision_position_estimate_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Decode a global_vision_position_estimate message into a struct
*
* @param msg The message to decode
* @param global_vision_position_estimate C-struct to decode the message contents into
*/
static inline void mavlink_msg_global_vision_position_estimate_decode(const mavlink_message_t* msg, mavlink_global_vision_position_estimate_t* global_vision_position_estimate)
{
#if MAVLINK_NEED_BYTE_SWAP
global_vision_position_estimate->usec = mavlink_msg_global_vision_position_estimate_get_usec(msg);
global_vision_position_estimate->x = mavlink_msg_global_vision_position_estimate_get_x(msg);
global_vision_position_estimate->y = mavlink_msg_global_vision_position_estimate_get_y(msg);
global_vision_position_estimate->z = mavlink_msg_global_vision_position_estimate_get_z(msg);
global_vision_position_estimate->roll = mavlink_msg_global_vision_position_estimate_get_roll(msg);
global_vision_position_estimate->pitch = mavlink_msg_global_vision_position_estimate_get_pitch(msg);
global_vision_position_estimate->yaw = mavlink_msg_global_vision_position_estimate_get_yaw(msg);
#else
memcpy(global_vision_position_estimate, _MAV_PAYLOAD(msg), 32);
#endif
}
// MESSAGE VICON_POSITION_ESTIMATE PACKING
#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE 157
#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE 104
typedef struct __mavlink_vicon_position_estimate_t
{
......@@ -14,7 +14,7 @@ typedef struct __mavlink_vicon_position_estimate_t
} mavlink_vicon_position_estimate_t;
#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN 32
#define MAVLINK_MSG_ID_157_LEN 32
#define MAVLINK_MSG_ID_104_LEN 32
......
// MESSAGE VISION_POSITION_ESTIMATE PACKING
#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE 156
#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE 102
typedef struct __mavlink_vision_position_estimate_t
{
......@@ -14,7 +14,7 @@ typedef struct __mavlink_vision_position_estimate_t
} mavlink_vision_position_estimate_t;
#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN 32
#define MAVLINK_MSG_ID_156_LEN 32
#define MAVLINK_MSG_ID_102_LEN 32
......
// MESSAGE VISION_SPEED_ESTIMATE PACKING
#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE 158
#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE 103
typedef struct __mavlink_vision_speed_estimate_t
{
......@@ -11,7 +11,7 @@ typedef struct __mavlink_vision_speed_estimate_t
} mavlink_vision_speed_estimate_t;
#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN 20
#define MAVLINK_MSG_ID_158_LEN 20
#define MAVLINK_MSG_ID_103_LEN 20
......
......@@ -5,8 +5,8 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Sun Sep 18 11:48:20 2011"
#define MAVLINK_BUILD_DATE "Mon Oct 10 15:56:56 2011"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
#endif // MAVLINK_VERSION_H
......@@ -272,165 +272,6 @@ static void mavlink_test_image_available(uint8_t system_id, uint8_t component_id
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_vision_position_estimate(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_vision_position_estimate_t packet_in = {
93372036854775807ULL,
73.0,
101.0,
129.0,
157.0,
185.0,
213.0,
};
mavlink_vision_position_estimate_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.usec = packet_in.usec;
packet1.x = packet_in.x;
packet1.y = packet_in.y;
packet1.z = packet_in.z;
packet1.roll = packet_in.roll;
packet1.pitch = packet_in.pitch;
packet1.yaw = packet_in.yaw;
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vision_position_estimate_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_vision_position_estimate_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vision_position_estimate_pack(system_id, component_id, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
mavlink_msg_vision_position_estimate_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vision_position_estimate_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
mavlink_msg_vision_position_estimate_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_vision_position_estimate_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vision_position_estimate_send(MAVLINK_COMM_1 , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
mavlink_msg_vision_position_estimate_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_vicon_position_estimate(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_vicon_position_estimate_t packet_in = {
93372036854775807ULL,
73.0,
101.0,
129.0,
157.0,
185.0,
213.0,
};
mavlink_vicon_position_estimate_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.usec = packet_in.usec;
packet1.x = packet_in.x;
packet1.y = packet_in.y;
packet1.z = packet_in.z;
packet1.roll = packet_in.roll;
packet1.pitch = packet_in.pitch;
packet1.yaw = packet_in.yaw;
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vicon_position_estimate_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_vicon_position_estimate_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vicon_position_estimate_pack(system_id, component_id, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
mavlink_msg_vicon_position_estimate_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vicon_position_estimate_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
mavlink_msg_vicon_position_estimate_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_vicon_position_estimate_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vicon_position_estimate_send(MAVLINK_COMM_1 , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
mavlink_msg_vicon_position_estimate_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_vision_speed_estimate(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_vision_speed_estimate_t packet_in = {
93372036854775807ULL,
73.0,
101.0,
129.0,
};
mavlink_vision_speed_estimate_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.usec = packet_in.usec;
packet1.x = packet_in.x;
packet1.y = packet_in.y;
packet1.z = packet_in.z;
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vision_speed_estimate_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_vision_speed_estimate_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vision_speed_estimate_pack(system_id, component_id, &msg , packet1.usec , packet1.x , packet1.y , packet1.z );
mavlink_msg_vision_speed_estimate_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vision_speed_estimate_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.x , packet1.y , packet1.z );
mavlink_msg_vision_speed_estimate_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_vision_speed_estimate_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vision_speed_estimate_send(MAVLINK_COMM_1 , packet1.usec , packet1.x , packet1.y , packet1.z );
mavlink_msg_vision_speed_estimate_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_position_control_setpoint_set(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
......@@ -1285,9 +1126,6 @@ static void mavlink_test_pixhawk(uint8_t system_id, uint8_t component_id, mavlin
mavlink_test_image_triggered(system_id, component_id, last_msg);
mavlink_test_image_trigger_control(system_id, component_id, last_msg);
mavlink_test_image_available(system_id, component_id, last_msg);
mavlink_test_vision_position_estimate(system_id, component_id, last_msg);
mavlink_test_vicon_position_estimate(system_id, component_id, last_msg);
mavlink_test_vision_speed_estimate(system_id, component_id, last_msg);
mavlink_test_position_control_setpoint_set(system_id, component_id, last_msg);
mavlink_test_position_control_offset_set(system_id, component_id, last_msg);
mavlink_test_position_control_setpoint(system_id, component_id, last_msg);
......
......@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Sun Sep 18 11:47:55 2011"
#define MAVLINK_BUILD_DATE "Mon Oct 10 15:56:56 2011"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
......
......@@ -97,7 +97,21 @@
<description>Eighth bit: 00000001</description>
</entry>
</enum>
<enum name="MAV_GOTO">
<description>Override command, pauses current mission execution and moves immediately to a position</description>
<entry value="0" name="MAV_GOTO_DO_HOLD">
<description>Hold at the current position.</description>
</entry>
<entry value="0" name="MAV_GOTO_DO_CONTINUE">
<description>Continue with the mission execution.</description>
</entry>
<entry value="0" name="MAV_GOTO_HOLD_AT_CURRENT_POSITION">
<description>Hold at the current position of the system</description>
</entry>
<entry value="0" name="MAV_GOTO_HOLD_AT_SPECIFIED_POSITION">
<description>Hold at the position specified in the parameters of the DO_HOLD action</description>
</entry>
</enum>
<enum name="MAV_MODE">
<description>These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it
simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override.</description>
......@@ -215,6 +229,9 @@
</entry>
</enum>
<enum name="MAV_COMPONENT">
<entry value="0" name="MAV_COMP_ID_ALL">
<description/>
</entry>
<entry value="220" name="MAV_COMP_ID_GPS">
<description/>
</entry>
......@@ -627,6 +644,26 @@
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="246" name="MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN">
<description>Request the reboot or shutdown of system components.</description>
<param index="1">0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.</param>
<param index="2">0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.</param>
<param index="3">Reserved</param>
<param index="4">Reserved</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="252" name="MAV_CMD_OVERRIDE_GOTO">
<description>Hold / continue the current action</description>
<param index="1">MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with mission plan</param>
<param index="2">MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position</param>
<param index="3">MAV_FRAME coordinate frame of hold point</param>
<param index="4">Desired yaw angle in degrees</param>
<param index="5">Latitude / X position</param>
<param index="6">Longitude / Y position</param>
<param index="7">Altitude / Z position</param>
</entry>
</enum>
<enum name="MAV_DATA_STREAM">
<description>Data stream IDs. A data stream is not a fixed set of messages, but rather a
......@@ -1214,8 +1251,8 @@
</message>
<message id="77" name="COMMAND_ACK">
<description>Report status of a command. Includes feedback wether the command was executed</description>
<field type="float" name="command">Current airspeed in m/s</field>
<field type="float" name="result">1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION</field>
<field type="uint16_t" name="command">Command ID, as defined by MAV_CMD enum.</field>
<field type="uint8_t" name="result">1: Command ACCEPTED and EXECUTED, 1: Command TEMPORARY REJECTED/DENIED, 2: Command PERMANENTLY DENIED, 3: Command UNKNOWN/UNSUPPORTED, 4: Command executed, but failed</field>
</message>
<!--
......@@ -1315,6 +1352,39 @@
<field type="uint8_t" name="quality">Optical flow quality / confidence. 0: bad, 255: maximum quality</field>
<field type="float" name="ground_distance">Ground distance in meters</field>
</message>
<message id="101" name="GLOBAL_VISION_POSITION_ESTIMATE">
<field type="uint64_t" name="usec">Timestamp (milliseconds)</field>
<field type="float" name="x">Global X position</field>
<field type="float" name="y">Global Y position</field>
<field type="float" name="z">Global Z position</field>
<field type="float" name="roll">Roll angle in rad</field>
<field type="float" name="pitch">Pitch angle in rad</field>
<field type="float" name="yaw">Yaw angle in rad</field>
</message>
<message id="102" name="VISION_POSITION_ESTIMATE">
<field type="uint64_t" name="usec">Timestamp (milliseconds)</field>
<field type="float" name="x">Global X position</field>
<field type="float" name="y">Global Y position</field>
<field type="float" name="z">Global Z position</field>
<field type="float" name="roll">Roll angle in rad</field>
<field type="float" name="pitch">Pitch angle in rad</field>
<field type="float" name="yaw">Yaw angle in rad</field>
</message>
<message id="103" name="VISION_SPEED_ESTIMATE">
<field type="uint64_t" name="usec">Timestamp (milliseconds)</field>
<field type="float" name="x">Global X speed</field>
<field type="float" name="y">Global Y speed</field>
<field type="float" name="z">Global Z speed</field>
</message>
<message id="104" name="VICON_POSITION_ESTIMATE">
<field type="uint64_t" name="usec">Timestamp (milliseconds)</field>
<field type="float" name="x">Global X position</field>
<field type="float" name="y">Global Y position</field>
<field type="float" name="z">Global Z position</field>
<field type="float" name="roll">Roll angle in rad</field>
<field type="float" name="pitch">Pitch angle in rad</field>
<field type="float" name="yaw">Yaw angle in rad</field>
</message>
<!-- MESSAGE IDs 150 - 240: Space for custom messages in individual projectname_messages.xml files -->
<message id="249" name="MEMORY_VECT">
<description>Send raw controller memory. 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>
......
......@@ -60,30 +60,6 @@
<field type="float" name="ground_y">Ground truth Y</field>
<field type="float" name="ground_z">Ground truth Z</field>
</message>
<message id="156" name="VISION_POSITION_ESTIMATE">
<field type="uint64_t" name="usec">Timestamp (milliseconds)</field>
<field type="float" name="x">Global X position</field>
<field type="float" name="y">Global Y position</field>
<field type="float" name="z">Global Z position</field>
<field type="float" name="roll">Roll angle in rad</field>
<field type="float" name="pitch">Pitch angle in rad</field>
<field type="float" name="yaw">Yaw angle in rad</field>
</message>
<message id="157" name="VICON_POSITION_ESTIMATE">
<field type="uint64_t" name="usec">Timestamp (milliseconds)</field>
<field type="float" name="x">Global X position</field>
<field type="float" name="y">Global Y position</field>
<field type="float" name="z">Global Z position</field>
<field type="float" name="roll">Roll angle in rad</field>
<field type="float" name="pitch">Pitch angle in rad</field>
<field type="float" name="yaw">Yaw angle in rad</field>
</message>
<message id="158" name="VISION_SPEED_ESTIMATE">
<field type="uint64_t" name="usec">Timestamp (milliseconds)</field>
<field type="float" name="x">Global X speed</field>
<field type="float" name="y">Global Y speed</field>
<field type="float" name="z">Global Z speed</field>
</message>
<message id="159" name="POSITION_CONTROL_SETPOINT_SET">
<description>Message sent to the MAV to set a new position as reference for the controller</description>
<field type="uint8_t" name="target_system">System ID</field>
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment