3 #define MAVLINK_MSG_ID_ATTITUDE 30
16 #define MAVLINK_MSG_ID_ATTITUDE_LEN 28
17 #define MAVLINK_MSG_ID_30_LEN 28
19 #define MAVLINK_MSG_ID_ATTITUDE_CRC 39
20 #define MAVLINK_MSG_ID_30_CRC 39
24 #define MAVLINK_MESSAGE_INFO_ATTITUDE { \
27 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_t, time_boot_ms) }, \
28 { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_t, roll) }, \
29 { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_t, pitch) }, \
30 { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_t, yaw) }, \
31 { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_t, rollspeed) }, \
32 { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_t, pitchspeed) }, \
33 { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_t, yawspeed) }, \
53 static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
54 uint32_t time_boot_ms,
float roll,
float pitch,
float yaw,
float rollspeed,
float pitchspeed,
float yawspeed)
56 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
103 static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
104 mavlink_message_t* msg,
105 uint32_t time_boot_ms,
float roll,
float pitch,
float yaw,
float rollspeed,
float pitchspeed,
float yawspeed)
107 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
132 #if MAVLINK_CRC_EXTRA
147 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)
161 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)
163 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);
178 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
180 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)
182 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
192 #if MAVLINK_CRC_EXTRA
207 #if MAVLINK_CRC_EXTRA
215 #if MAVLINK_MSG_ID_ATTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
223 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)
225 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
226 char *buf = (
char *)msgbuf;
235 #if MAVLINK_CRC_EXTRA
250 #if MAVLINK_CRC_EXTRA
269 static inline uint32_t mavlink_msg_attitude_get_time_boot_ms(
const mavlink_message_t* msg)
271 return _MAV_RETURN_uint32_t(msg, 0);
279 static inline float mavlink_msg_attitude_get_roll(
const mavlink_message_t* msg)
281 return _MAV_RETURN_float(msg, 4);
289 static inline float mavlink_msg_attitude_get_pitch(
const mavlink_message_t* msg)
291 return _MAV_RETURN_float(msg, 8);
299 static inline float mavlink_msg_attitude_get_yaw(
const mavlink_message_t* msg)
301 return _MAV_RETURN_float(msg, 12);
309 static inline float mavlink_msg_attitude_get_rollspeed(
const mavlink_message_t* msg)
311 return _MAV_RETURN_float(msg, 16);
319 static inline float mavlink_msg_attitude_get_pitchspeed(
const mavlink_message_t* msg)
321 return _MAV_RETURN_float(msg, 20);
329 static inline float mavlink_msg_attitude_get_yawspeed(
const mavlink_message_t* msg)
331 return _MAV_RETURN_float(msg, 24);
340 static inline void mavlink_msg_attitude_decode(
const mavlink_message_t* msg,
mavlink_attitude_t* attitude)
342 #if MAVLINK_NEED_BYTE_SWAP
343 attitude->
time_boot_ms = mavlink_msg_attitude_get_time_boot_ms(msg);
344 attitude->
roll = mavlink_msg_attitude_get_roll(msg);
345 attitude->
pitch = mavlink_msg_attitude_get_pitch(msg);
346 attitude->
yaw = mavlink_msg_attitude_get_yaw(msg);
347 attitude->
rollspeed = mavlink_msg_attitude_get_rollspeed(msg);
348 attitude->
pitchspeed = mavlink_msg_attitude_get_pitchspeed(msg);
349 attitude->
yawspeed = mavlink_msg_attitude_get_yawspeed(msg);
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:145
float roll
Roll angle (rad, -pi..+pi)
Definition: mavlink_msg_attitude.h:8
float pitchspeed
Pitch angular speed (rad/s)
Definition: mavlink_msg_attitude.h:12
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
Definition: mavlink_helpers.h:105
float pitch
Pitch angle (rad, -pi..+pi)
Definition: mavlink_msg_attitude.h:9
#define MAVLINK_MSG_ID_ATTITUDE_LEN
Definition: mavlink_msg_attitude.h:16
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
uint32_t time_boot_ms
Timestamp (milliseconds since system boot)
Definition: mavlink_msg_attitude.h:7
mavlink_channel_t
Definition: mavlink_types.h:178
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
float yawspeed
Yaw angular speed (rad/s)
Definition: mavlink_msg_attitude.h:13
int16_t pitch
Definition: accelerometer.h:52
int16_t yaw
Definition: sensors.h:31
#define MAVLINK_MSG_ID_ATTITUDE_CRC
Definition: mavlink_msg_attitude.h:19
Definition: mavlink_msg_attitude.h:5
float rollspeed
Roll angular speed (rad/s)
Definition: mavlink_msg_attitude.h:11
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
Finalize a MAVLink message with channel assignment.
Definition: mavlink_helpers.h:71
float yaw
Yaw angle (rad, -pi..+pi)
Definition: mavlink_msg_attitude.h:10
struct __mavlink_attitude_t mavlink_attitude_t
#define MAVLINK_MSG_ID_ATTITUDE
Definition: mavlink_msg_attitude.h:3
int16_t roll
Definition: accelerometer.h:51
#define _mav_put_uint32_t(buf, wire_offset, b)
Definition: protocol.h:141