mavlink_msg_gimbal_device_information.h 34 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582
  1. #pragma once
  2. // MESSAGE GIMBAL_DEVICE_INFORMATION PACKING
  3. #define MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION 283
  4. typedef struct __mavlink_gimbal_device_information_t {
  5. uint64_t uid; /*< UID of gimbal hardware (0 if unknown).*/
  6. uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
  7. uint32_t firmware_version; /*< Version of the gimbal firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).*/
  8. uint32_t hardware_version; /*< Version of the gimbal hardware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).*/
  9. float roll_min; /*< [rad] Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown.*/
  10. float roll_max; /*< [rad] Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown.*/
  11. float pitch_min; /*< [rad] Minimum hardware pitch angle (positive: up, negative: down). NAN if unknown.*/
  12. float pitch_max; /*< [rad] Maximum hardware pitch angle (positive: up, negative: down). NAN if unknown.*/
  13. float yaw_min; /*< [rad] Minimum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown.*/
  14. float yaw_max; /*< [rad] Maximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown.*/
  15. uint16_t cap_flags; /*< Bitmap of gimbal capability flags.*/
  16. uint16_t custom_cap_flags; /*< Bitmap for use for gimbal-specific capability flags.*/
  17. char vendor_name[32]; /*< Name of the gimbal vendor.*/
  18. char model_name[32]; /*< Name of the gimbal model.*/
  19. char custom_name[32]; /*< Custom name of the gimbal given to it by the user.*/
  20. uint8_t gimbal_device_id; /*< This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set to a number between 1-6. If the component ID is separate, this field is not required and must be set to 0.*/
  21. } mavlink_gimbal_device_information_t;
  22. #define MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN 145
  23. #define MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_MIN_LEN 144
  24. #define MAVLINK_MSG_ID_283_LEN 145
  25. #define MAVLINK_MSG_ID_283_MIN_LEN 144
  26. #define MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_CRC 74
  27. #define MAVLINK_MSG_ID_283_CRC 74
  28. #define MAVLINK_MSG_GIMBAL_DEVICE_INFORMATION_FIELD_VENDOR_NAME_LEN 32
  29. #define MAVLINK_MSG_GIMBAL_DEVICE_INFORMATION_FIELD_MODEL_NAME_LEN 32
  30. #define MAVLINK_MSG_GIMBAL_DEVICE_INFORMATION_FIELD_CUSTOM_NAME_LEN 32
  31. #if MAVLINK_COMMAND_24BIT
  32. #define MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_INFORMATION { \
  33. 283, \
  34. "GIMBAL_DEVICE_INFORMATION", \
  35. 16, \
  36. { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_gimbal_device_information_t, time_boot_ms) }, \
  37. { "vendor_name", NULL, MAVLINK_TYPE_CHAR, 32, 48, offsetof(mavlink_gimbal_device_information_t, vendor_name) }, \
  38. { "model_name", NULL, MAVLINK_TYPE_CHAR, 32, 80, offsetof(mavlink_gimbal_device_information_t, model_name) }, \
  39. { "custom_name", NULL, MAVLINK_TYPE_CHAR, 32, 112, offsetof(mavlink_gimbal_device_information_t, custom_name) }, \
  40. { "firmware_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_gimbal_device_information_t, firmware_version) }, \
  41. { "hardware_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_gimbal_device_information_t, hardware_version) }, \
  42. { "uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gimbal_device_information_t, uid) }, \
  43. { "cap_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 44, offsetof(mavlink_gimbal_device_information_t, cap_flags) }, \
  44. { "custom_cap_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 46, offsetof(mavlink_gimbal_device_information_t, custom_cap_flags) }, \
  45. { "roll_min", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_device_information_t, roll_min) }, \
  46. { "roll_max", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_device_information_t, roll_max) }, \
  47. { "pitch_min", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gimbal_device_information_t, pitch_min) }, \
  48. { "pitch_max", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gimbal_device_information_t, pitch_max) }, \
  49. { "yaw_min", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gimbal_device_information_t, yaw_min) }, \
  50. { "yaw_max", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gimbal_device_information_t, yaw_max) }, \
  51. { "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 144, offsetof(mavlink_gimbal_device_information_t, gimbal_device_id) }, \
  52. } \
  53. }
  54. #else
  55. #define MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_INFORMATION { \
  56. "GIMBAL_DEVICE_INFORMATION", \
  57. 16, \
  58. { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_gimbal_device_information_t, time_boot_ms) }, \
  59. { "vendor_name", NULL, MAVLINK_TYPE_CHAR, 32, 48, offsetof(mavlink_gimbal_device_information_t, vendor_name) }, \
  60. { "model_name", NULL, MAVLINK_TYPE_CHAR, 32, 80, offsetof(mavlink_gimbal_device_information_t, model_name) }, \
  61. { "custom_name", NULL, MAVLINK_TYPE_CHAR, 32, 112, offsetof(mavlink_gimbal_device_information_t, custom_name) }, \
  62. { "firmware_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_gimbal_device_information_t, firmware_version) }, \
  63. { "hardware_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_gimbal_device_information_t, hardware_version) }, \
  64. { "uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gimbal_device_information_t, uid) }, \
  65. { "cap_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 44, offsetof(mavlink_gimbal_device_information_t, cap_flags) }, \
  66. { "custom_cap_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 46, offsetof(mavlink_gimbal_device_information_t, custom_cap_flags) }, \
  67. { "roll_min", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_device_information_t, roll_min) }, \
  68. { "roll_max", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_device_information_t, roll_max) }, \
  69. { "pitch_min", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gimbal_device_information_t, pitch_min) }, \
  70. { "pitch_max", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gimbal_device_information_t, pitch_max) }, \
  71. { "yaw_min", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gimbal_device_information_t, yaw_min) }, \
  72. { "yaw_max", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gimbal_device_information_t, yaw_max) }, \
  73. { "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 144, offsetof(mavlink_gimbal_device_information_t, gimbal_device_id) }, \
  74. } \
  75. }
  76. #endif
  77. /**
  78. * @brief Pack a gimbal_device_information message
  79. * @param system_id ID of this system
  80. * @param component_id ID of this component (e.g. 200 for IMU)
  81. * @param msg The MAVLink message to compress the data into
  82. *
  83. * @param time_boot_ms [ms] Timestamp (time since system boot).
  84. * @param vendor_name Name of the gimbal vendor.
  85. * @param model_name Name of the gimbal model.
  86. * @param custom_name Custom name of the gimbal given to it by the user.
  87. * @param firmware_version Version of the gimbal firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).
  88. * @param hardware_version Version of the gimbal hardware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).
  89. * @param uid UID of gimbal hardware (0 if unknown).
  90. * @param cap_flags Bitmap of gimbal capability flags.
  91. * @param custom_cap_flags Bitmap for use for gimbal-specific capability flags.
  92. * @param roll_min [rad] Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown.
  93. * @param roll_max [rad] Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown.
  94. * @param pitch_min [rad] Minimum hardware pitch angle (positive: up, negative: down). NAN if unknown.
  95. * @param pitch_max [rad] Maximum hardware pitch angle (positive: up, negative: down). NAN if unknown.
  96. * @param yaw_min [rad] Minimum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown.
  97. * @param yaw_max [rad] Maximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown.
  98. * @param gimbal_device_id This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set to a number between 1-6. If the component ID is separate, this field is not required and must be set to 0.
  99. * @return length of the message in bytes (excluding serial stream start sign)
  100. */
  101. static inline uint16_t mavlink_msg_gimbal_device_information_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  102. uint32_t time_boot_ms, const char *vendor_name, const char *model_name, const char *custom_name, uint32_t firmware_version, uint32_t hardware_version, uint64_t uid, uint16_t cap_flags, uint16_t custom_cap_flags, float roll_min, float roll_max, float pitch_min, float pitch_max, float yaw_min, float yaw_max, uint8_t gimbal_device_id)
  103. {
  104. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  105. char buf[MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN];
  106. _mav_put_uint64_t(buf, 0, uid);
  107. _mav_put_uint32_t(buf, 8, time_boot_ms);
  108. _mav_put_uint32_t(buf, 12, firmware_version);
  109. _mav_put_uint32_t(buf, 16, hardware_version);
  110. _mav_put_float(buf, 20, roll_min);
  111. _mav_put_float(buf, 24, roll_max);
  112. _mav_put_float(buf, 28, pitch_min);
  113. _mav_put_float(buf, 32, pitch_max);
  114. _mav_put_float(buf, 36, yaw_min);
  115. _mav_put_float(buf, 40, yaw_max);
  116. _mav_put_uint16_t(buf, 44, cap_flags);
  117. _mav_put_uint16_t(buf, 46, custom_cap_flags);
  118. _mav_put_uint8_t(buf, 144, gimbal_device_id);
  119. _mav_put_char_array(buf, 48, vendor_name, 32);
  120. _mav_put_char_array(buf, 80, model_name, 32);
  121. _mav_put_char_array(buf, 112, custom_name, 32);
  122. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN);
  123. #else
  124. mavlink_gimbal_device_information_t packet;
  125. packet.uid = uid;
  126. packet.time_boot_ms = time_boot_ms;
  127. packet.firmware_version = firmware_version;
  128. packet.hardware_version = hardware_version;
  129. packet.roll_min = roll_min;
  130. packet.roll_max = roll_max;
  131. packet.pitch_min = pitch_min;
  132. packet.pitch_max = pitch_max;
  133. packet.yaw_min = yaw_min;
  134. packet.yaw_max = yaw_max;
  135. packet.cap_flags = cap_flags;
  136. packet.custom_cap_flags = custom_cap_flags;
  137. packet.gimbal_device_id = gimbal_device_id;
  138. mav_array_memcpy(packet.vendor_name, vendor_name, sizeof(char)*32);
  139. mav_array_memcpy(packet.model_name, model_name, sizeof(char)*32);
  140. mav_array_memcpy(packet.custom_name, custom_name, sizeof(char)*32);
  141. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN);
  142. #endif
  143. msg->msgid = MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION;
  144. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_CRC);
  145. }
  146. /**
  147. * @brief Pack a gimbal_device_information message on a channel
  148. * @param system_id ID of this system
  149. * @param component_id ID of this component (e.g. 200 for IMU)
  150. * @param chan The MAVLink channel this message will be sent over
  151. * @param msg The MAVLink message to compress the data into
  152. * @param time_boot_ms [ms] Timestamp (time since system boot).
  153. * @param vendor_name Name of the gimbal vendor.
  154. * @param model_name Name of the gimbal model.
  155. * @param custom_name Custom name of the gimbal given to it by the user.
  156. * @param firmware_version Version of the gimbal firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).
  157. * @param hardware_version Version of the gimbal hardware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).
  158. * @param uid UID of gimbal hardware (0 if unknown).
  159. * @param cap_flags Bitmap of gimbal capability flags.
  160. * @param custom_cap_flags Bitmap for use for gimbal-specific capability flags.
  161. * @param roll_min [rad] Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown.
  162. * @param roll_max [rad] Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown.
  163. * @param pitch_min [rad] Minimum hardware pitch angle (positive: up, negative: down). NAN if unknown.
  164. * @param pitch_max [rad] Maximum hardware pitch angle (positive: up, negative: down). NAN if unknown.
  165. * @param yaw_min [rad] Minimum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown.
  166. * @param yaw_max [rad] Maximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown.
  167. * @param gimbal_device_id This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set to a number between 1-6. If the component ID is separate, this field is not required and must be set to 0.
  168. * @return length of the message in bytes (excluding serial stream start sign)
  169. */
  170. static inline uint16_t mavlink_msg_gimbal_device_information_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  171. mavlink_message_t* msg,
  172. uint32_t time_boot_ms,const char *vendor_name,const char *model_name,const char *custom_name,uint32_t firmware_version,uint32_t hardware_version,uint64_t uid,uint16_t cap_flags,uint16_t custom_cap_flags,float roll_min,float roll_max,float pitch_min,float pitch_max,float yaw_min,float yaw_max,uint8_t gimbal_device_id)
  173. {
  174. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  175. char buf[MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN];
  176. _mav_put_uint64_t(buf, 0, uid);
  177. _mav_put_uint32_t(buf, 8, time_boot_ms);
  178. _mav_put_uint32_t(buf, 12, firmware_version);
  179. _mav_put_uint32_t(buf, 16, hardware_version);
  180. _mav_put_float(buf, 20, roll_min);
  181. _mav_put_float(buf, 24, roll_max);
  182. _mav_put_float(buf, 28, pitch_min);
  183. _mav_put_float(buf, 32, pitch_max);
  184. _mav_put_float(buf, 36, yaw_min);
  185. _mav_put_float(buf, 40, yaw_max);
  186. _mav_put_uint16_t(buf, 44, cap_flags);
  187. _mav_put_uint16_t(buf, 46, custom_cap_flags);
  188. _mav_put_uint8_t(buf, 144, gimbal_device_id);
  189. _mav_put_char_array(buf, 48, vendor_name, 32);
  190. _mav_put_char_array(buf, 80, model_name, 32);
  191. _mav_put_char_array(buf, 112, custom_name, 32);
  192. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN);
  193. #else
  194. mavlink_gimbal_device_information_t packet;
  195. packet.uid = uid;
  196. packet.time_boot_ms = time_boot_ms;
  197. packet.firmware_version = firmware_version;
  198. packet.hardware_version = hardware_version;
  199. packet.roll_min = roll_min;
  200. packet.roll_max = roll_max;
  201. packet.pitch_min = pitch_min;
  202. packet.pitch_max = pitch_max;
  203. packet.yaw_min = yaw_min;
  204. packet.yaw_max = yaw_max;
  205. packet.cap_flags = cap_flags;
  206. packet.custom_cap_flags = custom_cap_flags;
  207. packet.gimbal_device_id = gimbal_device_id;
  208. mav_array_memcpy(packet.vendor_name, vendor_name, sizeof(char)*32);
  209. mav_array_memcpy(packet.model_name, model_name, sizeof(char)*32);
  210. mav_array_memcpy(packet.custom_name, custom_name, sizeof(char)*32);
  211. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN);
  212. #endif
  213. msg->msgid = MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION;
  214. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_CRC);
  215. }
  216. /**
  217. * @brief Encode a gimbal_device_information struct
  218. *
  219. * @param system_id ID of this system
  220. * @param component_id ID of this component (e.g. 200 for IMU)
  221. * @param msg The MAVLink message to compress the data into
  222. * @param gimbal_device_information C-struct to read the message contents from
  223. */
  224. static inline uint16_t mavlink_msg_gimbal_device_information_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gimbal_device_information_t* gimbal_device_information)
  225. {
  226. return mavlink_msg_gimbal_device_information_pack(system_id, component_id, msg, gimbal_device_information->time_boot_ms, gimbal_device_information->vendor_name, gimbal_device_information->model_name, gimbal_device_information->custom_name, gimbal_device_information->firmware_version, gimbal_device_information->hardware_version, gimbal_device_information->uid, gimbal_device_information->cap_flags, gimbal_device_information->custom_cap_flags, gimbal_device_information->roll_min, gimbal_device_information->roll_max, gimbal_device_information->pitch_min, gimbal_device_information->pitch_max, gimbal_device_information->yaw_min, gimbal_device_information->yaw_max, gimbal_device_information->gimbal_device_id);
  227. }
  228. /**
  229. * @brief Encode a gimbal_device_information struct on a channel
  230. *
  231. * @param system_id ID of this system
  232. * @param component_id ID of this component (e.g. 200 for IMU)
  233. * @param chan The MAVLink channel this message will be sent over
  234. * @param msg The MAVLink message to compress the data into
  235. * @param gimbal_device_information C-struct to read the message contents from
  236. */
  237. static inline uint16_t mavlink_msg_gimbal_device_information_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gimbal_device_information_t* gimbal_device_information)
  238. {
  239. return mavlink_msg_gimbal_device_information_pack_chan(system_id, component_id, chan, msg, gimbal_device_information->time_boot_ms, gimbal_device_information->vendor_name, gimbal_device_information->model_name, gimbal_device_information->custom_name, gimbal_device_information->firmware_version, gimbal_device_information->hardware_version, gimbal_device_information->uid, gimbal_device_information->cap_flags, gimbal_device_information->custom_cap_flags, gimbal_device_information->roll_min, gimbal_device_information->roll_max, gimbal_device_information->pitch_min, gimbal_device_information->pitch_max, gimbal_device_information->yaw_min, gimbal_device_information->yaw_max, gimbal_device_information->gimbal_device_id);
  240. }
  241. /**
  242. * @brief Send a gimbal_device_information message
  243. * @param chan MAVLink channel to send the message
  244. *
  245. * @param time_boot_ms [ms] Timestamp (time since system boot).
  246. * @param vendor_name Name of the gimbal vendor.
  247. * @param model_name Name of the gimbal model.
  248. * @param custom_name Custom name of the gimbal given to it by the user.
  249. * @param firmware_version Version of the gimbal firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).
  250. * @param hardware_version Version of the gimbal hardware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).
  251. * @param uid UID of gimbal hardware (0 if unknown).
  252. * @param cap_flags Bitmap of gimbal capability flags.
  253. * @param custom_cap_flags Bitmap for use for gimbal-specific capability flags.
  254. * @param roll_min [rad] Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown.
  255. * @param roll_max [rad] Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown.
  256. * @param pitch_min [rad] Minimum hardware pitch angle (positive: up, negative: down). NAN if unknown.
  257. * @param pitch_max [rad] Maximum hardware pitch angle (positive: up, negative: down). NAN if unknown.
  258. * @param yaw_min [rad] Minimum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown.
  259. * @param yaw_max [rad] Maximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown.
  260. * @param gimbal_device_id This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set to a number between 1-6. If the component ID is separate, this field is not required and must be set to 0.
  261. */
  262. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  263. static inline void mavlink_msg_gimbal_device_information_send(mavlink_channel_t chan, uint32_t time_boot_ms, const char *vendor_name, const char *model_name, const char *custom_name, uint32_t firmware_version, uint32_t hardware_version, uint64_t uid, uint16_t cap_flags, uint16_t custom_cap_flags, float roll_min, float roll_max, float pitch_min, float pitch_max, float yaw_min, float yaw_max, uint8_t gimbal_device_id)
  264. {
  265. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  266. char buf[MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN];
  267. _mav_put_uint64_t(buf, 0, uid);
  268. _mav_put_uint32_t(buf, 8, time_boot_ms);
  269. _mav_put_uint32_t(buf, 12, firmware_version);
  270. _mav_put_uint32_t(buf, 16, hardware_version);
  271. _mav_put_float(buf, 20, roll_min);
  272. _mav_put_float(buf, 24, roll_max);
  273. _mav_put_float(buf, 28, pitch_min);
  274. _mav_put_float(buf, 32, pitch_max);
  275. _mav_put_float(buf, 36, yaw_min);
  276. _mav_put_float(buf, 40, yaw_max);
  277. _mav_put_uint16_t(buf, 44, cap_flags);
  278. _mav_put_uint16_t(buf, 46, custom_cap_flags);
  279. _mav_put_uint8_t(buf, 144, gimbal_device_id);
  280. _mav_put_char_array(buf, 48, vendor_name, 32);
  281. _mav_put_char_array(buf, 80, model_name, 32);
  282. _mav_put_char_array(buf, 112, custom_name, 32);
  283. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION, buf, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_CRC);
  284. #else
  285. mavlink_gimbal_device_information_t packet;
  286. packet.uid = uid;
  287. packet.time_boot_ms = time_boot_ms;
  288. packet.firmware_version = firmware_version;
  289. packet.hardware_version = hardware_version;
  290. packet.roll_min = roll_min;
  291. packet.roll_max = roll_max;
  292. packet.pitch_min = pitch_min;
  293. packet.pitch_max = pitch_max;
  294. packet.yaw_min = yaw_min;
  295. packet.yaw_max = yaw_max;
  296. packet.cap_flags = cap_flags;
  297. packet.custom_cap_flags = custom_cap_flags;
  298. packet.gimbal_device_id = gimbal_device_id;
  299. mav_array_memcpy(packet.vendor_name, vendor_name, sizeof(char)*32);
  300. mav_array_memcpy(packet.model_name, model_name, sizeof(char)*32);
  301. mav_array_memcpy(packet.custom_name, custom_name, sizeof(char)*32);
  302. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION, (const char *)&packet, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_CRC);
  303. #endif
  304. }
  305. /**
  306. * @brief Send a gimbal_device_information message
  307. * @param chan MAVLink channel to send the message
  308. * @param struct The MAVLink struct to serialize
  309. */
  310. static inline void mavlink_msg_gimbal_device_information_send_struct(mavlink_channel_t chan, const mavlink_gimbal_device_information_t* gimbal_device_information)
  311. {
  312. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  313. mavlink_msg_gimbal_device_information_send(chan, gimbal_device_information->time_boot_ms, gimbal_device_information->vendor_name, gimbal_device_information->model_name, gimbal_device_information->custom_name, gimbal_device_information->firmware_version, gimbal_device_information->hardware_version, gimbal_device_information->uid, gimbal_device_information->cap_flags, gimbal_device_information->custom_cap_flags, gimbal_device_information->roll_min, gimbal_device_information->roll_max, gimbal_device_information->pitch_min, gimbal_device_information->pitch_max, gimbal_device_information->yaw_min, gimbal_device_information->yaw_max, gimbal_device_information->gimbal_device_id);
  314. #else
  315. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION, (const char *)gimbal_device_information, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_CRC);
  316. #endif
  317. }
  318. #if MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  319. /*
  320. This variant of _send() can be used to save stack space by re-using
  321. memory from the receive buffer. The caller provides a
  322. mavlink_message_t which is the size of a full mavlink message. This
  323. is usually the receive buffer for the channel, and allows a reply to an
  324. incoming message with minimum stack space usage.
  325. */
  326. static inline void mavlink_msg_gimbal_device_information_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, const char *vendor_name, const char *model_name, const char *custom_name, uint32_t firmware_version, uint32_t hardware_version, uint64_t uid, uint16_t cap_flags, uint16_t custom_cap_flags, float roll_min, float roll_max, float pitch_min, float pitch_max, float yaw_min, float yaw_max, uint8_t gimbal_device_id)
  327. {
  328. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  329. char *buf = (char *)msgbuf;
  330. _mav_put_uint64_t(buf, 0, uid);
  331. _mav_put_uint32_t(buf, 8, time_boot_ms);
  332. _mav_put_uint32_t(buf, 12, firmware_version);
  333. _mav_put_uint32_t(buf, 16, hardware_version);
  334. _mav_put_float(buf, 20, roll_min);
  335. _mav_put_float(buf, 24, roll_max);
  336. _mav_put_float(buf, 28, pitch_min);
  337. _mav_put_float(buf, 32, pitch_max);
  338. _mav_put_float(buf, 36, yaw_min);
  339. _mav_put_float(buf, 40, yaw_max);
  340. _mav_put_uint16_t(buf, 44, cap_flags);
  341. _mav_put_uint16_t(buf, 46, custom_cap_flags);
  342. _mav_put_uint8_t(buf, 144, gimbal_device_id);
  343. _mav_put_char_array(buf, 48, vendor_name, 32);
  344. _mav_put_char_array(buf, 80, model_name, 32);
  345. _mav_put_char_array(buf, 112, custom_name, 32);
  346. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION, buf, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_CRC);
  347. #else
  348. mavlink_gimbal_device_information_t *packet = (mavlink_gimbal_device_information_t *)msgbuf;
  349. packet->uid = uid;
  350. packet->time_boot_ms = time_boot_ms;
  351. packet->firmware_version = firmware_version;
  352. packet->hardware_version = hardware_version;
  353. packet->roll_min = roll_min;
  354. packet->roll_max = roll_max;
  355. packet->pitch_min = pitch_min;
  356. packet->pitch_max = pitch_max;
  357. packet->yaw_min = yaw_min;
  358. packet->yaw_max = yaw_max;
  359. packet->cap_flags = cap_flags;
  360. packet->custom_cap_flags = custom_cap_flags;
  361. packet->gimbal_device_id = gimbal_device_id;
  362. mav_array_memcpy(packet->vendor_name, vendor_name, sizeof(char)*32);
  363. mav_array_memcpy(packet->model_name, model_name, sizeof(char)*32);
  364. mav_array_memcpy(packet->custom_name, custom_name, sizeof(char)*32);
  365. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION, (const char *)packet, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_CRC);
  366. #endif
  367. }
  368. #endif
  369. #endif
  370. // MESSAGE GIMBAL_DEVICE_INFORMATION UNPACKING
  371. /**
  372. * @brief Get field time_boot_ms from gimbal_device_information message
  373. *
  374. * @return [ms] Timestamp (time since system boot).
  375. */
  376. static inline uint32_t mavlink_msg_gimbal_device_information_get_time_boot_ms(const mavlink_message_t* msg)
  377. {
  378. return _MAV_RETURN_uint32_t(msg, 8);
  379. }
  380. /**
  381. * @brief Get field vendor_name from gimbal_device_information message
  382. *
  383. * @return Name of the gimbal vendor.
  384. */
  385. static inline uint16_t mavlink_msg_gimbal_device_information_get_vendor_name(const mavlink_message_t* msg, char *vendor_name)
  386. {
  387. return _MAV_RETURN_char_array(msg, vendor_name, 32, 48);
  388. }
  389. /**
  390. * @brief Get field model_name from gimbal_device_information message
  391. *
  392. * @return Name of the gimbal model.
  393. */
  394. static inline uint16_t mavlink_msg_gimbal_device_information_get_model_name(const mavlink_message_t* msg, char *model_name)
  395. {
  396. return _MAV_RETURN_char_array(msg, model_name, 32, 80);
  397. }
  398. /**
  399. * @brief Get field custom_name from gimbal_device_information message
  400. *
  401. * @return Custom name of the gimbal given to it by the user.
  402. */
  403. static inline uint16_t mavlink_msg_gimbal_device_information_get_custom_name(const mavlink_message_t* msg, char *custom_name)
  404. {
  405. return _MAV_RETURN_char_array(msg, custom_name, 32, 112);
  406. }
  407. /**
  408. * @brief Get field firmware_version from gimbal_device_information message
  409. *
  410. * @return Version of the gimbal firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).
  411. */
  412. static inline uint32_t mavlink_msg_gimbal_device_information_get_firmware_version(const mavlink_message_t* msg)
  413. {
  414. return _MAV_RETURN_uint32_t(msg, 12);
  415. }
  416. /**
  417. * @brief Get field hardware_version from gimbal_device_information message
  418. *
  419. * @return Version of the gimbal hardware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).
  420. */
  421. static inline uint32_t mavlink_msg_gimbal_device_information_get_hardware_version(const mavlink_message_t* msg)
  422. {
  423. return _MAV_RETURN_uint32_t(msg, 16);
  424. }
  425. /**
  426. * @brief Get field uid from gimbal_device_information message
  427. *
  428. * @return UID of gimbal hardware (0 if unknown).
  429. */
  430. static inline uint64_t mavlink_msg_gimbal_device_information_get_uid(const mavlink_message_t* msg)
  431. {
  432. return _MAV_RETURN_uint64_t(msg, 0);
  433. }
  434. /**
  435. * @brief Get field cap_flags from gimbal_device_information message
  436. *
  437. * @return Bitmap of gimbal capability flags.
  438. */
  439. static inline uint16_t mavlink_msg_gimbal_device_information_get_cap_flags(const mavlink_message_t* msg)
  440. {
  441. return _MAV_RETURN_uint16_t(msg, 44);
  442. }
  443. /**
  444. * @brief Get field custom_cap_flags from gimbal_device_information message
  445. *
  446. * @return Bitmap for use for gimbal-specific capability flags.
  447. */
  448. static inline uint16_t mavlink_msg_gimbal_device_information_get_custom_cap_flags(const mavlink_message_t* msg)
  449. {
  450. return _MAV_RETURN_uint16_t(msg, 46);
  451. }
  452. /**
  453. * @brief Get field roll_min from gimbal_device_information message
  454. *
  455. * @return [rad] Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown.
  456. */
  457. static inline float mavlink_msg_gimbal_device_information_get_roll_min(const mavlink_message_t* msg)
  458. {
  459. return _MAV_RETURN_float(msg, 20);
  460. }
  461. /**
  462. * @brief Get field roll_max from gimbal_device_information message
  463. *
  464. * @return [rad] Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown.
  465. */
  466. static inline float mavlink_msg_gimbal_device_information_get_roll_max(const mavlink_message_t* msg)
  467. {
  468. return _MAV_RETURN_float(msg, 24);
  469. }
  470. /**
  471. * @brief Get field pitch_min from gimbal_device_information message
  472. *
  473. * @return [rad] Minimum hardware pitch angle (positive: up, negative: down). NAN if unknown.
  474. */
  475. static inline float mavlink_msg_gimbal_device_information_get_pitch_min(const mavlink_message_t* msg)
  476. {
  477. return _MAV_RETURN_float(msg, 28);
  478. }
  479. /**
  480. * @brief Get field pitch_max from gimbal_device_information message
  481. *
  482. * @return [rad] Maximum hardware pitch angle (positive: up, negative: down). NAN if unknown.
  483. */
  484. static inline float mavlink_msg_gimbal_device_information_get_pitch_max(const mavlink_message_t* msg)
  485. {
  486. return _MAV_RETURN_float(msg, 32);
  487. }
  488. /**
  489. * @brief Get field yaw_min from gimbal_device_information message
  490. *
  491. * @return [rad] Minimum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown.
  492. */
  493. static inline float mavlink_msg_gimbal_device_information_get_yaw_min(const mavlink_message_t* msg)
  494. {
  495. return _MAV_RETURN_float(msg, 36);
  496. }
  497. /**
  498. * @brief Get field yaw_max from gimbal_device_information message
  499. *
  500. * @return [rad] Maximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown.
  501. */
  502. static inline float mavlink_msg_gimbal_device_information_get_yaw_max(const mavlink_message_t* msg)
  503. {
  504. return _MAV_RETURN_float(msg, 40);
  505. }
  506. /**
  507. * @brief Get field gimbal_device_id from gimbal_device_information message
  508. *
  509. * @return This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set to a number between 1-6. If the component ID is separate, this field is not required and must be set to 0.
  510. */
  511. static inline uint8_t mavlink_msg_gimbal_device_information_get_gimbal_device_id(const mavlink_message_t* msg)
  512. {
  513. return _MAV_RETURN_uint8_t(msg, 144);
  514. }
  515. /**
  516. * @brief Decode a gimbal_device_information message into a struct
  517. *
  518. * @param msg The message to decode
  519. * @param gimbal_device_information C-struct to decode the message contents into
  520. */
  521. static inline void mavlink_msg_gimbal_device_information_decode(const mavlink_message_t* msg, mavlink_gimbal_device_information_t* gimbal_device_information)
  522. {
  523. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  524. gimbal_device_information->uid = mavlink_msg_gimbal_device_information_get_uid(msg);
  525. gimbal_device_information->time_boot_ms = mavlink_msg_gimbal_device_information_get_time_boot_ms(msg);
  526. gimbal_device_information->firmware_version = mavlink_msg_gimbal_device_information_get_firmware_version(msg);
  527. gimbal_device_information->hardware_version = mavlink_msg_gimbal_device_information_get_hardware_version(msg);
  528. gimbal_device_information->roll_min = mavlink_msg_gimbal_device_information_get_roll_min(msg);
  529. gimbal_device_information->roll_max = mavlink_msg_gimbal_device_information_get_roll_max(msg);
  530. gimbal_device_information->pitch_min = mavlink_msg_gimbal_device_information_get_pitch_min(msg);
  531. gimbal_device_information->pitch_max = mavlink_msg_gimbal_device_information_get_pitch_max(msg);
  532. gimbal_device_information->yaw_min = mavlink_msg_gimbal_device_information_get_yaw_min(msg);
  533. gimbal_device_information->yaw_max = mavlink_msg_gimbal_device_information_get_yaw_max(msg);
  534. gimbal_device_information->cap_flags = mavlink_msg_gimbal_device_information_get_cap_flags(msg);
  535. gimbal_device_information->custom_cap_flags = mavlink_msg_gimbal_device_information_get_custom_cap_flags(msg);
  536. mavlink_msg_gimbal_device_information_get_vendor_name(msg, gimbal_device_information->vendor_name);
  537. mavlink_msg_gimbal_device_information_get_model_name(msg, gimbal_device_information->model_name);
  538. mavlink_msg_gimbal_device_information_get_custom_name(msg, gimbal_device_information->custom_name);
  539. gimbal_device_information->gimbal_device_id = mavlink_msg_gimbal_device_information_get_gimbal_device_id(msg);
  540. #else
  541. uint8_t len = msg->len < MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN? msg->len : MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN;
  542. memset(gimbal_device_information, 0, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN);
  543. memcpy(gimbal_device_information, _MAV_PAYLOAD(msg), len);
  544. #endif
  545. }