Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add new RAW_RPM message #5

Closed
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 4 additions & 3 deletions common/common.h

Large diffs are not rendered by default.

263 changes: 263 additions & 0 deletions common/mavlink_msg_raw_rpm.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,263 @@
#pragma once
// MESSAGE RAW_RPM PACKING

#define MAVLINK_MSG_ID_RAW_RPM 336

MAVPACKED(
typedef struct __mavlink_raw_rpm_t {
uint64_t timestamp; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
float indicated_frequency_rpm; /*< indicated rotor Frequency in Revolution per minute.*/
float estimated_accurancy_rpm; /*< estimated accurancy in Revolution per minute.*/
}) mavlink_raw_rpm_t;

#define MAVLINK_MSG_ID_RAW_RPM_LEN 16
#define MAVLINK_MSG_ID_RAW_RPM_MIN_LEN 16
#define MAVLINK_MSG_ID_336_LEN 16
#define MAVLINK_MSG_ID_336_MIN_LEN 16

#define MAVLINK_MSG_ID_RAW_RPM_CRC 92
#define MAVLINK_MSG_ID_336_CRC 92



#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_RAW_RPM { \
336, \
"RAW_RPM", \
3, \
{ { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_rpm_t, timestamp) }, \
{ "indicated_frequency_rpm", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_raw_rpm_t, indicated_frequency_rpm) }, \
{ "estimated_accurancy_rpm", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_raw_rpm_t, estimated_accurancy_rpm) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_RAW_RPM { \
"RAW_RPM", \
3, \
{ { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_rpm_t, timestamp) }, \
{ "indicated_frequency_rpm", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_raw_rpm_t, indicated_frequency_rpm) }, \
{ "estimated_accurancy_rpm", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_raw_rpm_t, estimated_accurancy_rpm) }, \
} \
}
#endif

/**
* @brief Pack a raw_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 timestamp [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param indicated_frequency_rpm indicated rotor Frequency in Revolution per minute.
* @param estimated_accurancy_rpm estimated accurancy in Revolution per minute.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_raw_rpm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t timestamp, float indicated_frequency_rpm, float estimated_accurancy_rpm)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_RAW_RPM_LEN];
_mav_put_uint64_t(buf, 0, timestamp);
_mav_put_float(buf, 8, indicated_frequency_rpm);
_mav_put_float(buf, 12, estimated_accurancy_rpm);

memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_RPM_LEN);
#else
mavlink_raw_rpm_t packet;
packet.timestamp = timestamp;
packet.indicated_frequency_rpm = indicated_frequency_rpm;
packet.estimated_accurancy_rpm = estimated_accurancy_rpm;

memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_RPM_LEN);
#endif

msg->msgid = MAVLINK_MSG_ID_RAW_RPM;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_RPM_MIN_LEN, MAVLINK_MSG_ID_RAW_RPM_LEN, MAVLINK_MSG_ID_RAW_RPM_CRC);
}

/**
* @brief Pack a raw_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 timestamp [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param indicated_frequency_rpm indicated rotor Frequency in Revolution per minute.
* @param estimated_accurancy_rpm estimated accurancy in Revolution per minute.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_raw_rpm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t timestamp,float indicated_frequency_rpm,float estimated_accurancy_rpm)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_RAW_RPM_LEN];
_mav_put_uint64_t(buf, 0, timestamp);
_mav_put_float(buf, 8, indicated_frequency_rpm);
_mav_put_float(buf, 12, estimated_accurancy_rpm);

memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_RPM_LEN);
#else
mavlink_raw_rpm_t packet;
packet.timestamp = timestamp;
packet.indicated_frequency_rpm = indicated_frequency_rpm;
packet.estimated_accurancy_rpm = estimated_accurancy_rpm;

memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_RPM_LEN);
#endif

msg->msgid = MAVLINK_MSG_ID_RAW_RPM;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_RPM_MIN_LEN, MAVLINK_MSG_ID_RAW_RPM_LEN, MAVLINK_MSG_ID_RAW_RPM_CRC);
}

/**
* @brief Encode a raw_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 raw_rpm C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_raw_rpm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_rpm_t* raw_rpm)
{
return mavlink_msg_raw_rpm_pack(system_id, component_id, msg, raw_rpm->timestamp, raw_rpm->indicated_frequency_rpm, raw_rpm->estimated_accurancy_rpm);
}

/**
* @brief Encode a raw_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 raw_rpm C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_raw_rpm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_raw_rpm_t* raw_rpm)
{
return mavlink_msg_raw_rpm_pack_chan(system_id, component_id, chan, msg, raw_rpm->timestamp, raw_rpm->indicated_frequency_rpm, raw_rpm->estimated_accurancy_rpm);
}

/**
* @brief Send a raw_rpm message
* @param chan MAVLink channel to send the message
*
* @param timestamp [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param indicated_frequency_rpm indicated rotor Frequency in Revolution per minute.
* @param estimated_accurancy_rpm estimated accurancy in Revolution per minute.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

static inline void mavlink_msg_raw_rpm_send(mavlink_channel_t chan, uint64_t timestamp, float indicated_frequency_rpm, float estimated_accurancy_rpm)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_RAW_RPM_LEN];
_mav_put_uint64_t(buf, 0, timestamp);
_mav_put_float(buf, 8, indicated_frequency_rpm);
_mav_put_float(buf, 12, estimated_accurancy_rpm);

_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_RPM, buf, MAVLINK_MSG_ID_RAW_RPM_MIN_LEN, MAVLINK_MSG_ID_RAW_RPM_LEN, MAVLINK_MSG_ID_RAW_RPM_CRC);
#else
mavlink_raw_rpm_t packet;
packet.timestamp = timestamp;
packet.indicated_frequency_rpm = indicated_frequency_rpm;
packet.estimated_accurancy_rpm = estimated_accurancy_rpm;

_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_RPM, (const char *)&packet, MAVLINK_MSG_ID_RAW_RPM_MIN_LEN, MAVLINK_MSG_ID_RAW_RPM_LEN, MAVLINK_MSG_ID_RAW_RPM_CRC);
#endif
}

/**
* @brief Send a raw_rpm message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_raw_rpm_send_struct(mavlink_channel_t chan, const mavlink_raw_rpm_t* raw_rpm)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_raw_rpm_send(chan, raw_rpm->timestamp, raw_rpm->indicated_frequency_rpm, raw_rpm->estimated_accurancy_rpm);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_RPM, (const char *)raw_rpm, MAVLINK_MSG_ID_RAW_RPM_MIN_LEN, MAVLINK_MSG_ID_RAW_RPM_LEN, MAVLINK_MSG_ID_RAW_RPM_CRC);
#endif
}

#if MAVLINK_MSG_ID_RAW_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_raw_rpm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, float indicated_frequency_rpm, float estimated_accurancy_rpm)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint64_t(buf, 0, timestamp);
_mav_put_float(buf, 8, indicated_frequency_rpm);
_mav_put_float(buf, 12, estimated_accurancy_rpm);

_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_RPM, buf, MAVLINK_MSG_ID_RAW_RPM_MIN_LEN, MAVLINK_MSG_ID_RAW_RPM_LEN, MAVLINK_MSG_ID_RAW_RPM_CRC);
#else
mavlink_raw_rpm_t *packet = (mavlink_raw_rpm_t *)msgbuf;
packet->timestamp = timestamp;
packet->indicated_frequency_rpm = indicated_frequency_rpm;
packet->estimated_accurancy_rpm = estimated_accurancy_rpm;

_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_RPM, (const char *)packet, MAVLINK_MSG_ID_RAW_RPM_MIN_LEN, MAVLINK_MSG_ID_RAW_RPM_LEN, MAVLINK_MSG_ID_RAW_RPM_CRC);
#endif
}
#endif

#endif

// MESSAGE RAW_RPM UNPACKING


/**
* @brief Get field timestamp from raw_rpm message
*
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_raw_rpm_get_timestamp(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}

/**
* @brief Get field indicated_frequency_rpm from raw_rpm message
*
* @return indicated rotor Frequency in Revolution per minute.
*/
static inline float mavlink_msg_raw_rpm_get_indicated_frequency_rpm(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}

/**
* @brief Get field estimated_accurancy_rpm from raw_rpm message
*
* @return estimated accurancy in Revolution per minute.
*/
static inline float mavlink_msg_raw_rpm_get_estimated_accurancy_rpm(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}

/**
* @brief Decode a raw_rpm message into a struct
*
* @param msg The message to decode
* @param raw_rpm C-struct to decode the message contents into
*/
static inline void mavlink_msg_raw_rpm_decode(const mavlink_message_t* msg, mavlink_raw_rpm_t* raw_rpm)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
raw_rpm->timestamp = mavlink_msg_raw_rpm_get_timestamp(msg);
raw_rpm->indicated_frequency_rpm = mavlink_msg_raw_rpm_get_indicated_frequency_rpm(msg);
raw_rpm->estimated_accurancy_rpm = mavlink_msg_raw_rpm_get_estimated_accurancy_rpm(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_RAW_RPM_LEN? msg->len : MAVLINK_MSG_ID_RAW_RPM_LEN;
memset(raw_rpm, 0, MAVLINK_MSG_ID_RAW_RPM_LEN);
memcpy(raw_rpm, _MAV_PAYLOAD(msg), len);
#endif
}
57 changes: 57 additions & 0 deletions common/testsuite.h
Original file line number Diff line number Diff line change
Expand Up @@ -10861,6 +10861,62 @@ static void mavlink_test_isbd_link_status(uint8_t system_id, uint8_t component_i
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}

static void mavlink_test_raw_rpm(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RAW_RPM >= 256) {
return;
}
#endif
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_raw_rpm_t packet_in = {
93372036854775807ULL,73.0,101.0
};
mavlink_raw_rpm_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.timestamp = packet_in.timestamp;
packet1.indicated_frequency_rpm = packet_in.indicated_frequency_rpm;
packet1.estimated_accurancy_rpm = packet_in.estimated_accurancy_rpm;


#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
// cope with extensions
memset(MAVLINK_MSG_ID_RAW_RPM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RAW_RPM_MIN_LEN);
}
#endif
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_raw_rpm_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_raw_rpm_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);

memset(&packet2, 0, sizeof(packet2));
mavlink_msg_raw_rpm_pack(system_id, component_id, &msg , packet1.timestamp , packet1.indicated_frequency_rpm , packet1.estimated_accurancy_rpm );
mavlink_msg_raw_rpm_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);

memset(&packet2, 0, sizeof(packet2));
mavlink_msg_raw_rpm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.indicated_frequency_rpm , packet1.estimated_accurancy_rpm );
mavlink_msg_raw_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_raw_rpm_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);

memset(&packet2, 0, sizeof(packet2));
mavlink_msg_raw_rpm_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.indicated_frequency_rpm , packet1.estimated_accurancy_rpm );
mavlink_msg_raw_rpm_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}

static void mavlink_test_utm_global_position(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
Expand Down Expand Up @@ -12237,6 +12293,7 @@ static void mavlink_test_common(uint8_t system_id, uint8_t component_id, mavlink
mavlink_test_trajectory_representation_bezier(system_id, component_id, last_msg);
mavlink_test_cellular_status(system_id, component_id, last_msg);
mavlink_test_isbd_link_status(system_id, component_id, last_msg);
mavlink_test_raw_rpm(system_id, component_id, last_msg);
mavlink_test_utm_global_position(system_id, component_id, last_msg);
mavlink_test_debug_float_array(system_id, component_id, last_msg);
mavlink_test_orbit_execution_status(system_id, component_id, last_msg);
Expand Down
2 changes: 1 addition & 1 deletion common/version.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H

#define MAVLINK_BUILD_DATE "Thu Mar 19 2020"
#define MAVLINK_BUILD_DATE "Wed Apr 01 2020"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255

Expand Down
8 changes: 7 additions & 1 deletion message_definitions/common.xml
Original file line number Diff line number Diff line change
Expand Up @@ -6310,7 +6310,13 @@
<field type="uint8_t" name="ring_pending">1: Ring call pending, 0: No call pending.</field>
<field type="uint8_t" name="tx_session_pending">1: Transmission session pending, 0: No transmission session pending.</field>
<field type="uint8_t" name="rx_session_pending">1: Receiving session pending, 0: No receiving session pending.</field>
</message>
</message>
<message id="336" name="RAW_RPM">
<description>RPM sensor data message.</description>
<field type="uint64_t" name="timestamp" units="us">Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.</field>
<field type="float" name="indicated_frequency_rpm">indicated rotor Frequency in Revolution per minute.</field>
<field type="float" name="estimated_accurancy_rpm">estimated accurancy in Revolution per minute.</field>
</message>
<message id="340" name="UTM_GLOBAL_POSITION">
<wip/>
<!-- This message is work-in-progress it can therefore change, and should NOT be used in stable production environments -->
Expand Down
Loading