GCS_MAVLink: regenerate for COMPASSMOT_STATUS msg
This commit is contained in:
parent
a7c25ec649
commit
aa5ea23245
File diff suppressed because one or more lines are too long
@ -0,0 +1,287 @@
|
||||
// MESSAGE COMPASSMOT_STATUS PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_COMPASSMOT_STATUS 177
|
||||
|
||||
typedef struct __mavlink_compassmot_status_t
|
||||
{
|
||||
float current; ///< current (amps)
|
||||
float CompensationX; ///< Motor Compensation X
|
||||
float CompensationY; ///< Motor Compensation Y
|
||||
float CompensationZ; ///< Motor Compensation Z
|
||||
uint16_t throttle; ///< throttle (percent*10)
|
||||
uint16_t interference; ///< interference (percent)
|
||||
} mavlink_compassmot_status_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN 20
|
||||
#define MAVLINK_MSG_ID_177_LEN 20
|
||||
|
||||
#define MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC 240
|
||||
#define MAVLINK_MSG_ID_177_CRC 240
|
||||
|
||||
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_COMPASSMOT_STATUS { \
|
||||
"COMPASSMOT_STATUS", \
|
||||
6, \
|
||||
{ { "current", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_compassmot_status_t, current) }, \
|
||||
{ "CompensationX", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_compassmot_status_t, CompensationX) }, \
|
||||
{ "CompensationY", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_compassmot_status_t, CompensationY) }, \
|
||||
{ "CompensationZ", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_compassmot_status_t, CompensationZ) }, \
|
||||
{ "throttle", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_compassmot_status_t, throttle) }, \
|
||||
{ "interference", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_compassmot_status_t, interference) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Pack a compassmot_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 throttle throttle (percent*10)
|
||||
* @param current current (amps)
|
||||
* @param interference interference (percent)
|
||||
* @param CompensationX Motor Compensation X
|
||||
* @param CompensationY Motor Compensation Y
|
||||
* @param CompensationZ Motor Compensation Z
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_compassmot_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||
uint16_t throttle, float current, uint16_t interference, float CompensationX, float CompensationY, float CompensationZ)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN];
|
||||
_mav_put_float(buf, 0, current);
|
||||
_mav_put_float(buf, 4, CompensationX);
|
||||
_mav_put_float(buf, 8, CompensationY);
|
||||
_mav_put_float(buf, 12, CompensationZ);
|
||||
_mav_put_uint16_t(buf, 16, throttle);
|
||||
_mav_put_uint16_t(buf, 18, interference);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
|
||||
#else
|
||||
mavlink_compassmot_status_t packet;
|
||||
packet.current = current;
|
||||
packet.CompensationX = CompensationX;
|
||||
packet.CompensationY = CompensationY;
|
||||
packet.CompensationZ = CompensationZ;
|
||||
packet.throttle = throttle;
|
||||
packet.interference = interference;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
|
||||
#endif
|
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_COMPASSMOT_STATUS;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Pack a compassmot_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 throttle throttle (percent*10)
|
||||
* @param current current (amps)
|
||||
* @param interference interference (percent)
|
||||
* @param CompensationX Motor Compensation X
|
||||
* @param CompensationY Motor Compensation Y
|
||||
* @param CompensationZ Motor Compensation Z
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_compassmot_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||
mavlink_message_t* msg,
|
||||
uint16_t throttle,float current,uint16_t interference,float CompensationX,float CompensationY,float CompensationZ)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN];
|
||||
_mav_put_float(buf, 0, current);
|
||||
_mav_put_float(buf, 4, CompensationX);
|
||||
_mav_put_float(buf, 8, CompensationY);
|
||||
_mav_put_float(buf, 12, CompensationZ);
|
||||
_mav_put_uint16_t(buf, 16, throttle);
|
||||
_mav_put_uint16_t(buf, 18, interference);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
|
||||
#else
|
||||
mavlink_compassmot_status_t packet;
|
||||
packet.current = current;
|
||||
packet.CompensationX = CompensationX;
|
||||
packet.CompensationY = CompensationY;
|
||||
packet.CompensationZ = CompensationZ;
|
||||
packet.throttle = throttle;
|
||||
packet.interference = interference;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
|
||||
#endif
|
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_COMPASSMOT_STATUS;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a compassmot_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 compassmot_status C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_compassmot_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_compassmot_status_t* compassmot_status)
|
||||
{
|
||||
return mavlink_msg_compassmot_status_pack(system_id, component_id, msg, compassmot_status->throttle, compassmot_status->current, compassmot_status->interference, compassmot_status->CompensationX, compassmot_status->CompensationY, compassmot_status->CompensationZ);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a compassmot_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 compassmot_status C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_compassmot_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_compassmot_status_t* compassmot_status)
|
||||
{
|
||||
return mavlink_msg_compassmot_status_pack_chan(system_id, component_id, chan, msg, compassmot_status->throttle, compassmot_status->current, compassmot_status->interference, compassmot_status->CompensationX, compassmot_status->CompensationY, compassmot_status->CompensationZ);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a compassmot_status message
|
||||
* @param chan MAVLink channel to send the message
|
||||
*
|
||||
* @param throttle throttle (percent*10)
|
||||
* @param current current (amps)
|
||||
* @param interference interference (percent)
|
||||
* @param CompensationX Motor Compensation X
|
||||
* @param CompensationY Motor Compensation Y
|
||||
* @param CompensationZ Motor Compensation Z
|
||||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_compassmot_status_send(mavlink_channel_t chan, uint16_t throttle, float current, uint16_t interference, float CompensationX, float CompensationY, float CompensationZ)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN];
|
||||
_mav_put_float(buf, 0, current);
|
||||
_mav_put_float(buf, 4, CompensationX);
|
||||
_mav_put_float(buf, 8, CompensationY);
|
||||
_mav_put_float(buf, 12, CompensationZ);
|
||||
_mav_put_uint16_t(buf, 16, throttle);
|
||||
_mav_put_uint16_t(buf, 18, interference);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, buf, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, buf, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_compassmot_status_t packet;
|
||||
packet.current = current;
|
||||
packet.CompensationX = CompensationX;
|
||||
packet.CompensationY = CompensationY;
|
||||
packet.CompensationZ = CompensationZ;
|
||||
packet.throttle = throttle;
|
||||
packet.interference = interference;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, (const char *)&packet, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, (const char *)&packet, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
// MESSAGE COMPASSMOT_STATUS UNPACKING
|
||||
|
||||
|
||||
/**
|
||||
* @brief Get field throttle from compassmot_status message
|
||||
*
|
||||
* @return throttle (percent*10)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_compassmot_status_get_throttle(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint16_t(msg, 16);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field current from compassmot_status message
|
||||
*
|
||||
* @return current (amps)
|
||||
*/
|
||||
static inline float mavlink_msg_compassmot_status_get_current(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 0);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field interference from compassmot_status message
|
||||
*
|
||||
* @return interference (percent)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_compassmot_status_get_interference(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint16_t(msg, 18);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field CompensationX from compassmot_status message
|
||||
*
|
||||
* @return Motor Compensation X
|
||||
*/
|
||||
static inline float mavlink_msg_compassmot_status_get_CompensationX(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 4);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field CompensationY from compassmot_status message
|
||||
*
|
||||
* @return Motor Compensation Y
|
||||
*/
|
||||
static inline float mavlink_msg_compassmot_status_get_CompensationY(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 8);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field CompensationZ from compassmot_status message
|
||||
*
|
||||
* @return Motor Compensation Z
|
||||
*/
|
||||
static inline float mavlink_msg_compassmot_status_get_CompensationZ(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 12);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Decode a compassmot_status message into a struct
|
||||
*
|
||||
* @param msg The message to decode
|
||||
* @param compassmot_status C-struct to decode the message contents into
|
||||
*/
|
||||
static inline void mavlink_msg_compassmot_status_decode(const mavlink_message_t* msg, mavlink_compassmot_status_t* compassmot_status)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP
|
||||
compassmot_status->current = mavlink_msg_compassmot_status_get_current(msg);
|
||||
compassmot_status->CompensationX = mavlink_msg_compassmot_status_get_CompensationX(msg);
|
||||
compassmot_status->CompensationY = mavlink_msg_compassmot_status_get_CompensationY(msg);
|
||||
compassmot_status->CompensationZ = mavlink_msg_compassmot_status_get_CompensationZ(msg);
|
||||
compassmot_status->throttle = mavlink_msg_compassmot_status_get_throttle(msg);
|
||||
compassmot_status->interference = mavlink_msg_compassmot_status_get_interference(msg);
|
||||
#else
|
||||
memcpy(compassmot_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
|
||||
#endif
|
||||
}
|
@ -1398,6 +1398,59 @@ static void mavlink_test_rally_fetch_point(uint8_t system_id, uint8_t component_
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_compassmot_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_compassmot_status_t packet_in = {
|
||||
17.0,
|
||||
}45.0,
|
||||
}73.0,
|
||||
}101.0,
|
||||
}18067,
|
||||
}18171,
|
||||
};
|
||||
mavlink_compassmot_status_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
packet1.current = packet_in.current;
|
||||
packet1.CompensationX = packet_in.CompensationX;
|
||||
packet1.CompensationY = packet_in.CompensationY;
|
||||
packet1.CompensationZ = packet_in.CompensationZ;
|
||||
packet1.throttle = packet_in.throttle;
|
||||
packet1.interference = packet_in.interference;
|
||||
|
||||
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_compassmot_status_encode(system_id, component_id, &msg, &packet1);
|
||||
mavlink_msg_compassmot_status_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_compassmot_status_pack(system_id, component_id, &msg , packet1.throttle , packet1.current , packet1.interference , packet1.CompensationX , packet1.CompensationY , packet1.CompensationZ );
|
||||
mavlink_msg_compassmot_status_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_compassmot_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.throttle , packet1.current , packet1.interference , packet1.CompensationX , packet1.CompensationY , packet1.CompensationZ );
|
||||
mavlink_msg_compassmot_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_compassmot_status_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_compassmot_status_send(MAVLINK_COMM_1 , packet1.throttle , packet1.current , packet1.interference , packet1.CompensationX , packet1.CompensationY , packet1.CompensationZ );
|
||||
mavlink_msg_compassmot_status_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_ahrs2(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
@ -1479,6 +1532,7 @@ static void mavlink_test_ardupilotmega(uint8_t system_id, uint8_t component_id,
|
||||
mavlink_test_airspeed_autocal(system_id, component_id, last_msg);
|
||||
mavlink_test_rally_point(system_id, component_id, last_msg);
|
||||
mavlink_test_rally_fetch_point(system_id, component_id, last_msg);
|
||||
mavlink_test_compassmot_status(system_id, component_id, last_msg);
|
||||
mavlink_test_ahrs2(system_id, component_id, last_msg);
|
||||
}
|
||||
|
||||
|
@ -5,7 +5,7 @@
|
||||
#ifndef MAVLINK_VERSION_H
|
||||
#define MAVLINK_VERSION_H
|
||||
|
||||
#define MAVLINK_BUILD_DATE "Sat Feb 15 05:36:12 2014"
|
||||
#define MAVLINK_BUILD_DATE "Wed Feb 19 13:43:52 2014"
|
||||
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
|
||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254
|
||||
|
||||
|
@ -5,7 +5,7 @@
|
||||
#ifndef MAVLINK_VERSION_H
|
||||
#define MAVLINK_VERSION_H
|
||||
|
||||
#define MAVLINK_BUILD_DATE "Sat Feb 15 05:36:12 2014"
|
||||
#define MAVLINK_BUILD_DATE "Wed Feb 19 13:43:52 2014"
|
||||
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
|
||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254
|
||||
|
||||
|
@ -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
|
||||
uint32_t nav_mode; ///< Unused, can be used by user to store the system's navigation mode
|
||||
uint8_t nav_mode; ///< Unused, can be used by user to store the system's navigation mode
|
||||
} mavlink_system_t;
|
||||
|
||||
typedef struct __mavlink_message {
|
||||
|
Loading…
Reference in New Issue
Block a user