123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418 |
- #pragma once
- // MESSAGE ATTITUDE_TARGET PACKING
- #define MAVLINK_MSG_ID_ATTITUDE_TARGET 83
- typedef struct __mavlink_attitude_target_t {
- uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
- float q[4]; /*< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/
- float body_roll_rate; /*< [rad/s] Body roll rate*/
- float body_pitch_rate; /*< [rad/s] Body pitch rate*/
- float body_yaw_rate; /*< [rad/s] Body yaw rate*/
- float thrust; /*< Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)*/
- uint8_t type_mask; /*< Bitmap to indicate which dimensions should be ignored by the vehicle.*/
- } mavlink_attitude_target_t;
- #define MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN 37
- #define MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN 37
- #define MAVLINK_MSG_ID_83_LEN 37
- #define MAVLINK_MSG_ID_83_MIN_LEN 37
- #define MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC 22
- #define MAVLINK_MSG_ID_83_CRC 22
- #define MAVLINK_MSG_ATTITUDE_TARGET_FIELD_Q_LEN 4
- #if MAVLINK_COMMAND_24BIT
- #define MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET { \
- 83, \
- "ATTITUDE_TARGET", \
- 7, \
- { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_target_t, time_boot_ms) }, \
- { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_attitude_target_t, type_mask) }, \
- { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_attitude_target_t, q) }, \
- { "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_target_t, body_roll_rate) }, \
- { "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_target_t, body_pitch_rate) }, \
- { "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_target_t, body_yaw_rate) }, \
- { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_target_t, thrust) }, \
- } \
- }
- #else
- #define MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET { \
- "ATTITUDE_TARGET", \
- 7, \
- { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_target_t, time_boot_ms) }, \
- { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_attitude_target_t, type_mask) }, \
- { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_attitude_target_t, q) }, \
- { "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_target_t, body_roll_rate) }, \
- { "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_target_t, body_pitch_rate) }, \
- { "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_target_t, body_yaw_rate) }, \
- { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_target_t, thrust) }, \
- } \
- }
- #endif
- /**
- * @brief Pack a attitude_target 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 time_boot_ms [ms] Timestamp (time since system boot).
- * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle.
- * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
- * @param body_roll_rate [rad/s] Body roll rate
- * @param body_pitch_rate [rad/s] Body pitch rate
- * @param body_yaw_rate [rad/s] Body yaw rate
- * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
- * @return length of the message in bytes (excluding serial stream start sign)
- */
- static inline uint16_t mavlink_msg_attitude_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint32_t time_boot_ms, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN];
- _mav_put_uint32_t(buf, 0, time_boot_ms);
- _mav_put_float(buf, 20, body_roll_rate);
- _mav_put_float(buf, 24, body_pitch_rate);
- _mav_put_float(buf, 28, body_yaw_rate);
- _mav_put_float(buf, 32, thrust);
- _mav_put_uint8_t(buf, 36, type_mask);
- _mav_put_float_array(buf, 4, q, 4);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
- #else
- mavlink_attitude_target_t packet;
- packet.time_boot_ms = time_boot_ms;
- packet.body_roll_rate = body_roll_rate;
- packet.body_pitch_rate = body_pitch_rate;
- packet.body_yaw_rate = body_yaw_rate;
- packet.thrust = thrust;
- packet.type_mask = type_mask;
- mav_array_memcpy(packet.q, q, sizeof(float)*4);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
- #endif
- msg->msgid = MAVLINK_MSG_ID_ATTITUDE_TARGET;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC);
- }
- /**
- * @brief Pack a attitude_target 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 time_boot_ms [ms] Timestamp (time since system boot).
- * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle.
- * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
- * @param body_roll_rate [rad/s] Body roll rate
- * @param body_pitch_rate [rad/s] Body pitch rate
- * @param body_yaw_rate [rad/s] Body yaw rate
- * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
- * @return length of the message in bytes (excluding serial stream start sign)
- */
- static inline uint16_t mavlink_msg_attitude_target_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
- uint32_t time_boot_ms, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN];
- _mav_put_uint32_t(buf, 0, time_boot_ms);
- _mav_put_float(buf, 20, body_roll_rate);
- _mav_put_float(buf, 24, body_pitch_rate);
- _mav_put_float(buf, 28, body_yaw_rate);
- _mav_put_float(buf, 32, thrust);
- _mav_put_uint8_t(buf, 36, type_mask);
- _mav_put_float_array(buf, 4, q, 4);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
- #else
- mavlink_attitude_target_t packet;
- packet.time_boot_ms = time_boot_ms;
- packet.body_roll_rate = body_roll_rate;
- packet.body_pitch_rate = body_pitch_rate;
- packet.body_yaw_rate = body_yaw_rate;
- packet.thrust = thrust;
- packet.type_mask = type_mask;
- mav_array_memcpy(packet.q, q, sizeof(float)*4);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
- #endif
- msg->msgid = MAVLINK_MSG_ID_ATTITUDE_TARGET;
- #if MAVLINK_CRC_EXTRA
- return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC);
- #else
- return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
- #endif
- }
- /**
- * @brief Pack a attitude_target 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 time_boot_ms [ms] Timestamp (time since system boot).
- * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle.
- * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
- * @param body_roll_rate [rad/s] Body roll rate
- * @param body_pitch_rate [rad/s] Body pitch rate
- * @param body_yaw_rate [rad/s] Body yaw rate
- * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
- * @return length of the message in bytes (excluding serial stream start sign)
- */
- static inline uint16_t mavlink_msg_attitude_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint32_t time_boot_ms,uint8_t type_mask,const float *q,float body_roll_rate,float body_pitch_rate,float body_yaw_rate,float thrust)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN];
- _mav_put_uint32_t(buf, 0, time_boot_ms);
- _mav_put_float(buf, 20, body_roll_rate);
- _mav_put_float(buf, 24, body_pitch_rate);
- _mav_put_float(buf, 28, body_yaw_rate);
- _mav_put_float(buf, 32, thrust);
- _mav_put_uint8_t(buf, 36, type_mask);
- _mav_put_float_array(buf, 4, q, 4);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
- #else
- mavlink_attitude_target_t packet;
- packet.time_boot_ms = time_boot_ms;
- packet.body_roll_rate = body_roll_rate;
- packet.body_pitch_rate = body_pitch_rate;
- packet.body_yaw_rate = body_yaw_rate;
- packet.thrust = thrust;
- packet.type_mask = type_mask;
- mav_array_memcpy(packet.q, q, sizeof(float)*4);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
- #endif
- msg->msgid = MAVLINK_MSG_ID_ATTITUDE_TARGET;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC);
- }
- /**
- * @brief Encode a attitude_target 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 attitude_target C-struct to read the message contents from
- */
- static inline uint16_t mavlink_msg_attitude_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_target_t* attitude_target)
- {
- return mavlink_msg_attitude_target_pack(system_id, component_id, msg, attitude_target->time_boot_ms, attitude_target->type_mask, attitude_target->q, attitude_target->body_roll_rate, attitude_target->body_pitch_rate, attitude_target->body_yaw_rate, attitude_target->thrust);
- }
- /**
- * @brief Encode a attitude_target 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 attitude_target C-struct to read the message contents from
- */
- static inline uint16_t mavlink_msg_attitude_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_target_t* attitude_target)
- {
- return mavlink_msg_attitude_target_pack_chan(system_id, component_id, chan, msg, attitude_target->time_boot_ms, attitude_target->type_mask, attitude_target->q, attitude_target->body_roll_rate, attitude_target->body_pitch_rate, attitude_target->body_yaw_rate, attitude_target->thrust);
- }
- /**
- * @brief Encode a attitude_target 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 attitude_target C-struct to read the message contents from
- */
- static inline uint16_t mavlink_msg_attitude_target_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_attitude_target_t* attitude_target)
- {
- return mavlink_msg_attitude_target_pack_status(system_id, component_id, _status, msg, attitude_target->time_boot_ms, attitude_target->type_mask, attitude_target->q, attitude_target->body_roll_rate, attitude_target->body_pitch_rate, attitude_target->body_yaw_rate, attitude_target->thrust);
- }
- /**
- * @brief Send a attitude_target message
- * @param chan MAVLink channel to send the message
- *
- * @param time_boot_ms [ms] Timestamp (time since system boot).
- * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle.
- * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
- * @param body_roll_rate [rad/s] Body roll rate
- * @param body_pitch_rate [rad/s] Body pitch rate
- * @param body_yaw_rate [rad/s] Body yaw rate
- * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
- */
- #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
- static inline void mavlink_msg_attitude_target_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN];
- _mav_put_uint32_t(buf, 0, time_boot_ms);
- _mav_put_float(buf, 20, body_roll_rate);
- _mav_put_float(buf, 24, body_pitch_rate);
- _mav_put_float(buf, 28, body_yaw_rate);
- _mav_put_float(buf, 32, thrust);
- _mav_put_uint8_t(buf, 36, type_mask);
- _mav_put_float_array(buf, 4, q, 4);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC);
- #else
- mavlink_attitude_target_t packet;
- packet.time_boot_ms = time_boot_ms;
- packet.body_roll_rate = body_roll_rate;
- packet.body_pitch_rate = body_pitch_rate;
- packet.body_yaw_rate = body_yaw_rate;
- packet.thrust = thrust;
- packet.type_mask = type_mask;
- mav_array_memcpy(packet.q, q, sizeof(float)*4);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC);
- #endif
- }
- /**
- * @brief Send a attitude_target message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
- static inline void mavlink_msg_attitude_target_send_struct(mavlink_channel_t chan, const mavlink_attitude_target_t* attitude_target)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_attitude_target_send(chan, attitude_target->time_boot_ms, attitude_target->type_mask, attitude_target->q, attitude_target->body_roll_rate, attitude_target->body_pitch_rate, attitude_target->body_yaw_rate, attitude_target->thrust);
- #else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)attitude_target, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC);
- #endif
- }
- #if MAVLINK_MSG_ID_ATTITUDE_TARGET_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_attitude_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint32_t(buf, 0, time_boot_ms);
- _mav_put_float(buf, 20, body_roll_rate);
- _mav_put_float(buf, 24, body_pitch_rate);
- _mav_put_float(buf, 28, body_yaw_rate);
- _mav_put_float(buf, 32, thrust);
- _mav_put_uint8_t(buf, 36, type_mask);
- _mav_put_float_array(buf, 4, q, 4);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC);
- #else
- mavlink_attitude_target_t *packet = (mavlink_attitude_target_t *)msgbuf;
- packet->time_boot_ms = time_boot_ms;
- packet->body_roll_rate = body_roll_rate;
- packet->body_pitch_rate = body_pitch_rate;
- packet->body_yaw_rate = body_yaw_rate;
- packet->thrust = thrust;
- packet->type_mask = type_mask;
- mav_array_memcpy(packet->q, q, sizeof(float)*4);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC);
- #endif
- }
- #endif
- #endif
- // MESSAGE ATTITUDE_TARGET UNPACKING
- /**
- * @brief Get field time_boot_ms from attitude_target message
- *
- * @return [ms] Timestamp (time since system boot).
- */
- static inline uint32_t mavlink_msg_attitude_target_get_time_boot_ms(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_uint32_t(msg, 0);
- }
- /**
- * @brief Get field type_mask from attitude_target message
- *
- * @return Bitmap to indicate which dimensions should be ignored by the vehicle.
- */
- static inline uint8_t mavlink_msg_attitude_target_get_type_mask(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_uint8_t(msg, 36);
- }
- /**
- * @brief Get field q from attitude_target message
- *
- * @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
- */
- static inline uint16_t mavlink_msg_attitude_target_get_q(const mavlink_message_t* msg, float *q)
- {
- return _MAV_RETURN_float_array(msg, q, 4, 4);
- }
- /**
- * @brief Get field body_roll_rate from attitude_target message
- *
- * @return [rad/s] Body roll rate
- */
- static inline float mavlink_msg_attitude_target_get_body_roll_rate(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 20);
- }
- /**
- * @brief Get field body_pitch_rate from attitude_target message
- *
- * @return [rad/s] Body pitch rate
- */
- static inline float mavlink_msg_attitude_target_get_body_pitch_rate(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 24);
- }
- /**
- * @brief Get field body_yaw_rate from attitude_target message
- *
- * @return [rad/s] Body yaw rate
- */
- static inline float mavlink_msg_attitude_target_get_body_yaw_rate(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 28);
- }
- /**
- * @brief Get field thrust from attitude_target message
- *
- * @return Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
- */
- static inline float mavlink_msg_attitude_target_get_thrust(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_float(msg, 32);
- }
- /**
- * @brief Decode a attitude_target message into a struct
- *
- * @param msg The message to decode
- * @param attitude_target C-struct to decode the message contents into
- */
- static inline void mavlink_msg_attitude_target_decode(const mavlink_message_t* msg, mavlink_attitude_target_t* attitude_target)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- attitude_target->time_boot_ms = mavlink_msg_attitude_target_get_time_boot_ms(msg);
- mavlink_msg_attitude_target_get_q(msg, attitude_target->q);
- attitude_target->body_roll_rate = mavlink_msg_attitude_target_get_body_roll_rate(msg);
- attitude_target->body_pitch_rate = mavlink_msg_attitude_target_get_body_pitch_rate(msg);
- attitude_target->body_yaw_rate = mavlink_msg_attitude_target_get_body_yaw_rate(msg);
- attitude_target->thrust = mavlink_msg_attitude_target_get_thrust(msg);
- attitude_target->type_mask = mavlink_msg_attitude_target_get_type_mask(msg);
- #else
- uint8_t len = msg->len < MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN? msg->len : MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN;
- memset(attitude_target, 0, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
- memcpy(attitude_target, _MAV_PAYLOAD(msg), len);
- #endif
- }
|