[324] | 1 | // MESSAGE ATTITUDE PACKING
|
---|
| 2 |
|
---|
| 3 | #define MAVLINK_MSG_ID_ATTITUDE 30
|
---|
| 4 |
|
---|
| 5 | typedef struct MAVLINK_PACKED __mavlink_attitude_t
|
---|
| 6 | {
|
---|
| 7 | uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/
|
---|
| 8 | float roll; /*< Roll angle (rad, -pi..+pi)*/
|
---|
| 9 | float pitch; /*< Pitch angle (rad, -pi..+pi)*/
|
---|
| 10 | float yaw; /*< Yaw angle (rad, -pi..+pi)*/
|
---|
| 11 | float rollspeed; /*< Roll angular speed (rad/s)*/
|
---|
| 12 | float pitchspeed; /*< Pitch angular speed (rad/s)*/
|
---|
| 13 | float yawspeed; /*< Yaw angular speed (rad/s)*/
|
---|
| 14 | } mavlink_attitude_t;
|
---|
| 15 |
|
---|
| 16 | #define MAVLINK_MSG_ID_ATTITUDE_LEN 28
|
---|
| 17 | #define MAVLINK_MSG_ID_ATTITUDE_MIN_LEN 28
|
---|
| 18 | #define MAVLINK_MSG_ID_30_LEN 28
|
---|
| 19 | #define MAVLINK_MSG_ID_30_MIN_LEN 28
|
---|
| 20 |
|
---|
| 21 | #define MAVLINK_MSG_ID_ATTITUDE_CRC 39
|
---|
| 22 | #define MAVLINK_MSG_ID_30_CRC 39
|
---|
| 23 |
|
---|
| 24 |
|
---|
| 25 |
|
---|
| 26 | #if MAVLINK_COMMAND_24BIT
|
---|
| 27 | #define MAVLINK_MESSAGE_INFO_ATTITUDE { \
|
---|
| 28 | 30, \
|
---|
| 29 | "ATTITUDE", \
|
---|
| 30 | 7, \
|
---|
| 31 | { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_t, time_boot_ms) }, \
|
---|
| 32 | { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_t, roll) }, \
|
---|
| 33 | { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_t, pitch) }, \
|
---|
| 34 | { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_t, yaw) }, \
|
---|
| 35 | { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_t, rollspeed) }, \
|
---|
| 36 | { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_t, pitchspeed) }, \
|
---|
| 37 | { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_t, yawspeed) }, \
|
---|
| 38 | } \
|
---|
| 39 | }
|
---|
| 40 | #else
|
---|
| 41 | #define MAVLINK_MESSAGE_INFO_ATTITUDE { \
|
---|
| 42 | "ATTITUDE", \
|
---|
| 43 | 7, \
|
---|
| 44 | { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_t, time_boot_ms) }, \
|
---|
| 45 | { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_t, roll) }, \
|
---|
| 46 | { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_t, pitch) }, \
|
---|
| 47 | { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_t, yaw) }, \
|
---|
| 48 | { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_t, rollspeed) }, \
|
---|
| 49 | { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_t, pitchspeed) }, \
|
---|
| 50 | { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_t, yawspeed) }, \
|
---|
| 51 | } \
|
---|
| 52 | }
|
---|
| 53 | #endif
|
---|
| 54 |
|
---|
| 55 | /**
|
---|
| 56 | * @brief Pack a attitude message
|
---|
| 57 | * @param system_id ID of this system
|
---|
| 58 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
| 59 | * @param msg The MAVLink message to compress the data into
|
---|
| 60 | *
|
---|
| 61 | * @param time_boot_ms Timestamp (milliseconds since system boot)
|
---|
| 62 | * @param roll Roll angle (rad, -pi..+pi)
|
---|
| 63 | * @param pitch Pitch angle (rad, -pi..+pi)
|
---|
| 64 | * @param yaw Yaw angle (rad, -pi..+pi)
|
---|
| 65 | * @param rollspeed Roll angular speed (rad/s)
|
---|
| 66 | * @param pitchspeed Pitch angular speed (rad/s)
|
---|
| 67 | * @param yawspeed Yaw angular speed (rad/s)
|
---|
| 68 | * @return length of the message in bytes (excluding serial stream start sign)
|
---|
| 69 | */
|
---|
| 70 | static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
---|
| 71 | uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed)
|
---|
| 72 | {
|
---|
| 73 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 74 | char buf[MAVLINK_MSG_ID_ATTITUDE_LEN];
|
---|
| 75 | _mav_put_uint32_t(buf, 0, time_boot_ms);
|
---|
| 76 | _mav_put_float(buf, 4, roll);
|
---|
| 77 | _mav_put_float(buf, 8, pitch);
|
---|
| 78 | _mav_put_float(buf, 12, yaw);
|
---|
| 79 | _mav_put_float(buf, 16, rollspeed);
|
---|
| 80 | _mav_put_float(buf, 20, pitchspeed);
|
---|
| 81 | _mav_put_float(buf, 24, yawspeed);
|
---|
| 82 |
|
---|
| 83 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_LEN);
|
---|
| 84 | #else
|
---|
| 85 | mavlink_attitude_t packet;
|
---|
| 86 | packet.time_boot_ms = time_boot_ms;
|
---|
| 87 | packet.roll = roll;
|
---|
| 88 | packet.pitch = pitch;
|
---|
| 89 | packet.yaw = yaw;
|
---|
| 90 | packet.rollspeed = rollspeed;
|
---|
| 91 | packet.pitchspeed = pitchspeed;
|
---|
| 92 | packet.yawspeed = yawspeed;
|
---|
| 93 |
|
---|
| 94 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_LEN);
|
---|
| 95 | #endif
|
---|
| 96 |
|
---|
| 97 | msg->msgid = MAVLINK_MSG_ID_ATTITUDE;
|
---|
| 98 | return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
|
---|
| 99 | }
|
---|
| 100 |
|
---|
| 101 | /**
|
---|
| 102 | * @brief Pack a attitude message on a channel
|
---|
| 103 | * @param system_id ID of this system
|
---|
| 104 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
| 105 | * @param chan The MAVLink channel this message will be sent over
|
---|
| 106 | * @param msg The MAVLink message to compress the data into
|
---|
| 107 | * @param time_boot_ms Timestamp (milliseconds since system boot)
|
---|
| 108 | * @param roll Roll angle (rad, -pi..+pi)
|
---|
| 109 | * @param pitch Pitch angle (rad, -pi..+pi)
|
---|
| 110 | * @param yaw Yaw angle (rad, -pi..+pi)
|
---|
| 111 | * @param rollspeed Roll angular speed (rad/s)
|
---|
| 112 | * @param pitchspeed Pitch angular speed (rad/s)
|
---|
| 113 | * @param yawspeed Yaw angular speed (rad/s)
|
---|
| 114 | * @return length of the message in bytes (excluding serial stream start sign)
|
---|
| 115 | */
|
---|
| 116 | static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
---|
| 117 | mavlink_message_t* msg,
|
---|
| 118 | uint32_t time_boot_ms,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed)
|
---|
| 119 | {
|
---|
| 120 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 121 | char buf[MAVLINK_MSG_ID_ATTITUDE_LEN];
|
---|
| 122 | _mav_put_uint32_t(buf, 0, time_boot_ms);
|
---|
| 123 | _mav_put_float(buf, 4, roll);
|
---|
| 124 | _mav_put_float(buf, 8, pitch);
|
---|
| 125 | _mav_put_float(buf, 12, yaw);
|
---|
| 126 | _mav_put_float(buf, 16, rollspeed);
|
---|
| 127 | _mav_put_float(buf, 20, pitchspeed);
|
---|
| 128 | _mav_put_float(buf, 24, yawspeed);
|
---|
| 129 |
|
---|
| 130 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_LEN);
|
---|
| 131 | #else
|
---|
| 132 | mavlink_attitude_t packet;
|
---|
| 133 | packet.time_boot_ms = time_boot_ms;
|
---|
| 134 | packet.roll = roll;
|
---|
| 135 | packet.pitch = pitch;
|
---|
| 136 | packet.yaw = yaw;
|
---|
| 137 | packet.rollspeed = rollspeed;
|
---|
| 138 | packet.pitchspeed = pitchspeed;
|
---|
| 139 | packet.yawspeed = yawspeed;
|
---|
| 140 |
|
---|
| 141 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_LEN);
|
---|
| 142 | #endif
|
---|
| 143 |
|
---|
| 144 | msg->msgid = MAVLINK_MSG_ID_ATTITUDE;
|
---|
| 145 | return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
|
---|
| 146 | }
|
---|
| 147 |
|
---|
| 148 | /**
|
---|
| 149 | * @brief Encode a attitude struct
|
---|
| 150 | *
|
---|
| 151 | * @param system_id ID of this system
|
---|
| 152 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
| 153 | * @param msg The MAVLink message to compress the data into
|
---|
| 154 | * @param attitude C-struct to read the message contents from
|
---|
| 155 | */
|
---|
| 156 | static inline uint16_t mavlink_msg_attitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_t* attitude)
|
---|
| 157 | {
|
---|
| 158 | return mavlink_msg_attitude_pack(system_id, component_id, msg, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed);
|
---|
| 159 | }
|
---|
| 160 |
|
---|
| 161 | /**
|
---|
| 162 | * @brief Encode a attitude struct on a channel
|
---|
| 163 | *
|
---|
| 164 | * @param system_id ID of this system
|
---|
| 165 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
| 166 | * @param chan The MAVLink channel this message will be sent over
|
---|
| 167 | * @param msg The MAVLink message to compress the data into
|
---|
| 168 | * @param attitude C-struct to read the message contents from
|
---|
| 169 | */
|
---|
| 170 | static inline uint16_t mavlink_msg_attitude_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_t* attitude)
|
---|
| 171 | {
|
---|
| 172 | return mavlink_msg_attitude_pack_chan(system_id, component_id, chan, msg, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed);
|
---|
| 173 | }
|
---|
| 174 |
|
---|
| 175 | /**
|
---|
| 176 | * @brief Send a attitude message
|
---|
| 177 | * @param chan MAVLink channel to send the message
|
---|
| 178 | *
|
---|
| 179 | * @param time_boot_ms Timestamp (milliseconds since system boot)
|
---|
| 180 | * @param roll Roll angle (rad, -pi..+pi)
|
---|
| 181 | * @param pitch Pitch angle (rad, -pi..+pi)
|
---|
| 182 | * @param yaw Yaw angle (rad, -pi..+pi)
|
---|
| 183 | * @param rollspeed Roll angular speed (rad/s)
|
---|
| 184 | * @param pitchspeed Pitch angular speed (rad/s)
|
---|
| 185 | * @param yawspeed Yaw angular speed (rad/s)
|
---|
| 186 | */
|
---|
| 187 | #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
---|
| 188 |
|
---|
| 189 | static inline void mavlink_msg_attitude_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed)
|
---|
| 190 | {
|
---|
| 191 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 192 | char buf[MAVLINK_MSG_ID_ATTITUDE_LEN];
|
---|
| 193 | _mav_put_uint32_t(buf, 0, time_boot_ms);
|
---|
| 194 | _mav_put_float(buf, 4, roll);
|
---|
| 195 | _mav_put_float(buf, 8, pitch);
|
---|
| 196 | _mav_put_float(buf, 12, yaw);
|
---|
| 197 | _mav_put_float(buf, 16, rollspeed);
|
---|
| 198 | _mav_put_float(buf, 20, pitchspeed);
|
---|
| 199 | _mav_put_float(buf, 24, yawspeed);
|
---|
| 200 |
|
---|
| 201 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
|
---|
| 202 | #else
|
---|
| 203 | mavlink_attitude_t packet;
|
---|
| 204 | packet.time_boot_ms = time_boot_ms;
|
---|
| 205 | packet.roll = roll;
|
---|
| 206 | packet.pitch = pitch;
|
---|
| 207 | packet.yaw = yaw;
|
---|
| 208 | packet.rollspeed = rollspeed;
|
---|
| 209 | packet.pitchspeed = pitchspeed;
|
---|
| 210 | packet.yawspeed = yawspeed;
|
---|
| 211 |
|
---|
| 212 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
|
---|
| 213 | #endif
|
---|
| 214 | }
|
---|
| 215 |
|
---|
| 216 | /**
|
---|
| 217 | * @brief Send a attitude message
|
---|
| 218 | * @param chan MAVLink channel to send the message
|
---|
| 219 | * @param struct The MAVLink struct to serialize
|
---|
| 220 | */
|
---|
| 221 | static inline void mavlink_msg_attitude_send_struct(mavlink_channel_t chan, const mavlink_attitude_t* attitude)
|
---|
| 222 | {
|
---|
| 223 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 224 | mavlink_msg_attitude_send(chan, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed);
|
---|
| 225 | #else
|
---|
| 226 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)attitude, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
|
---|
| 227 | #endif
|
---|
| 228 | }
|
---|
| 229 |
|
---|
| 230 | #if MAVLINK_MSG_ID_ATTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
|
---|
| 231 | /*
|
---|
| 232 | This varient of _send() can be used to save stack space by re-using
|
---|
| 233 | memory from the receive buffer. The caller provides a
|
---|
| 234 | mavlink_message_t which is the size of a full mavlink message. This
|
---|
| 235 | is usually the receive buffer for the channel, and allows a reply to an
|
---|
| 236 | incoming message with minimum stack space usage.
|
---|
| 237 | */
|
---|
| 238 | static inline void mavlink_msg_attitude_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed)
|
---|
| 239 | {
|
---|
| 240 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 241 | char *buf = (char *)msgbuf;
|
---|
| 242 | _mav_put_uint32_t(buf, 0, time_boot_ms);
|
---|
| 243 | _mav_put_float(buf, 4, roll);
|
---|
| 244 | _mav_put_float(buf, 8, pitch);
|
---|
| 245 | _mav_put_float(buf, 12, yaw);
|
---|
| 246 | _mav_put_float(buf, 16, rollspeed);
|
---|
| 247 | _mav_put_float(buf, 20, pitchspeed);
|
---|
| 248 | _mav_put_float(buf, 24, yawspeed);
|
---|
| 249 |
|
---|
| 250 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
|
---|
| 251 | #else
|
---|
| 252 | mavlink_attitude_t *packet = (mavlink_attitude_t *)msgbuf;
|
---|
| 253 | packet->time_boot_ms = time_boot_ms;
|
---|
| 254 | packet->roll = roll;
|
---|
| 255 | packet->pitch = pitch;
|
---|
| 256 | packet->yaw = yaw;
|
---|
| 257 | packet->rollspeed = rollspeed;
|
---|
| 258 | packet->pitchspeed = pitchspeed;
|
---|
| 259 | packet->yawspeed = yawspeed;
|
---|
| 260 |
|
---|
| 261 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
|
---|
| 262 | #endif
|
---|
| 263 | }
|
---|
| 264 | #endif
|
---|
| 265 |
|
---|
| 266 | #endif
|
---|
| 267 |
|
---|
| 268 | // MESSAGE ATTITUDE UNPACKING
|
---|
| 269 |
|
---|
| 270 |
|
---|
| 271 | /**
|
---|
| 272 | * @brief Get field time_boot_ms from attitude message
|
---|
| 273 | *
|
---|
| 274 | * @return Timestamp (milliseconds since system boot)
|
---|
| 275 | */
|
---|
| 276 | static inline uint32_t mavlink_msg_attitude_get_time_boot_ms(const mavlink_message_t* msg)
|
---|
| 277 | {
|
---|
| 278 | return _MAV_RETURN_uint32_t(msg, 0);
|
---|
| 279 | }
|
---|
| 280 |
|
---|
| 281 | /**
|
---|
| 282 | * @brief Get field roll from attitude message
|
---|
| 283 | *
|
---|
| 284 | * @return Roll angle (rad, -pi..+pi)
|
---|
| 285 | */
|
---|
| 286 | static inline float mavlink_msg_attitude_get_roll(const mavlink_message_t* msg)
|
---|
| 287 | {
|
---|
| 288 | return _MAV_RETURN_float(msg, 4);
|
---|
| 289 | }
|
---|
| 290 |
|
---|
| 291 | /**
|
---|
| 292 | * @brief Get field pitch from attitude message
|
---|
| 293 | *
|
---|
| 294 | * @return Pitch angle (rad, -pi..+pi)
|
---|
| 295 | */
|
---|
| 296 | static inline float mavlink_msg_attitude_get_pitch(const mavlink_message_t* msg)
|
---|
| 297 | {
|
---|
| 298 | return _MAV_RETURN_float(msg, 8);
|
---|
| 299 | }
|
---|
| 300 |
|
---|
| 301 | /**
|
---|
| 302 | * @brief Get field yaw from attitude message
|
---|
| 303 | *
|
---|
| 304 | * @return Yaw angle (rad, -pi..+pi)
|
---|
| 305 | */
|
---|
| 306 | static inline float mavlink_msg_attitude_get_yaw(const mavlink_message_t* msg)
|
---|
| 307 | {
|
---|
| 308 | return _MAV_RETURN_float(msg, 12);
|
---|
| 309 | }
|
---|
| 310 |
|
---|
| 311 | /**
|
---|
| 312 | * @brief Get field rollspeed from attitude message
|
---|
| 313 | *
|
---|
| 314 | * @return Roll angular speed (rad/s)
|
---|
| 315 | */
|
---|
| 316 | static inline float mavlink_msg_attitude_get_rollspeed(const mavlink_message_t* msg)
|
---|
| 317 | {
|
---|
| 318 | return _MAV_RETURN_float(msg, 16);
|
---|
| 319 | }
|
---|
| 320 |
|
---|
| 321 | /**
|
---|
| 322 | * @brief Get field pitchspeed from attitude message
|
---|
| 323 | *
|
---|
| 324 | * @return Pitch angular speed (rad/s)
|
---|
| 325 | */
|
---|
| 326 | static inline float mavlink_msg_attitude_get_pitchspeed(const mavlink_message_t* msg)
|
---|
| 327 | {
|
---|
| 328 | return _MAV_RETURN_float(msg, 20);
|
---|
| 329 | }
|
---|
| 330 |
|
---|
| 331 | /**
|
---|
| 332 | * @brief Get field yawspeed from attitude message
|
---|
| 333 | *
|
---|
| 334 | * @return Yaw angular speed (rad/s)
|
---|
| 335 | */
|
---|
| 336 | static inline float mavlink_msg_attitude_get_yawspeed(const mavlink_message_t* msg)
|
---|
| 337 | {
|
---|
| 338 | return _MAV_RETURN_float(msg, 24);
|
---|
| 339 | }
|
---|
| 340 |
|
---|
| 341 | /**
|
---|
| 342 | * @brief Decode a attitude message into a struct
|
---|
| 343 | *
|
---|
| 344 | * @param msg The message to decode
|
---|
| 345 | * @param attitude C-struct to decode the message contents into
|
---|
| 346 | */
|
---|
| 347 | static inline void mavlink_msg_attitude_decode(const mavlink_message_t* msg, mavlink_attitude_t* attitude)
|
---|
| 348 | {
|
---|
| 349 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
| 350 | attitude->time_boot_ms = mavlink_msg_attitude_get_time_boot_ms(msg);
|
---|
| 351 | attitude->roll = mavlink_msg_attitude_get_roll(msg);
|
---|
| 352 | attitude->pitch = mavlink_msg_attitude_get_pitch(msg);
|
---|
| 353 | attitude->yaw = mavlink_msg_attitude_get_yaw(msg);
|
---|
| 354 | attitude->rollspeed = mavlink_msg_attitude_get_rollspeed(msg);
|
---|
| 355 | attitude->pitchspeed = mavlink_msg_attitude_get_pitchspeed(msg);
|
---|
| 356 | attitude->yawspeed = mavlink_msg_attitude_get_yawspeed(msg);
|
---|
| 357 | #else
|
---|
| 358 | uint8_t len = msg->len < MAVLINK_MSG_ID_ATTITUDE_LEN? msg->len : MAVLINK_MSG_ID_ATTITUDE_LEN;
|
---|
| 359 | memset(attitude, 0, MAVLINK_MSG_ID_ATTITUDE_LEN);
|
---|
| 360 | memcpy(attitude, _MAV_PAYLOAD(msg), len);
|
---|
| 361 | #endif
|
---|
| 362 | }
|
---|