GCS_MAVLink: regenerate headers

This commit is contained in:
Andrew Tridgell 2015-08-07 15:34:19 +10:00 committed by Randy Mackay
parent bfd409b465
commit 8efaa74b38
5 changed files with 285 additions and 6 deletions

File diff suppressed because one or more lines are too long

View File

@ -0,0 +1,233 @@
// MESSAGE RPM PACKING
#define MAVLINK_MSG_ID_RPM 226
typedef struct __mavlink_rpm_t
{
float rpm1; ///< RPM Sensor1
float rpm2; ///< RPM Sensor2
} mavlink_rpm_t;
#define MAVLINK_MSG_ID_RPM_LEN 8
#define MAVLINK_MSG_ID_226_LEN 8
#define MAVLINK_MSG_ID_RPM_CRC 207
#define MAVLINK_MSG_ID_226_CRC 207
#define MAVLINK_MESSAGE_INFO_RPM { \
"RPM", \
2, \
{ { "rpm1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_rpm_t, rpm1) }, \
{ "rpm2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_rpm_t, rpm2) }, \
} \
}
/**
* @brief Pack a rpm 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 rpm1 RPM Sensor1
* @param rpm2 RPM Sensor2
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_rpm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float rpm1, float rpm2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_RPM_LEN];
_mav_put_float(buf, 0, rpm1);
_mav_put_float(buf, 4, rpm2);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RPM_LEN);
#else
mavlink_rpm_t packet;
packet.rpm1 = rpm1;
packet.rpm2 = rpm2;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RPM_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_RPM;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RPM_LEN, MAVLINK_MSG_ID_RPM_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RPM_LEN);
#endif
}
/**
* @brief Pack a rpm 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 rpm1 RPM Sensor1
* @param rpm2 RPM Sensor2
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_rpm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float rpm1,float rpm2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_RPM_LEN];
_mav_put_float(buf, 0, rpm1);
_mav_put_float(buf, 4, rpm2);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RPM_LEN);
#else
mavlink_rpm_t packet;
packet.rpm1 = rpm1;
packet.rpm2 = rpm2;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RPM_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_RPM;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RPM_LEN, MAVLINK_MSG_ID_RPM_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RPM_LEN);
#endif
}
/**
* @brief Encode a rpm 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 rpm C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_rpm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rpm_t* rpm)
{
return mavlink_msg_rpm_pack(system_id, component_id, msg, rpm->rpm1, rpm->rpm2);
}
/**
* @brief Encode a rpm 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 rpm C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_rpm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rpm_t* rpm)
{
return mavlink_msg_rpm_pack_chan(system_id, component_id, chan, msg, rpm->rpm1, rpm->rpm2);
}
/**
* @brief Send a rpm message
* @param chan MAVLink channel to send the message
*
* @param rpm1 RPM Sensor1
* @param rpm2 RPM Sensor2
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_rpm_send(mavlink_channel_t chan, float rpm1, float rpm2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_RPM_LEN];
_mav_put_float(buf, 0, rpm1);
_mav_put_float(buf, 4, rpm2);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RPM, buf, MAVLINK_MSG_ID_RPM_LEN, MAVLINK_MSG_ID_RPM_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RPM, buf, MAVLINK_MSG_ID_RPM_LEN);
#endif
#else
mavlink_rpm_t packet;
packet.rpm1 = rpm1;
packet.rpm2 = rpm2;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RPM, (const char *)&packet, MAVLINK_MSG_ID_RPM_LEN, MAVLINK_MSG_ID_RPM_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RPM, (const char *)&packet, MAVLINK_MSG_ID_RPM_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_RPM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_rpm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float rpm1, float rpm2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_float(buf, 0, rpm1);
_mav_put_float(buf, 4, rpm2);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RPM, buf, MAVLINK_MSG_ID_RPM_LEN, MAVLINK_MSG_ID_RPM_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RPM, buf, MAVLINK_MSG_ID_RPM_LEN);
#endif
#else
mavlink_rpm_t *packet = (mavlink_rpm_t *)msgbuf;
packet->rpm1 = rpm1;
packet->rpm2 = rpm2;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RPM, (const char *)packet, MAVLINK_MSG_ID_RPM_LEN, MAVLINK_MSG_ID_RPM_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RPM, (const char *)packet, MAVLINK_MSG_ID_RPM_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE RPM UNPACKING
/**
* @brief Get field rpm1 from rpm message
*
* @return RPM Sensor1
*/
static inline float mavlink_msg_rpm_get_rpm1(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field rpm2 from rpm message
*
* @return RPM Sensor2
*/
static inline float mavlink_msg_rpm_get_rpm2(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Decode a rpm message into a struct
*
* @param msg The message to decode
* @param rpm C-struct to decode the message contents into
*/
static inline void mavlink_msg_rpm_decode(const mavlink_message_t* msg, mavlink_rpm_t* rpm)
{
#if MAVLINK_NEED_BYTE_SWAP
rpm->rpm1 = mavlink_msg_rpm_get_rpm1(msg);
rpm->rpm2 = mavlink_msg_rpm_get_rpm2(msg);
#else
memcpy(rpm, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RPM_LEN);
#endif
}

View File

@ -2730,6 +2730,50 @@ static void mavlink_test_gopro_set_response(uint8_t system_id, uint8_t component
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_rpm(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_rpm_t packet_in = {
17.0,45.0
};
mavlink_rpm_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.rpm1 = packet_in.rpm1;
packet1.rpm2 = packet_in.rpm2;
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_rpm_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_rpm_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_rpm_pack(system_id, component_id, &msg , packet1.rpm1 , packet1.rpm2 );
mavlink_msg_rpm_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_rpm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.rpm1 , packet1.rpm2 );
mavlink_msg_rpm_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_rpm_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_rpm_send(MAVLINK_COMM_1 , packet1.rpm1 , packet1.rpm2 );
mavlink_msg_rpm_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);
@ -2789,6 +2833,7 @@ static void mavlink_test_ardupilotmega(uint8_t system_id, uint8_t component_id,
mavlink_test_gopro_get_response(system_id, component_id, last_msg);
mavlink_test_gopro_set_request(system_id, component_id, last_msg);
mavlink_test_gopro_set_response(system_id, component_id, last_msg);
mavlink_test_rpm(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 "Wed Jul 1 12:02:16 2015"
#define MAVLINK_BUILD_DATE "Fri Aug 7 15:29:23 2015"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255

View File

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Wed Jul 1 12:02:19 2015"
#define MAVLINK_BUILD_DATE "Fri Aug 7 15:29:25 2015"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255