mavlink_msg_gimbal_manager_set_pitchyaw.h 20 KB

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