mavlink_msg_attitude.h
Go to the documentation of this file.
00001 // MESSAGE ATTITUDE PACKING
00002 
00003 #define MAVLINK_MSG_ID_ATTITUDE 30
00004 
00005 typedef struct __mavlink_attitude_t
00006 {
00007  uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/
00008  float roll; /*< Roll angle (rad, -pi..+pi)*/
00009  float pitch; /*< Pitch angle (rad, -pi..+pi)*/
00010  float yaw; /*< Yaw angle (rad, -pi..+pi)*/
00011  float rollspeed; /*< Roll angular speed (rad/s)*/
00012  float pitchspeed; /*< Pitch angular speed (rad/s)*/
00013  float yawspeed; /*< Yaw angular speed (rad/s)*/
00014 } mavlink_attitude_t;
00015 
00016 #define MAVLINK_MSG_ID_ATTITUDE_LEN 28
00017 #define MAVLINK_MSG_ID_30_LEN 28
00018 
00019 #define MAVLINK_MSG_ID_ATTITUDE_CRC 39
00020 #define MAVLINK_MSG_ID_30_CRC 39
00021 
00022 
00023 
00024 #define MAVLINK_MESSAGE_INFO_ATTITUDE { \
00025         "ATTITUDE", \
00026         7, \
00027         {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_t, time_boot_ms) }, \
00028          { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_t, roll) }, \
00029          { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_t, pitch) }, \
00030          { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_t, yaw) }, \
00031          { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_t, rollspeed) }, \
00032          { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_t, pitchspeed) }, \
00033          { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_t, yawspeed) }, \
00034          } \
00035 }
00036 
00037 
00053 static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00054                                                        uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed)
00055 {
00056 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00057         char buf[MAVLINK_MSG_ID_ATTITUDE_LEN];
00058         _mav_put_uint32_t(buf, 0, time_boot_ms);
00059         _mav_put_float(buf, 4, roll);
00060         _mav_put_float(buf, 8, pitch);
00061         _mav_put_float(buf, 12, yaw);
00062         _mav_put_float(buf, 16, rollspeed);
00063         _mav_put_float(buf, 20, pitchspeed);
00064         _mav_put_float(buf, 24, yawspeed);
00065 
00066         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_LEN);
00067 #else
00068         mavlink_attitude_t packet;
00069         packet.time_boot_ms = time_boot_ms;
00070         packet.roll = roll;
00071         packet.pitch = pitch;
00072         packet.yaw = yaw;
00073         packet.rollspeed = rollspeed;
00074         packet.pitchspeed = pitchspeed;
00075         packet.yawspeed = yawspeed;
00076 
00077         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_LEN);
00078 #endif
00079 
00080         msg->msgid = MAVLINK_MSG_ID_ATTITUDE;
00081 #if MAVLINK_CRC_EXTRA
00082     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
00083 #else
00084     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_LEN);
00085 #endif
00086 }
00087 
00103 static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00104                                                            mavlink_message_t* msg,
00105                                                            uint32_t time_boot_ms,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed)
00106 {
00107 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00108         char buf[MAVLINK_MSG_ID_ATTITUDE_LEN];
00109         _mav_put_uint32_t(buf, 0, time_boot_ms);
00110         _mav_put_float(buf, 4, roll);
00111         _mav_put_float(buf, 8, pitch);
00112         _mav_put_float(buf, 12, yaw);
00113         _mav_put_float(buf, 16, rollspeed);
00114         _mav_put_float(buf, 20, pitchspeed);
00115         _mav_put_float(buf, 24, yawspeed);
00116 
00117         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_LEN);
00118 #else
00119         mavlink_attitude_t packet;
00120         packet.time_boot_ms = time_boot_ms;
00121         packet.roll = roll;
00122         packet.pitch = pitch;
00123         packet.yaw = yaw;
00124         packet.rollspeed = rollspeed;
00125         packet.pitchspeed = pitchspeed;
00126         packet.yawspeed = yawspeed;
00127 
00128         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_LEN);
00129 #endif
00130 
00131         msg->msgid = MAVLINK_MSG_ID_ATTITUDE;
00132 #if MAVLINK_CRC_EXTRA
00133     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
00134 #else
00135     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_LEN);
00136 #endif
00137 }
00138 
00147 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)
00148 {
00149         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);
00150 }
00151 
00161 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)
00162 {
00163         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);
00164 }
00165 
00178 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00179 
00180 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)
00181 {
00182 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00183         char buf[MAVLINK_MSG_ID_ATTITUDE_LEN];
00184         _mav_put_uint32_t(buf, 0, time_boot_ms);
00185         _mav_put_float(buf, 4, roll);
00186         _mav_put_float(buf, 8, pitch);
00187         _mav_put_float(buf, 12, yaw);
00188         _mav_put_float(buf, 16, rollspeed);
00189         _mav_put_float(buf, 20, pitchspeed);
00190         _mav_put_float(buf, 24, yawspeed);
00191 
00192 #if MAVLINK_CRC_EXTRA
00193     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
00194 #else
00195     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_LEN);
00196 #endif
00197 #else
00198         mavlink_attitude_t packet;
00199         packet.time_boot_ms = time_boot_ms;
00200         packet.roll = roll;
00201         packet.pitch = pitch;
00202         packet.yaw = yaw;
00203         packet.rollspeed = rollspeed;
00204         packet.pitchspeed = pitchspeed;
00205         packet.yawspeed = yawspeed;
00206 
00207 #if MAVLINK_CRC_EXTRA
00208     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
00209 #else
00210     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_LEN);
00211 #endif
00212 #endif
00213 }
00214 
00215 #if MAVLINK_MSG_ID_ATTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00216 /*
00217   This varient of _send() can be used to save stack space by re-using
00218   memory from the receive buffer.  The caller provides a
00219   mavlink_message_t which is the size of a full mavlink message. This
00220   is usually the receive buffer for the channel, and allows a reply to an
00221   incoming message with minimum stack space usage.
00222  */
00223 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)
00224 {
00225 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00226         char *buf = (char *)msgbuf;
00227         _mav_put_uint32_t(buf, 0, time_boot_ms);
00228         _mav_put_float(buf, 4, roll);
00229         _mav_put_float(buf, 8, pitch);
00230         _mav_put_float(buf, 12, yaw);
00231         _mav_put_float(buf, 16, rollspeed);
00232         _mav_put_float(buf, 20, pitchspeed);
00233         _mav_put_float(buf, 24, yawspeed);
00234 
00235 #if MAVLINK_CRC_EXTRA
00236     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
00237 #else
00238     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_LEN);
00239 #endif
00240 #else
00241         mavlink_attitude_t *packet = (mavlink_attitude_t *)msgbuf;
00242         packet->time_boot_ms = time_boot_ms;
00243         packet->roll = roll;
00244         packet->pitch = pitch;
00245         packet->yaw = yaw;
00246         packet->rollspeed = rollspeed;
00247         packet->pitchspeed = pitchspeed;
00248         packet->yawspeed = yawspeed;
00249 
00250 #if MAVLINK_CRC_EXTRA
00251     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
00252 #else
00253     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_LEN);
00254 #endif
00255 #endif
00256 }
00257 #endif
00258 
00259 #endif
00260 
00261 // MESSAGE ATTITUDE UNPACKING
00262 
00263 
00269 static inline uint32_t mavlink_msg_attitude_get_time_boot_ms(const mavlink_message_t* msg)
00270 {
00271         return _MAV_RETURN_uint32_t(msg,  0);
00272 }
00273 
00279 static inline float mavlink_msg_attitude_get_roll(const mavlink_message_t* msg)
00280 {
00281         return _MAV_RETURN_float(msg,  4);
00282 }
00283 
00289 static inline float mavlink_msg_attitude_get_pitch(const mavlink_message_t* msg)
00290 {
00291         return _MAV_RETURN_float(msg,  8);
00292 }
00293 
00299 static inline float mavlink_msg_attitude_get_yaw(const mavlink_message_t* msg)
00300 {
00301         return _MAV_RETURN_float(msg,  12);
00302 }
00303 
00309 static inline float mavlink_msg_attitude_get_rollspeed(const mavlink_message_t* msg)
00310 {
00311         return _MAV_RETURN_float(msg,  16);
00312 }
00313 
00319 static inline float mavlink_msg_attitude_get_pitchspeed(const mavlink_message_t* msg)
00320 {
00321         return _MAV_RETURN_float(msg,  20);
00322 }
00323 
00329 static inline float mavlink_msg_attitude_get_yawspeed(const mavlink_message_t* msg)
00330 {
00331         return _MAV_RETURN_float(msg,  24);
00332 }
00333 
00340 static inline void mavlink_msg_attitude_decode(const mavlink_message_t* msg, mavlink_attitude_t* attitude)
00341 {
00342 #if MAVLINK_NEED_BYTE_SWAP
00343         attitude->time_boot_ms = mavlink_msg_attitude_get_time_boot_ms(msg);
00344         attitude->roll = mavlink_msg_attitude_get_roll(msg);
00345         attitude->pitch = mavlink_msg_attitude_get_pitch(msg);
00346         attitude->yaw = mavlink_msg_attitude_get_yaw(msg);
00347         attitude->rollspeed = mavlink_msg_attitude_get_rollspeed(msg);
00348         attitude->pitchspeed = mavlink_msg_attitude_get_pitchspeed(msg);
00349         attitude->yawspeed = mavlink_msg_attitude_get_yawspeed(msg);
00350 #else
00351         memcpy(attitude, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATTITUDE_LEN);
00352 #endif
00353 }


dji_sdk_dji2mav
Author(s):
autogenerated on Thu Jun 6 2019 17:55:34