From 1385d3d62a8db9b5ce81b5ba90f665f282dab7ac Mon Sep 17 00:00:00 2001 From: Emilio Corigliano <emilio.corigliano@skywarder.eu> Date: Tue, 12 Dec 2023 17:21:49 +0100 Subject: [PATCH] [ARP] Added height field in set coordinates commands and turned steps to a int16_t --- mavlink_lib/lyra/mavlink_msg_arp_command_tc.h | 213 ++++++++++++++++++ message_definitions/lyra.xml | 45 +++- 2 files changed, 257 insertions(+), 1 deletion(-) create mode 100644 mavlink_lib/lyra/mavlink_msg_arp_command_tc.h diff --git a/mavlink_lib/lyra/mavlink_msg_arp_command_tc.h b/mavlink_lib/lyra/mavlink_msg_arp_command_tc.h new file mode 100644 index 0000000..c99ad25 --- /dev/null +++ b/mavlink_lib/lyra/mavlink_msg_arp_command_tc.h @@ -0,0 +1,213 @@ +#pragma once +// MESSAGE ARP_COMMAND_TC PACKING + +#define MAVLINK_MSG_ID_ARP_COMMAND_TC 172 + + +typedef struct __mavlink_arp_command_tc_t { + uint8_t command_id; /*< A member of the MavArpCommandList enum*/ +} mavlink_arp_command_tc_t; + +#define MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN 1 +#define MAVLINK_MSG_ID_ARP_COMMAND_TC_MIN_LEN 1 +#define MAVLINK_MSG_ID_172_LEN 1 +#define MAVLINK_MSG_ID_172_MIN_LEN 1 + +#define MAVLINK_MSG_ID_ARP_COMMAND_TC_CRC 181 +#define MAVLINK_MSG_ID_172_CRC 181 + + + +#if MAVLINK_COMMAND_24BIT +#define MAVLINK_MESSAGE_INFO_ARP_COMMAND_TC { \ + 172, \ + "ARP_COMMAND_TC", \ + 1, \ + { { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_arp_command_tc_t, command_id) }, \ + } \ +} +#else +#define MAVLINK_MESSAGE_INFO_ARP_COMMAND_TC { \ + "ARP_COMMAND_TC", \ + 1, \ + { { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_arp_command_tc_t, command_id) }, \ + } \ +} +#endif + +/** + * @brief Pack a arp_command_tc 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 command_id A member of the MavArpCommandList enum + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_arp_command_tc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t command_id) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN]; + _mav_put_uint8_t(buf, 0, command_id); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN); +#else + mavlink_arp_command_tc_t packet; + packet.command_id = command_id; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ARP_COMMAND_TC; + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ARP_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_CRC); +} + +/** + * @brief Pack a arp_command_tc 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 command_id A member of the MavArpCommandList enum + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_arp_command_tc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t command_id) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN]; + _mav_put_uint8_t(buf, 0, command_id); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN); +#else + mavlink_arp_command_tc_t packet; + packet.command_id = command_id; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ARP_COMMAND_TC; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ARP_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_CRC); +} + +/** + * @brief Encode a arp_command_tc 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 arp_command_tc C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_arp_command_tc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_arp_command_tc_t* arp_command_tc) +{ + return mavlink_msg_arp_command_tc_pack(system_id, component_id, msg, arp_command_tc->command_id); +} + +/** + * @brief Encode a arp_command_tc 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 arp_command_tc C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_arp_command_tc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_arp_command_tc_t* arp_command_tc) +{ + return mavlink_msg_arp_command_tc_pack_chan(system_id, component_id, chan, msg, arp_command_tc->command_id); +} + +/** + * @brief Send a arp_command_tc message + * @param chan MAVLink channel to send the message + * + * @param command_id A member of the MavArpCommandList enum + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_arp_command_tc_send(mavlink_channel_t chan, uint8_t command_id) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN]; + _mav_put_uint8_t(buf, 0, command_id); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARP_COMMAND_TC, buf, MAVLINK_MSG_ID_ARP_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_CRC); +#else + mavlink_arp_command_tc_t packet; + packet.command_id = command_id; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARP_COMMAND_TC, (const char *)&packet, MAVLINK_MSG_ID_ARP_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_CRC); +#endif +} + +/** + * @brief Send a arp_command_tc message + * @param chan MAVLink channel to send the message + * @param struct The MAVLink struct to serialize + */ +static inline void mavlink_msg_arp_command_tc_send_struct(mavlink_channel_t chan, const mavlink_arp_command_tc_t* arp_command_tc) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + mavlink_msg_arp_command_tc_send(chan, arp_command_tc->command_id); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARP_COMMAND_TC, (const char *)arp_command_tc, MAVLINK_MSG_ID_ARP_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_CRC); +#endif +} + +#if MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This variant 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_arp_command_tc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t command_id) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, command_id); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARP_COMMAND_TC, buf, MAVLINK_MSG_ID_ARP_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_CRC); +#else + mavlink_arp_command_tc_t *packet = (mavlink_arp_command_tc_t *)msgbuf; + packet->command_id = command_id; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ARP_COMMAND_TC, (const char *)packet, MAVLINK_MSG_ID_ARP_COMMAND_TC_MIN_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN, MAVLINK_MSG_ID_ARP_COMMAND_TC_CRC); +#endif +} +#endif + +#endif + +// MESSAGE ARP_COMMAND_TC UNPACKING + + +/** + * @brief Get field command_id from arp_command_tc message + * + * @return A member of the MavArpCommandList enum + */ +static inline uint8_t mavlink_msg_arp_command_tc_get_command_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Decode a arp_command_tc message into a struct + * + * @param msg The message to decode + * @param arp_command_tc C-struct to decode the message contents into + */ +static inline void mavlink_msg_arp_command_tc_decode(const mavlink_message_t* msg, mavlink_arp_command_tc_t* arp_command_tc) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + arp_command_tc->command_id = mavlink_msg_arp_command_tc_get_command_id(msg); +#else + uint8_t len = msg->len < MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN? msg->len : MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN; + memset(arp_command_tc, 0, MAVLINK_MSG_ID_ARP_COMMAND_TC_LEN); + memcpy(arp_command_tc, _MAV_PAYLOAD(msg), len); +#endif +} diff --git a/message_definitions/lyra.xml b/message_definitions/lyra.xml index 35c1b3c..0d09cdc 100644 --- a/message_definitions/lyra.xml +++ b/message_definitions/lyra.xml @@ -8,6 +8,7 @@ <entry name="MAV_SYSID_PAYLOAD" value="2"></entry> <entry name="MAV_SYSID_RIG" value="3"></entry> <entry name="MAV_SYSID_GS" value="4"></entry> + <entry name="MAV_SYSID_ARP" value="5"></entry> </enum> <enum name="SystemTMList"> <description>Enum list for all the telemetries that can be requested</description> @@ -159,7 +160,7 @@ </entry> </enum> <enum name="MavCommandList"> - <description>Enum of the commands</description> + <description>Enum of the rocket commands</description> <entry name="MAV_CMD_ARM" value="1"> <description>Command to arm the rocket</description> </entry> @@ -227,6 +228,39 @@ <description>Command to enter HIL mode at next reboot</description> </entry> </enum> + <enum name="MavArpCommandList"> + <description>Enum of the ARP commands</description> + <entry name="MAV_ARP_CMD_FORCE_INIT" value="1"> + <description>Command to force the initialization of ARP</description> + </entry> + <entry name="MAV_ARP_CMD_RESET_ALGORITHM" value="2"> + <description>Command to reset the algorithm</description> + </entry> + <entry name="MAV_ARP_CMD_RESET_BOARD" value="3"> + <description>Command to force a reboot</description> + </entry> + <entry name="MAV_ARP_CMD_FORCE_NO_FEEDBACK" value="4"> + <description>Command to move ARP to the not-feedback mode</description> + </entry> + <entry name="MAV_ARP_CMD_ARM" value="5"> + <description>Command to arm ARP</description> + </entry> + <entry name="MAV_ARP_CMD_DISARM" value="6"> + <description>Command to disarm ARP</description> + </entry> + <entry name="MAV_ARP_CMD_FOLLOW" value="7"> + <description>Command to start Follow loop of ARP</description> + </entry> + <entry name="MAV_ARP_CMD_CALIBRATE" value="8"> + <description>Command to calibrate ARP</description> + </entry> + <entry name="MAV_ARP_CMD_ENTER_TEST_MODE" value="9"> + <description>Command to enter the test mode</description> + </entry> + <entry name="MAV_ARP_CMD_EXIT_TEST_MODE" value="10"> + <description>Command to exit the test mode</description> + </entry> + </enum> <enum name="ServosList"> <description>Enum of all the servos used on Gemini</description> <entry name="AIR_BRAKES_SERVO" value="1"></entry> @@ -525,6 +559,7 @@ <message id="150" name="ARP_TM"> <description></description> <field name="timestamp" type="uint64_t" units="us">Timestamp</field> + <field name="state" type="uint8_t">State Machine Controller State</field> <field name="yaw" type="float" units="deg">Current Yaw</field> <field name="pitch" type="float" units="deg">Current Pitch</field> <field name="roll" type="float" units="deg">Current Roll</field> @@ -557,16 +592,23 @@ <field name="ethernet_present" type="uint8_t">Boolean indicating the presence of the ethernet module</field> <field name="ethernet_status" type="uint8_t">Status flag indicating the status of the ethernet PHY</field> <field name="battery_voltage" type="float" units="V">Battery voltage</field> + <field name="log_number" type="int16_t">Currently active log file, -1 if the logger is inactive</field> </message> <message id="151" name="SET_ANTENNA_COORDINATES_ARP_TC"> <description>Sets current antennas coordinates</description> <field name="latitude" type="float" units="deg">Latitude</field> <field name="longitude" type="float" units="deg">Longitude</field> + <field name="height" type="float" units="m">Height</field> </message> <message id="152" name="SET_ROCKET_COORDINATES_ARP_TC"> <description>Sets current rocket coordinates</description> <field name="latitude" type="float" units="deg">Latitude</field> <field name="longitude" type="float" units="deg">Longitude</field> + <field name="height" type="float" units="m">Height</field> + </message> + <message id="172" name="ARP_COMMAND_TC"> + <description>TC containing a command with no parameters that trigger some action</description> + <field name="command_id" type="uint8_t">A member of the MavArpCommandList enum</field> </message> <!-- FROM ROCKET TO GROUND: SPECIFIC --> @@ -861,6 +903,7 @@ <field name="top_tank_pressure" type="float" units="Bar">Tank upper pressure</field> <field name="bottom_tank_pressure" type="float" units="Bar">Tank bottom pressure</field> <field name="combustion_chamber_pressure" type="float" units="Bar">Pressure inside the combustion chamber used for automatic shutdown</field> + <field name="floating_level" type="uint8_t">Floating level in tank</field> <field name="tank_temperature" type="float">Tank temperature</field> <field name="main_valve_state" type="uint8_t">1 If the main valve is open </field> <field name="venting_valve_state" type="uint8_t">1 If the venting valve is open </field> -- GitLab