123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316 |
- #pragma once
- // MESSAGE SET_MODE PACKING
- #define MAVLINK_MSG_ID_SET_MODE 11
- typedef struct __mavlink_set_mode_t {
- uint32_t custom_mode; /*< The new autopilot-specific mode. This field can be ignored by an autopilot.*/
- uint8_t target_system; /*< The system setting the mode*/
- uint8_t base_mode; /*< The new base mode.*/
- } mavlink_set_mode_t;
- #define MAVLINK_MSG_ID_SET_MODE_LEN 6
- #define MAVLINK_MSG_ID_SET_MODE_MIN_LEN 6
- #define MAVLINK_MSG_ID_11_LEN 6
- #define MAVLINK_MSG_ID_11_MIN_LEN 6
- #define MAVLINK_MSG_ID_SET_MODE_CRC 89
- #define MAVLINK_MSG_ID_11_CRC 89
- #if MAVLINK_COMMAND_24BIT
- #define MAVLINK_MESSAGE_INFO_SET_MODE { \
- 11, \
- "SET_MODE", \
- 3, \
- { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_mode_t, target_system) }, \
- { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_set_mode_t, base_mode) }, \
- { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_mode_t, custom_mode) }, \
- } \
- }
- #else
- #define MAVLINK_MESSAGE_INFO_SET_MODE { \
- "SET_MODE", \
- 3, \
- { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_mode_t, target_system) }, \
- { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_set_mode_t, base_mode) }, \
- { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_mode_t, custom_mode) }, \
- } \
- }
- #endif
- /**
- * @brief Pack a set_mode 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 target_system The system setting the mode
- * @param base_mode The new base mode.
- * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
- static inline uint16_t mavlink_msg_set_mode_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t target_system, uint8_t base_mode, uint32_t custom_mode)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_MODE_LEN];
- _mav_put_uint32_t(buf, 0, custom_mode);
- _mav_put_uint8_t(buf, 4, target_system);
- _mav_put_uint8_t(buf, 5, base_mode);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_MODE_LEN);
- #else
- mavlink_set_mode_t packet;
- packet.custom_mode = custom_mode;
- packet.target_system = target_system;
- packet.base_mode = base_mode;
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_MODE_LEN);
- #endif
- msg->msgid = MAVLINK_MSG_ID_SET_MODE;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC);
- }
- /**
- * @brief Pack a set_mode message
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param status MAVLink status structure
- * @param msg The MAVLink message to compress the data into
- *
- * @param target_system The system setting the mode
- * @param base_mode The new base mode.
- * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
- static inline uint16_t mavlink_msg_set_mode_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
- uint8_t target_system, uint8_t base_mode, uint32_t custom_mode)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_MODE_LEN];
- _mav_put_uint32_t(buf, 0, custom_mode);
- _mav_put_uint8_t(buf, 4, target_system);
- _mav_put_uint8_t(buf, 5, base_mode);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_MODE_LEN);
- #else
- mavlink_set_mode_t packet;
- packet.custom_mode = custom_mode;
- packet.target_system = target_system;
- packet.base_mode = base_mode;
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_MODE_LEN);
- #endif
- msg->msgid = MAVLINK_MSG_ID_SET_MODE;
- #if MAVLINK_CRC_EXTRA
- return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC);
- #else
- return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN);
- #endif
- }
- /**
- * @brief Pack a set_mode 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 target_system The system setting the mode
- * @param base_mode The new base mode.
- * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot.
- * @return length of the message in bytes (excluding serial stream start sign)
- */
- static inline uint16_t mavlink_msg_set_mode_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t target_system,uint8_t base_mode,uint32_t custom_mode)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_MODE_LEN];
- _mav_put_uint32_t(buf, 0, custom_mode);
- _mav_put_uint8_t(buf, 4, target_system);
- _mav_put_uint8_t(buf, 5, base_mode);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_MODE_LEN);
- #else
- mavlink_set_mode_t packet;
- packet.custom_mode = custom_mode;
- packet.target_system = target_system;
- packet.base_mode = base_mode;
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_MODE_LEN);
- #endif
- msg->msgid = MAVLINK_MSG_ID_SET_MODE;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC);
- }
- /**
- * @brief Encode a set_mode 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 set_mode C-struct to read the message contents from
- */
- static inline uint16_t mavlink_msg_set_mode_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_mode_t* set_mode)
- {
- return mavlink_msg_set_mode_pack(system_id, component_id, msg, set_mode->target_system, set_mode->base_mode, set_mode->custom_mode);
- }
- /**
- * @brief Encode a set_mode 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 set_mode C-struct to read the message contents from
- */
- static inline uint16_t mavlink_msg_set_mode_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_mode_t* set_mode)
- {
- return mavlink_msg_set_mode_pack_chan(system_id, component_id, chan, msg, set_mode->target_system, set_mode->base_mode, set_mode->custom_mode);
- }
- /**
- * @brief Encode a set_mode struct with provided status structure
- *
- * @param system_id ID of this system
- * @param component_id ID of this component (e.g. 200 for IMU)
- * @param status MAVLink status structure
- * @param msg The MAVLink message to compress the data into
- * @param set_mode C-struct to read the message contents from
- */
- static inline uint16_t mavlink_msg_set_mode_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_set_mode_t* set_mode)
- {
- return mavlink_msg_set_mode_pack_status(system_id, component_id, _status, msg, set_mode->target_system, set_mode->base_mode, set_mode->custom_mode);
- }
- /**
- * @brief Send a set_mode message
- * @param chan MAVLink channel to send the message
- *
- * @param target_system The system setting the mode
- * @param base_mode The new base mode.
- * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot.
- */
- #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
- static inline void mavlink_msg_set_mode_send(mavlink_channel_t chan, uint8_t target_system, uint8_t base_mode, uint32_t custom_mode)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_SET_MODE_LEN];
- _mav_put_uint32_t(buf, 0, custom_mode);
- _mav_put_uint8_t(buf, 4, target_system);
- _mav_put_uint8_t(buf, 5, base_mode);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC);
- #else
- mavlink_set_mode_t packet;
- packet.custom_mode = custom_mode;
- packet.target_system = target_system;
- packet.base_mode = base_mode;
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)&packet, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC);
- #endif
- }
- /**
- * @brief Send a set_mode message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
- static inline void mavlink_msg_set_mode_send_struct(mavlink_channel_t chan, const mavlink_set_mode_t* set_mode)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_set_mode_send(chan, set_mode->target_system, set_mode->base_mode, set_mode->custom_mode);
- #else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)set_mode, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC);
- #endif
- }
- #if MAVLINK_MSG_ID_SET_MODE_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_set_mode_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t base_mode, uint32_t custom_mode)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint32_t(buf, 0, custom_mode);
- _mav_put_uint8_t(buf, 4, target_system);
- _mav_put_uint8_t(buf, 5, base_mode);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC);
- #else
- mavlink_set_mode_t *packet = (mavlink_set_mode_t *)msgbuf;
- packet->custom_mode = custom_mode;
- packet->target_system = target_system;
- packet->base_mode = base_mode;
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)packet, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC);
- #endif
- }
- #endif
- #endif
- // MESSAGE SET_MODE UNPACKING
- /**
- * @brief Get field target_system from set_mode message
- *
- * @return The system setting the mode
- */
- static inline uint8_t mavlink_msg_set_mode_get_target_system(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_uint8_t(msg, 4);
- }
- /**
- * @brief Get field base_mode from set_mode message
- *
- * @return The new base mode.
- */
- static inline uint8_t mavlink_msg_set_mode_get_base_mode(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_uint8_t(msg, 5);
- }
- /**
- * @brief Get field custom_mode from set_mode message
- *
- * @return The new autopilot-specific mode. This field can be ignored by an autopilot.
- */
- static inline uint32_t mavlink_msg_set_mode_get_custom_mode(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_uint32_t(msg, 0);
- }
- /**
- * @brief Decode a set_mode message into a struct
- *
- * @param msg The message to decode
- * @param set_mode C-struct to decode the message contents into
- */
- static inline void mavlink_msg_set_mode_decode(const mavlink_message_t* msg, mavlink_set_mode_t* set_mode)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- set_mode->custom_mode = mavlink_msg_set_mode_get_custom_mode(msg);
- set_mode->target_system = mavlink_msg_set_mode_get_target_system(msg);
- set_mode->base_mode = mavlink_msg_set_mode_get_base_mode(msg);
- #else
- uint8_t len = msg->len < MAVLINK_MSG_ID_SET_MODE_LEN? msg->len : MAVLINK_MSG_ID_SET_MODE_LEN;
- memset(set_mode, 0, MAVLINK_MSG_ID_SET_MODE_LEN);
- memcpy(set_mode, _MAV_PAYLOAD(msg), len);
- #endif
- }
|