GCS_MAVLink: regenerate MAVLink headers

This commit is contained in:
Andrew Tridgell 2014-02-14 21:32:19 +11:00
parent 0cbd5a2ef0
commit 8797f38038
7 changed files with 294 additions and 9 deletions

File diff suppressed because one or more lines are too long

View File

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Sun Dec 15 15:38:31 2013"
#define MAVLINK_BUILD_DATE "Fri Feb 14 21:31:46 2014"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254

File diff suppressed because one or more lines are too long

View File

@ -0,0 +1,221 @@
// MESSAGE POWER_STATUS PACKING
#define MAVLINK_MSG_ID_POWER_STATUS 125
typedef struct __mavlink_power_status_t
{
uint16_t Vcc; ///< 5V rail voltage in millivolts
uint16_t Vservo; ///< servo rail voltage in millivolts
uint16_t flags; ///< power supply status flags (see MAV_POWER_STATUS enum)
} mavlink_power_status_t;
#define MAVLINK_MSG_ID_POWER_STATUS_LEN 6
#define MAVLINK_MSG_ID_125_LEN 6
#define MAVLINK_MSG_ID_POWER_STATUS_CRC 203
#define MAVLINK_MSG_ID_125_CRC 203
#define MAVLINK_MESSAGE_INFO_POWER_STATUS { \
"POWER_STATUS", \
3, \
{ { "Vcc", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_power_status_t, Vcc) }, \
{ "Vservo", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_power_status_t, Vservo) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_power_status_t, flags) }, \
} \
}
/**
* @brief Pack a power_status 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 Vcc 5V rail voltage in millivolts
* @param Vservo servo rail voltage in millivolts
* @param flags power supply status flags (see MAV_POWER_STATUS enum)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_power_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t Vcc, uint16_t Vservo, uint16_t flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_POWER_STATUS_LEN];
_mav_put_uint16_t(buf, 0, Vcc);
_mav_put_uint16_t(buf, 2, Vservo);
_mav_put_uint16_t(buf, 4, flags);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POWER_STATUS_LEN);
#else
mavlink_power_status_t packet;
packet.Vcc = Vcc;
packet.Vservo = Vservo;
packet.flags = flags;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POWER_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_POWER_STATUS;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POWER_STATUS_LEN);
#endif
}
/**
* @brief Pack a power_status 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param Vcc 5V rail voltage in millivolts
* @param Vservo servo rail voltage in millivolts
* @param flags power supply status flags (see MAV_POWER_STATUS enum)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_power_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t Vcc,uint16_t Vservo,uint16_t flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_POWER_STATUS_LEN];
_mav_put_uint16_t(buf, 0, Vcc);
_mav_put_uint16_t(buf, 2, Vservo);
_mav_put_uint16_t(buf, 4, flags);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POWER_STATUS_LEN);
#else
mavlink_power_status_t packet;
packet.Vcc = Vcc;
packet.Vservo = Vservo;
packet.flags = flags;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POWER_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_POWER_STATUS;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POWER_STATUS_LEN);
#endif
}
/**
* @brief Encode a power_status struct
*
* @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 power_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_power_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_power_status_t* power_status)
{
return mavlink_msg_power_status_pack(system_id, component_id, msg, power_status->Vcc, power_status->Vservo, power_status->flags);
}
/**
* @brief Encode a power_status struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param power_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_power_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_power_status_t* power_status)
{
return mavlink_msg_power_status_pack_chan(system_id, component_id, chan, msg, power_status->Vcc, power_status->Vservo, power_status->flags);
}
/**
* @brief Send a power_status message
* @param chan MAVLink channel to send the message
*
* @param Vcc 5V rail voltage in millivolts
* @param Vservo servo rail voltage in millivolts
* @param flags power supply status flags (see MAV_POWER_STATUS enum)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_power_status_send(mavlink_channel_t chan, uint16_t Vcc, uint16_t Vservo, uint16_t flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_POWER_STATUS_LEN];
_mav_put_uint16_t(buf, 0, Vcc);
_mav_put_uint16_t(buf, 2, Vservo);
_mav_put_uint16_t(buf, 4, flags);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_LEN);
#endif
#else
mavlink_power_status_t packet;
packet.Vcc = Vcc;
packet.Vservo = Vservo;
packet.flags = flags;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)&packet, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)&packet, MAVLINK_MSG_ID_POWER_STATUS_LEN);
#endif
#endif
}
#endif
// MESSAGE POWER_STATUS UNPACKING
/**
* @brief Get field Vcc from power_status message
*
* @return 5V rail voltage in millivolts
*/
static inline uint16_t mavlink_msg_power_status_get_Vcc(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Get field Vservo from power_status message
*
* @return servo rail voltage in millivolts
*/
static inline uint16_t mavlink_msg_power_status_get_Vservo(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
/**
* @brief Get field flags from power_status message
*
* @return power supply status flags (see MAV_POWER_STATUS enum)
*/
static inline uint16_t mavlink_msg_power_status_get_flags(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
/**
* @brief Decode a power_status message into a struct
*
* @param msg The message to decode
* @param power_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_power_status_decode(const mavlink_message_t* msg, mavlink_power_status_t* power_status)
{
#if MAVLINK_NEED_BYTE_SWAP
power_status->Vcc = mavlink_msg_power_status_get_Vcc(msg);
power_status->Vservo = mavlink_msg_power_status_get_Vservo(msg);
power_status->flags = mavlink_msg_power_status_get_flags(msg);
#else
memcpy(power_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_POWER_STATUS_LEN);
#endif
}

View File

@ -4839,6 +4839,53 @@ static void mavlink_test_log_request_end(uint8_t system_id, uint8_t component_id
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_power_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_power_status_t packet_in = {
17235,
}17339,
}17443,
};
mavlink_power_status_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.Vcc = packet_in.Vcc;
packet1.Vservo = packet_in.Vservo;
packet1.flags = packet_in.flags;
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_power_status_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_power_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_power_status_pack(system_id, component_id, &msg , packet1.Vcc , packet1.Vservo , packet1.flags );
mavlink_msg_power_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_power_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.Vcc , packet1.Vservo , packet1.flags );
mavlink_msg_power_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_power_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_power_status_send(MAVLINK_COMM_1 , packet1.Vcc , packet1.Vservo , packet1.flags );
mavlink_msg_power_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_battery_status(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
@ -5393,6 +5440,7 @@ static void mavlink_test_common(uint8_t system_id, uint8_t component_id, mavlink
mavlink_test_log_data(system_id, component_id, last_msg);
mavlink_test_log_erase(system_id, component_id, last_msg);
mavlink_test_log_request_end(system_id, component_id, last_msg);
mavlink_test_power_status(system_id, component_id, last_msg);
mavlink_test_battery_status(system_id, component_id, last_msg);
mavlink_test_setpoint_8dof(system_id, component_id, last_msg);
mavlink_test_setpoint_6dof(system_id, component_id, last_msg);

View File

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Sun Dec 15 15:38:31 2013"
#define MAVLINK_BUILD_DATE "Fri Feb 14 21:31:46 2014"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254

View File

@ -48,7 +48,7 @@ typedef struct __mavlink_system {
uint8_t type; ///< Unused, can be used by user to store the system's type
uint8_t state; ///< Unused, can be used by user to store the system's state
uint8_t mode; ///< Unused, can be used by user to store the system's mode
uint8_t nav_mode; ///< Unused, can be used by user to store the system's navigation mode
uint32_t nav_mode; ///< Unused, can be used by user to store the system's navigation mode
} mavlink_system_t;
typedef struct __mavlink_message {