mavlink_msg_gimbal_manager_set_attitude.h 22 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380
  1. #pragma once
  2. // MESSAGE GIMBAL_MANAGER_SET_ATTITUDE PACKING
  3. #define MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE 282
  4. typedef struct __mavlink_gimbal_manager_set_attitude_t {
  5. uint32_t flags; /*< High level gimbal manager flags to use.*/
  6. float q[4]; /*< Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set)*/
  7. float angular_velocity_x; /*< [rad/s] X component of angular velocity, positive is rolling to the right, NaN to be ignored.*/
  8. float angular_velocity_y; /*< [rad/s] Y component of angular velocity, positive is pitching up, NaN to be ignored.*/
  9. float angular_velocity_z; /*< [rad/s] Z component of angular velocity, positive is yawing to the right, NaN to be ignored.*/
  10. uint8_t target_system; /*< System ID*/
  11. uint8_t target_component; /*< Component ID*/
  12. uint8_t gimbal_device_id; /*< Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).*/
  13. } mavlink_gimbal_manager_set_attitude_t;
  14. #define MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN 35
  15. #define MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_MIN_LEN 35
  16. #define MAVLINK_MSG_ID_282_LEN 35
  17. #define MAVLINK_MSG_ID_282_MIN_LEN 35
  18. #define MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_CRC 123
  19. #define MAVLINK_MSG_ID_282_CRC 123
  20. #define MAVLINK_MSG_GIMBAL_MANAGER_SET_ATTITUDE_FIELD_Q_LEN 4
  21. #if MAVLINK_COMMAND_24BIT
  22. #define MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_SET_ATTITUDE { \
  23. 282, \
  24. "GIMBAL_MANAGER_SET_ATTITUDE", \
  25. 8, \
  26. { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gimbal_manager_set_attitude_t, target_system) }, \
  27. { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gimbal_manager_set_attitude_t, target_component) }, \
  28. { "flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gimbal_manager_set_attitude_t, flags) }, \
  29. { "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gimbal_manager_set_attitude_t, gimbal_device_id) }, \
  30. { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_gimbal_manager_set_attitude_t, q) }, \
  31. { "angular_velocity_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_manager_set_attitude_t, angular_velocity_x) }, \
  32. { "angular_velocity_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_manager_set_attitude_t, angular_velocity_y) }, \
  33. { "angular_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gimbal_manager_set_attitude_t, angular_velocity_z) }, \
  34. } \
  35. }
  36. #else
  37. #define MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_SET_ATTITUDE { \
  38. "GIMBAL_MANAGER_SET_ATTITUDE", \
  39. 8, \
  40. { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gimbal_manager_set_attitude_t, target_system) }, \
  41. { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gimbal_manager_set_attitude_t, target_component) }, \
  42. { "flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gimbal_manager_set_attitude_t, flags) }, \
  43. { "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gimbal_manager_set_attitude_t, gimbal_device_id) }, \
  44. { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_gimbal_manager_set_attitude_t, q) }, \
  45. { "angular_velocity_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_manager_set_attitude_t, angular_velocity_x) }, \
  46. { "angular_velocity_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_manager_set_attitude_t, angular_velocity_y) }, \
  47. { "angular_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gimbal_manager_set_attitude_t, angular_velocity_z) }, \
  48. } \
  49. }
  50. #endif
  51. /**
  52. * @brief Pack a gimbal_manager_set_attitude message
  53. * @param system_id ID of this system
  54. * @param component_id ID of this component (e.g. 200 for IMU)
  55. * @param msg The MAVLink message to compress the data into
  56. *
  57. * @param target_system System ID
  58. * @param target_component Component ID
  59. * @param flags High level gimbal manager flags to use.
  60. * @param gimbal_device_id Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).
  61. * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set)
  62. * @param angular_velocity_x [rad/s] X component of angular velocity, positive is rolling to the right, NaN to be ignored.
  63. * @param angular_velocity_y [rad/s] Y component of angular velocity, positive is pitching up, NaN to be ignored.
  64. * @param angular_velocity_z [rad/s] Z component of angular velocity, positive is yawing to the right, NaN to be ignored.
  65. * @return length of the message in bytes (excluding serial stream start sign)
  66. */
  67. static inline uint16_t mavlink_msg_gimbal_manager_set_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  68. uint8_t target_system, uint8_t target_component, uint32_t flags, uint8_t gimbal_device_id, const float *q, float angular_velocity_x, float angular_velocity_y, float angular_velocity_z)
  69. {
  70. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  71. char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN];
  72. _mav_put_uint32_t(buf, 0, flags);
  73. _mav_put_float(buf, 20, angular_velocity_x);
  74. _mav_put_float(buf, 24, angular_velocity_y);
  75. _mav_put_float(buf, 28, angular_velocity_z);
  76. _mav_put_uint8_t(buf, 32, target_system);
  77. _mav_put_uint8_t(buf, 33, target_component);
  78. _mav_put_uint8_t(buf, 34, gimbal_device_id);
  79. _mav_put_float_array(buf, 4, q, 4);
  80. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN);
  81. #else
  82. mavlink_gimbal_manager_set_attitude_t packet;
  83. packet.flags = flags;
  84. packet.angular_velocity_x = angular_velocity_x;
  85. packet.angular_velocity_y = angular_velocity_y;
  86. packet.angular_velocity_z = angular_velocity_z;
  87. packet.target_system = target_system;
  88. packet.target_component = target_component;
  89. packet.gimbal_device_id = gimbal_device_id;
  90. mav_array_memcpy(packet.q, q, sizeof(float)*4);
  91. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN);
  92. #endif
  93. msg->msgid = MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE;
  94. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_CRC);
  95. }
  96. /**
  97. * @brief Pack a gimbal_manager_set_attitude message on a channel
  98. * @param system_id ID of this system
  99. * @param component_id ID of this component (e.g. 200 for IMU)
  100. * @param chan The MAVLink channel this message will be sent over
  101. * @param msg The MAVLink message to compress the data into
  102. * @param target_system System ID
  103. * @param target_component Component ID
  104. * @param flags High level gimbal manager flags to use.
  105. * @param gimbal_device_id Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).
  106. * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set)
  107. * @param angular_velocity_x [rad/s] X component of angular velocity, positive is rolling to the right, NaN to be ignored.
  108. * @param angular_velocity_y [rad/s] Y component of angular velocity, positive is pitching up, NaN to be ignored.
  109. * @param angular_velocity_z [rad/s] Z component of angular velocity, positive is yawing to the right, NaN to be ignored.
  110. * @return length of the message in bytes (excluding serial stream start sign)
  111. */
  112. static inline uint16_t mavlink_msg_gimbal_manager_set_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  113. mavlink_message_t* msg,
  114. uint8_t target_system,uint8_t target_component,uint32_t flags,uint8_t gimbal_device_id,const float *q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z)
  115. {
  116. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  117. char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN];
  118. _mav_put_uint32_t(buf, 0, flags);
  119. _mav_put_float(buf, 20, angular_velocity_x);
  120. _mav_put_float(buf, 24, angular_velocity_y);
  121. _mav_put_float(buf, 28, angular_velocity_z);
  122. _mav_put_uint8_t(buf, 32, target_system);
  123. _mav_put_uint8_t(buf, 33, target_component);
  124. _mav_put_uint8_t(buf, 34, gimbal_device_id);
  125. _mav_put_float_array(buf, 4, q, 4);
  126. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN);
  127. #else
  128. mavlink_gimbal_manager_set_attitude_t packet;
  129. packet.flags = flags;
  130. packet.angular_velocity_x = angular_velocity_x;
  131. packet.angular_velocity_y = angular_velocity_y;
  132. packet.angular_velocity_z = angular_velocity_z;
  133. packet.target_system = target_system;
  134. packet.target_component = target_component;
  135. packet.gimbal_device_id = gimbal_device_id;
  136. mav_array_memcpy(packet.q, q, sizeof(float)*4);
  137. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN);
  138. #endif
  139. msg->msgid = MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE;
  140. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_CRC);
  141. }
  142. /**
  143. * @brief Encode a gimbal_manager_set_attitude struct
  144. *
  145. * @param system_id ID of this system
  146. * @param component_id ID of this component (e.g. 200 for IMU)
  147. * @param msg The MAVLink message to compress the data into
  148. * @param gimbal_manager_set_attitude C-struct to read the message contents from
  149. */
  150. static inline uint16_t mavlink_msg_gimbal_manager_set_attitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gimbal_manager_set_attitude_t* gimbal_manager_set_attitude)
  151. {
  152. return mavlink_msg_gimbal_manager_set_attitude_pack(system_id, component_id, msg, gimbal_manager_set_attitude->target_system, gimbal_manager_set_attitude->target_component, gimbal_manager_set_attitude->flags, gimbal_manager_set_attitude->gimbal_device_id, gimbal_manager_set_attitude->q, gimbal_manager_set_attitude->angular_velocity_x, gimbal_manager_set_attitude->angular_velocity_y, gimbal_manager_set_attitude->angular_velocity_z);
  153. }
  154. /**
  155. * @brief Encode a gimbal_manager_set_attitude struct on a channel
  156. *
  157. * @param system_id ID of this system
  158. * @param component_id ID of this component (e.g. 200 for IMU)
  159. * @param chan The MAVLink channel this message will be sent over
  160. * @param msg The MAVLink message to compress the data into
  161. * @param gimbal_manager_set_attitude C-struct to read the message contents from
  162. */
  163. static inline uint16_t mavlink_msg_gimbal_manager_set_attitude_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gimbal_manager_set_attitude_t* gimbal_manager_set_attitude)
  164. {
  165. return mavlink_msg_gimbal_manager_set_attitude_pack_chan(system_id, component_id, chan, msg, gimbal_manager_set_attitude->target_system, gimbal_manager_set_attitude->target_component, gimbal_manager_set_attitude->flags, gimbal_manager_set_attitude->gimbal_device_id, gimbal_manager_set_attitude->q, gimbal_manager_set_attitude->angular_velocity_x, gimbal_manager_set_attitude->angular_velocity_y, gimbal_manager_set_attitude->angular_velocity_z);
  166. }
  167. /**
  168. * @brief Send a gimbal_manager_set_attitude message
  169. * @param chan MAVLink channel to send the message
  170. *
  171. * @param target_system System ID
  172. * @param target_component Component ID
  173. * @param flags High level gimbal manager flags to use.
  174. * @param gimbal_device_id Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).
  175. * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set)
  176. * @param angular_velocity_x [rad/s] X component of angular velocity, positive is rolling to the right, NaN to be ignored.
  177. * @param angular_velocity_y [rad/s] Y component of angular velocity, positive is pitching up, NaN to be ignored.
  178. * @param angular_velocity_z [rad/s] Z component of angular velocity, positive is yawing to the right, NaN to be ignored.
  179. */
  180. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  181. static inline void mavlink_msg_gimbal_manager_set_attitude_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t flags, uint8_t gimbal_device_id, const float *q, float angular_velocity_x, float angular_velocity_y, float angular_velocity_z)
  182. {
  183. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  184. char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN];
  185. _mav_put_uint32_t(buf, 0, flags);
  186. _mav_put_float(buf, 20, angular_velocity_x);
  187. _mav_put_float(buf, 24, angular_velocity_y);
  188. _mav_put_float(buf, 28, angular_velocity_z);
  189. _mav_put_uint8_t(buf, 32, target_system);
  190. _mav_put_uint8_t(buf, 33, target_component);
  191. _mav_put_uint8_t(buf, 34, gimbal_device_id);
  192. _mav_put_float_array(buf, 4, q, 4);
  193. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE, buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_CRC);
  194. #else
  195. mavlink_gimbal_manager_set_attitude_t packet;
  196. packet.flags = flags;
  197. packet.angular_velocity_x = angular_velocity_x;
  198. packet.angular_velocity_y = angular_velocity_y;
  199. packet.angular_velocity_z = angular_velocity_z;
  200. packet.target_system = target_system;
  201. packet.target_component = target_component;
  202. packet.gimbal_device_id = gimbal_device_id;
  203. mav_array_memcpy(packet.q, q, sizeof(float)*4);
  204. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE, (const char *)&packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_CRC);
  205. #endif
  206. }
  207. /**
  208. * @brief Send a gimbal_manager_set_attitude message
  209. * @param chan MAVLink channel to send the message
  210. * @param struct The MAVLink struct to serialize
  211. */
  212. static inline void mavlink_msg_gimbal_manager_set_attitude_send_struct(mavlink_channel_t chan, const mavlink_gimbal_manager_set_attitude_t* gimbal_manager_set_attitude)
  213. {
  214. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  215. mavlink_msg_gimbal_manager_set_attitude_send(chan, gimbal_manager_set_attitude->target_system, gimbal_manager_set_attitude->target_component, gimbal_manager_set_attitude->flags, gimbal_manager_set_attitude->gimbal_device_id, gimbal_manager_set_attitude->q, gimbal_manager_set_attitude->angular_velocity_x, gimbal_manager_set_attitude->angular_velocity_y, gimbal_manager_set_attitude->angular_velocity_z);
  216. #else
  217. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE, (const char *)gimbal_manager_set_attitude, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_CRC);
  218. #endif
  219. }
  220. #if MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  221. /*
  222. This variant of _send() can be used to save stack space by re-using
  223. memory from the receive buffer. The caller provides a
  224. mavlink_message_t which is the size of a full mavlink message. This
  225. is usually the receive buffer for the channel, and allows a reply to an
  226. incoming message with minimum stack space usage.
  227. */
  228. static inline void mavlink_msg_gimbal_manager_set_attitude_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t flags, uint8_t gimbal_device_id, const float *q, float angular_velocity_x, float angular_velocity_y, float angular_velocity_z)
  229. {
  230. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  231. char *buf = (char *)msgbuf;
  232. _mav_put_uint32_t(buf, 0, flags);
  233. _mav_put_float(buf, 20, angular_velocity_x);
  234. _mav_put_float(buf, 24, angular_velocity_y);
  235. _mav_put_float(buf, 28, angular_velocity_z);
  236. _mav_put_uint8_t(buf, 32, target_system);
  237. _mav_put_uint8_t(buf, 33, target_component);
  238. _mav_put_uint8_t(buf, 34, gimbal_device_id);
  239. _mav_put_float_array(buf, 4, q, 4);
  240. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE, buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_CRC);
  241. #else
  242. mavlink_gimbal_manager_set_attitude_t *packet = (mavlink_gimbal_manager_set_attitude_t *)msgbuf;
  243. packet->flags = flags;
  244. packet->angular_velocity_x = angular_velocity_x;
  245. packet->angular_velocity_y = angular_velocity_y;
  246. packet->angular_velocity_z = angular_velocity_z;
  247. packet->target_system = target_system;
  248. packet->target_component = target_component;
  249. packet->gimbal_device_id = gimbal_device_id;
  250. mav_array_memcpy(packet->q, q, sizeof(float)*4);
  251. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE, (const char *)packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_CRC);
  252. #endif
  253. }
  254. #endif
  255. #endif
  256. // MESSAGE GIMBAL_MANAGER_SET_ATTITUDE UNPACKING
  257. /**
  258. * @brief Get field target_system from gimbal_manager_set_attitude message
  259. *
  260. * @return System ID
  261. */
  262. static inline uint8_t mavlink_msg_gimbal_manager_set_attitude_get_target_system(const mavlink_message_t* msg)
  263. {
  264. return _MAV_RETURN_uint8_t(msg, 32);
  265. }
  266. /**
  267. * @brief Get field target_component from gimbal_manager_set_attitude message
  268. *
  269. * @return Component ID
  270. */
  271. static inline uint8_t mavlink_msg_gimbal_manager_set_attitude_get_target_component(const mavlink_message_t* msg)
  272. {
  273. return _MAV_RETURN_uint8_t(msg, 33);
  274. }
  275. /**
  276. * @brief Get field flags from gimbal_manager_set_attitude message
  277. *
  278. * @return High level gimbal manager flags to use.
  279. */
  280. static inline uint32_t mavlink_msg_gimbal_manager_set_attitude_get_flags(const mavlink_message_t* msg)
  281. {
  282. return _MAV_RETURN_uint32_t(msg, 0);
  283. }
  284. /**
  285. * @brief Get field gimbal_device_id from gimbal_manager_set_attitude message
  286. *
  287. * @return Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).
  288. */
  289. static inline uint8_t mavlink_msg_gimbal_manager_set_attitude_get_gimbal_device_id(const mavlink_message_t* msg)
  290. {
  291. return _MAV_RETURN_uint8_t(msg, 34);
  292. }
  293. /**
  294. * @brief Get field q from gimbal_manager_set_attitude message
  295. *
  296. * @return Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set)
  297. */
  298. static inline uint16_t mavlink_msg_gimbal_manager_set_attitude_get_q(const mavlink_message_t* msg, float *q)
  299. {
  300. return _MAV_RETURN_float_array(msg, q, 4, 4);
  301. }
  302. /**
  303. * @brief Get field angular_velocity_x from gimbal_manager_set_attitude message
  304. *
  305. * @return [rad/s] X component of angular velocity, positive is rolling to the right, NaN to be ignored.
  306. */
  307. static inline float mavlink_msg_gimbal_manager_set_attitude_get_angular_velocity_x(const mavlink_message_t* msg)
  308. {
  309. return _MAV_RETURN_float(msg, 20);
  310. }
  311. /**
  312. * @brief Get field angular_velocity_y from gimbal_manager_set_attitude message
  313. *
  314. * @return [rad/s] Y component of angular velocity, positive is pitching up, NaN to be ignored.
  315. */
  316. static inline float mavlink_msg_gimbal_manager_set_attitude_get_angular_velocity_y(const mavlink_message_t* msg)
  317. {
  318. return _MAV_RETURN_float(msg, 24);
  319. }
  320. /**
  321. * @brief Get field angular_velocity_z from gimbal_manager_set_attitude message
  322. *
  323. * @return [rad/s] Z component of angular velocity, positive is yawing to the right, NaN to be ignored.
  324. */
  325. static inline float mavlink_msg_gimbal_manager_set_attitude_get_angular_velocity_z(const mavlink_message_t* msg)
  326. {
  327. return _MAV_RETURN_float(msg, 28);
  328. }
  329. /**
  330. * @brief Decode a gimbal_manager_set_attitude message into a struct
  331. *
  332. * @param msg The message to decode
  333. * @param gimbal_manager_set_attitude C-struct to decode the message contents into
  334. */
  335. static inline void mavlink_msg_gimbal_manager_set_attitude_decode(const mavlink_message_t* msg, mavlink_gimbal_manager_set_attitude_t* gimbal_manager_set_attitude)
  336. {
  337. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  338. gimbal_manager_set_attitude->flags = mavlink_msg_gimbal_manager_set_attitude_get_flags(msg);
  339. mavlink_msg_gimbal_manager_set_attitude_get_q(msg, gimbal_manager_set_attitude->q);
  340. gimbal_manager_set_attitude->angular_velocity_x = mavlink_msg_gimbal_manager_set_attitude_get_angular_velocity_x(msg);
  341. gimbal_manager_set_attitude->angular_velocity_y = mavlink_msg_gimbal_manager_set_attitude_get_angular_velocity_y(msg);
  342. gimbal_manager_set_attitude->angular_velocity_z = mavlink_msg_gimbal_manager_set_attitude_get_angular_velocity_z(msg);
  343. gimbal_manager_set_attitude->target_system = mavlink_msg_gimbal_manager_set_attitude_get_target_system(msg);
  344. gimbal_manager_set_attitude->target_component = mavlink_msg_gimbal_manager_set_attitude_get_target_component(msg);
  345. gimbal_manager_set_attitude->gimbal_device_id = mavlink_msg_gimbal_manager_set_attitude_get_gimbal_device_id(msg);
  346. #else
  347. uint8_t len = msg->len < MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN? msg->len : MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN;
  348. memset(gimbal_manager_set_attitude, 0, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN);
  349. memcpy(gimbal_manager_set_attitude, _MAV_PAYLOAD(msg), len);
  350. #endif
  351. }