00001
00002
00003 #define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET 82
00004
00005 typedef struct __mavlink_set_attitude_target_t
00006 {
00007 uint32_t time_boot_ms;
00008 float q[4];
00009 float body_roll_rate;
00010 float body_pitch_rate;
00011 float body_yaw_rate;
00012 float thrust;
00013 uint8_t target_system;
00014 uint8_t target_component;
00015 uint8_t type_mask;
00016 } mavlink_set_attitude_target_t;
00017
00018 #define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN 39
00019 #define MAVLINK_MSG_ID_82_LEN 39
00020
00021 #define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC 49
00022 #define MAVLINK_MSG_ID_82_CRC 49
00023
00024 #define MAVLINK_MSG_SET_ATTITUDE_TARGET_FIELD_Q_LEN 4
00025
00026 #define MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET { \
00027 "SET_ATTITUDE_TARGET", \
00028 9, \
00029 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_attitude_target_t, time_boot_ms) }, \
00030 { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_set_attitude_target_t, q) }, \
00031 { "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_attitude_target_t, body_roll_rate) }, \
00032 { "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_attitude_target_t, body_pitch_rate) }, \
00033 { "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_attitude_target_t, body_yaw_rate) }, \
00034 { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_attitude_target_t, thrust) }, \
00035 { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_set_attitude_target_t, target_system) }, \
00036 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_set_attitude_target_t, target_component) }, \
00037 { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_set_attitude_target_t, type_mask) }, \
00038 } \
00039 }
00040
00041
00059 static inline uint16_t mavlink_msg_set_attitude_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00060 uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust)
00061 {
00062 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00063 char buf[MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN];
00064 _mav_put_uint32_t(buf, 0, time_boot_ms);
00065 _mav_put_float(buf, 20, body_roll_rate);
00066 _mav_put_float(buf, 24, body_pitch_rate);
00067 _mav_put_float(buf, 28, body_yaw_rate);
00068 _mav_put_float(buf, 32, thrust);
00069 _mav_put_uint8_t(buf, 36, target_system);
00070 _mav_put_uint8_t(buf, 37, target_component);
00071 _mav_put_uint8_t(buf, 38, type_mask);
00072 _mav_put_float_array(buf, 4, q, 4);
00073 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN);
00074 #else
00075 mavlink_set_attitude_target_t packet;
00076 packet.time_boot_ms = time_boot_ms;
00077 packet.body_roll_rate = body_roll_rate;
00078 packet.body_pitch_rate = body_pitch_rate;
00079 packet.body_yaw_rate = body_yaw_rate;
00080 packet.thrust = thrust;
00081 packet.target_system = target_system;
00082 packet.target_component = target_component;
00083 packet.type_mask = type_mask;
00084 mav_array_memcpy(packet.q, q, sizeof(float)*4);
00085 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN);
00086 #endif
00087
00088 msg->msgid = MAVLINK_MSG_ID_SET_ATTITUDE_TARGET;
00089 #if MAVLINK_CRC_EXTRA
00090 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC);
00091 #else
00092 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN);
00093 #endif
00094 }
00095
00113 static inline uint16_t mavlink_msg_set_attitude_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00114 mavlink_message_t* msg,
00115 uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t type_mask,const float *q,float body_roll_rate,float body_pitch_rate,float body_yaw_rate,float thrust)
00116 {
00117 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00118 char buf[MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN];
00119 _mav_put_uint32_t(buf, 0, time_boot_ms);
00120 _mav_put_float(buf, 20, body_roll_rate);
00121 _mav_put_float(buf, 24, body_pitch_rate);
00122 _mav_put_float(buf, 28, body_yaw_rate);
00123 _mav_put_float(buf, 32, thrust);
00124 _mav_put_uint8_t(buf, 36, target_system);
00125 _mav_put_uint8_t(buf, 37, target_component);
00126 _mav_put_uint8_t(buf, 38, type_mask);
00127 _mav_put_float_array(buf, 4, q, 4);
00128 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN);
00129 #else
00130 mavlink_set_attitude_target_t packet;
00131 packet.time_boot_ms = time_boot_ms;
00132 packet.body_roll_rate = body_roll_rate;
00133 packet.body_pitch_rate = body_pitch_rate;
00134 packet.body_yaw_rate = body_yaw_rate;
00135 packet.thrust = thrust;
00136 packet.target_system = target_system;
00137 packet.target_component = target_component;
00138 packet.type_mask = type_mask;
00139 mav_array_memcpy(packet.q, q, sizeof(float)*4);
00140 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN);
00141 #endif
00142
00143 msg->msgid = MAVLINK_MSG_ID_SET_ATTITUDE_TARGET;
00144 #if MAVLINK_CRC_EXTRA
00145 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC);
00146 #else
00147 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN);
00148 #endif
00149 }
00150
00159 static inline uint16_t mavlink_msg_set_attitude_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_attitude_target_t* set_attitude_target)
00160 {
00161 return mavlink_msg_set_attitude_target_pack(system_id, component_id, msg, set_attitude_target->time_boot_ms, set_attitude_target->target_system, set_attitude_target->target_component, set_attitude_target->type_mask, set_attitude_target->q, set_attitude_target->body_roll_rate, set_attitude_target->body_pitch_rate, set_attitude_target->body_yaw_rate, set_attitude_target->thrust);
00162 }
00163
00173 static inline uint16_t mavlink_msg_set_attitude_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_attitude_target_t* set_attitude_target)
00174 {
00175 return mavlink_msg_set_attitude_target_pack_chan(system_id, component_id, chan, msg, set_attitude_target->time_boot_ms, set_attitude_target->target_system, set_attitude_target->target_component, set_attitude_target->type_mask, set_attitude_target->q, set_attitude_target->body_roll_rate, set_attitude_target->body_pitch_rate, set_attitude_target->body_yaw_rate, set_attitude_target->thrust);
00176 }
00177
00192 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00193
00194 static inline void mavlink_msg_set_attitude_target_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust)
00195 {
00196 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00197 char buf[MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN];
00198 _mav_put_uint32_t(buf, 0, time_boot_ms);
00199 _mav_put_float(buf, 20, body_roll_rate);
00200 _mav_put_float(buf, 24, body_pitch_rate);
00201 _mav_put_float(buf, 28, body_yaw_rate);
00202 _mav_put_float(buf, 32, thrust);
00203 _mav_put_uint8_t(buf, 36, target_system);
00204 _mav_put_uint8_t(buf, 37, target_component);
00205 _mav_put_uint8_t(buf, 38, type_mask);
00206 _mav_put_float_array(buf, 4, q, 4);
00207 #if MAVLINK_CRC_EXTRA
00208 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC);
00209 #else
00210 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN);
00211 #endif
00212 #else
00213 mavlink_set_attitude_target_t packet;
00214 packet.time_boot_ms = time_boot_ms;
00215 packet.body_roll_rate = body_roll_rate;
00216 packet.body_pitch_rate = body_pitch_rate;
00217 packet.body_yaw_rate = body_yaw_rate;
00218 packet.thrust = thrust;
00219 packet.target_system = target_system;
00220 packet.target_component = target_component;
00221 packet.type_mask = type_mask;
00222 mav_array_memcpy(packet.q, q, sizeof(float)*4);
00223 #if MAVLINK_CRC_EXTRA
00224 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, (const char *)&packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC);
00225 #else
00226 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, (const char *)&packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN);
00227 #endif
00228 #endif
00229 }
00230
00231 #if MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00232
00233
00234
00235
00236
00237
00238
00239 static inline void mavlink_msg_set_attitude_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust)
00240 {
00241 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00242 char *buf = (char *)msgbuf;
00243 _mav_put_uint32_t(buf, 0, time_boot_ms);
00244 _mav_put_float(buf, 20, body_roll_rate);
00245 _mav_put_float(buf, 24, body_pitch_rate);
00246 _mav_put_float(buf, 28, body_yaw_rate);
00247 _mav_put_float(buf, 32, thrust);
00248 _mav_put_uint8_t(buf, 36, target_system);
00249 _mav_put_uint8_t(buf, 37, target_component);
00250 _mav_put_uint8_t(buf, 38, type_mask);
00251 _mav_put_float_array(buf, 4, q, 4);
00252 #if MAVLINK_CRC_EXTRA
00253 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC);
00254 #else
00255 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN);
00256 #endif
00257 #else
00258 mavlink_set_attitude_target_t *packet = (mavlink_set_attitude_target_t *)msgbuf;
00259 packet->time_boot_ms = time_boot_ms;
00260 packet->body_roll_rate = body_roll_rate;
00261 packet->body_pitch_rate = body_pitch_rate;
00262 packet->body_yaw_rate = body_yaw_rate;
00263 packet->thrust = thrust;
00264 packet->target_system = target_system;
00265 packet->target_component = target_component;
00266 packet->type_mask = type_mask;
00267 mav_array_memcpy(packet->q, q, sizeof(float)*4);
00268 #if MAVLINK_CRC_EXTRA
00269 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, (const char *)packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC);
00270 #else
00271 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, (const char *)packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN);
00272 #endif
00273 #endif
00274 }
00275 #endif
00276
00277 #endif
00278
00279
00280
00281
00287 static inline uint32_t mavlink_msg_set_attitude_target_get_time_boot_ms(const mavlink_message_t* msg)
00288 {
00289 return _MAV_RETURN_uint32_t(msg, 0);
00290 }
00291
00297 static inline uint8_t mavlink_msg_set_attitude_target_get_target_system(const mavlink_message_t* msg)
00298 {
00299 return _MAV_RETURN_uint8_t(msg, 36);
00300 }
00301
00307 static inline uint8_t mavlink_msg_set_attitude_target_get_target_component(const mavlink_message_t* msg)
00308 {
00309 return _MAV_RETURN_uint8_t(msg, 37);
00310 }
00311
00317 static inline uint8_t mavlink_msg_set_attitude_target_get_type_mask(const mavlink_message_t* msg)
00318 {
00319 return _MAV_RETURN_uint8_t(msg, 38);
00320 }
00321
00327 static inline uint16_t mavlink_msg_set_attitude_target_get_q(const mavlink_message_t* msg, float *q)
00328 {
00329 return _MAV_RETURN_float_array(msg, q, 4, 4);
00330 }
00331
00337 static inline float mavlink_msg_set_attitude_target_get_body_roll_rate(const mavlink_message_t* msg)
00338 {
00339 return _MAV_RETURN_float(msg, 20);
00340 }
00341
00347 static inline float mavlink_msg_set_attitude_target_get_body_pitch_rate(const mavlink_message_t* msg)
00348 {
00349 return _MAV_RETURN_float(msg, 24);
00350 }
00351
00357 static inline float mavlink_msg_set_attitude_target_get_body_yaw_rate(const mavlink_message_t* msg)
00358 {
00359 return _MAV_RETURN_float(msg, 28);
00360 }
00361
00367 static inline float mavlink_msg_set_attitude_target_get_thrust(const mavlink_message_t* msg)
00368 {
00369 return _MAV_RETURN_float(msg, 32);
00370 }
00371
00378 static inline void mavlink_msg_set_attitude_target_decode(const mavlink_message_t* msg, mavlink_set_attitude_target_t* set_attitude_target)
00379 {
00380 #if MAVLINK_NEED_BYTE_SWAP
00381 set_attitude_target->time_boot_ms = mavlink_msg_set_attitude_target_get_time_boot_ms(msg);
00382 mavlink_msg_set_attitude_target_get_q(msg, set_attitude_target->q);
00383 set_attitude_target->body_roll_rate = mavlink_msg_set_attitude_target_get_body_roll_rate(msg);
00384 set_attitude_target->body_pitch_rate = mavlink_msg_set_attitude_target_get_body_pitch_rate(msg);
00385 set_attitude_target->body_yaw_rate = mavlink_msg_set_attitude_target_get_body_yaw_rate(msg);
00386 set_attitude_target->thrust = mavlink_msg_set_attitude_target_get_thrust(msg);
00387 set_attitude_target->target_system = mavlink_msg_set_attitude_target_get_target_system(msg);
00388 set_attitude_target->target_component = mavlink_msg_set_attitude_target_get_target_component(msg);
00389 set_attitude_target->type_mask = mavlink_msg_set_attitude_target_get_type_mask(msg);
00390 #else
00391 memcpy(set_attitude_target, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN);
00392 #endif
00393 }