mavlink_msg_camera_information.h 31 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532
  1. #pragma once
  2. // MESSAGE CAMERA_INFORMATION PACKING
  3. #define MAVLINK_MSG_ID_CAMERA_INFORMATION 259
  4. typedef struct __mavlink_camera_information_t {
  5. uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
  6. uint32_t firmware_version; /*< Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). Use 0 if not known.*/
  7. float focal_length; /*< [mm] Focal length. Use NaN if not known.*/
  8. float sensor_size_h; /*< [mm] Image sensor size horizontal. Use NaN if not known.*/
  9. float sensor_size_v; /*< [mm] Image sensor size vertical. Use NaN if not known.*/
  10. uint32_t flags; /*< Bitmap of camera capability flags.*/
  11. uint16_t resolution_h; /*< [pix] Horizontal image resolution. Use 0 if not known.*/
  12. uint16_t resolution_v; /*< [pix] Vertical image resolution. Use 0 if not known.*/
  13. uint16_t cam_definition_version; /*< Camera definition version (iteration). Use 0 if not known.*/
  14. uint8_t vendor_name[32]; /*< Name of the camera vendor*/
  15. uint8_t model_name[32]; /*< Name of the camera model*/
  16. uint8_t lens_id; /*< Reserved for a lens ID. Use 0 if not known.*/
  17. char cam_definition_uri[140]; /*< Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). The definition file may be xz compressed, which will be indicated by the file extension .xml.xz (a GCS that implements the protocol must support decompressing the file). The string needs to be zero terminated. Use a zero-length string if not known.*/
  18. uint8_t gimbal_device_id; /*< Gimbal id of a gimbal associated with this camera. This is the component id of the gimbal device, or 1-6 for non mavlink gimbals. Use 0 if no gimbal is associated with the camera.*/
  19. } mavlink_camera_information_t;
  20. #define MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN 236
  21. #define MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN 235
  22. #define MAVLINK_MSG_ID_259_LEN 236
  23. #define MAVLINK_MSG_ID_259_MIN_LEN 235
  24. #define MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC 92
  25. #define MAVLINK_MSG_ID_259_CRC 92
  26. #define MAVLINK_MSG_CAMERA_INFORMATION_FIELD_VENDOR_NAME_LEN 32
  27. #define MAVLINK_MSG_CAMERA_INFORMATION_FIELD_MODEL_NAME_LEN 32
  28. #define MAVLINK_MSG_CAMERA_INFORMATION_FIELD_CAM_DEFINITION_URI_LEN 140
  29. #if MAVLINK_COMMAND_24BIT
  30. #define MAVLINK_MESSAGE_INFO_CAMERA_INFORMATION { \
  31. 259, \
  32. "CAMERA_INFORMATION", \
  33. 14, \
  34. { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_camera_information_t, time_boot_ms) }, \
  35. { "vendor_name", NULL, MAVLINK_TYPE_UINT8_T, 32, 30, offsetof(mavlink_camera_information_t, vendor_name) }, \
  36. { "model_name", NULL, MAVLINK_TYPE_UINT8_T, 32, 62, offsetof(mavlink_camera_information_t, model_name) }, \
  37. { "firmware_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_camera_information_t, firmware_version) }, \
  38. { "focal_length", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_camera_information_t, focal_length) }, \
  39. { "sensor_size_h", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_information_t, sensor_size_h) }, \
  40. { "sensor_size_v", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_information_t, sensor_size_v) }, \
  41. { "resolution_h", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_camera_information_t, resolution_h) }, \
  42. { "resolution_v", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_camera_information_t, resolution_v) }, \
  43. { "lens_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 94, offsetof(mavlink_camera_information_t, lens_id) }, \
  44. { "flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_camera_information_t, flags) }, \
  45. { "cam_definition_version", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_camera_information_t, cam_definition_version) }, \
  46. { "cam_definition_uri", NULL, MAVLINK_TYPE_CHAR, 140, 95, offsetof(mavlink_camera_information_t, cam_definition_uri) }, \
  47. { "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 235, offsetof(mavlink_camera_information_t, gimbal_device_id) }, \
  48. } \
  49. }
  50. #else
  51. #define MAVLINK_MESSAGE_INFO_CAMERA_INFORMATION { \
  52. "CAMERA_INFORMATION", \
  53. 14, \
  54. { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_camera_information_t, time_boot_ms) }, \
  55. { "vendor_name", NULL, MAVLINK_TYPE_UINT8_T, 32, 30, offsetof(mavlink_camera_information_t, vendor_name) }, \
  56. { "model_name", NULL, MAVLINK_TYPE_UINT8_T, 32, 62, offsetof(mavlink_camera_information_t, model_name) }, \
  57. { "firmware_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_camera_information_t, firmware_version) }, \
  58. { "focal_length", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_camera_information_t, focal_length) }, \
  59. { "sensor_size_h", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_information_t, sensor_size_h) }, \
  60. { "sensor_size_v", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_information_t, sensor_size_v) }, \
  61. { "resolution_h", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_camera_information_t, resolution_h) }, \
  62. { "resolution_v", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_camera_information_t, resolution_v) }, \
  63. { "lens_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 94, offsetof(mavlink_camera_information_t, lens_id) }, \
  64. { "flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_camera_information_t, flags) }, \
  65. { "cam_definition_version", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_camera_information_t, cam_definition_version) }, \
  66. { "cam_definition_uri", NULL, MAVLINK_TYPE_CHAR, 140, 95, offsetof(mavlink_camera_information_t, cam_definition_uri) }, \
  67. { "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 235, offsetof(mavlink_camera_information_t, gimbal_device_id) }, \
  68. } \
  69. }
  70. #endif
  71. /**
  72. * @brief Pack a camera_information message
  73. * @param system_id ID of this system
  74. * @param component_id ID of this component (e.g. 200 for IMU)
  75. * @param msg The MAVLink message to compress the data into
  76. *
  77. * @param time_boot_ms [ms] Timestamp (time since system boot).
  78. * @param vendor_name Name of the camera vendor
  79. * @param model_name Name of the camera model
  80. * @param firmware_version Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). Use 0 if not known.
  81. * @param focal_length [mm] Focal length. Use NaN if not known.
  82. * @param sensor_size_h [mm] Image sensor size horizontal. Use NaN if not known.
  83. * @param sensor_size_v [mm] Image sensor size vertical. Use NaN if not known.
  84. * @param resolution_h [pix] Horizontal image resolution. Use 0 if not known.
  85. * @param resolution_v [pix] Vertical image resolution. Use 0 if not known.
  86. * @param lens_id Reserved for a lens ID. Use 0 if not known.
  87. * @param flags Bitmap of camera capability flags.
  88. * @param cam_definition_version Camera definition version (iteration). Use 0 if not known.
  89. * @param cam_definition_uri Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). The definition file may be xz compressed, which will be indicated by the file extension .xml.xz (a GCS that implements the protocol must support decompressing the file). The string needs to be zero terminated. Use a zero-length string if not known.
  90. * @param gimbal_device_id Gimbal id of a gimbal associated with this camera. This is the component id of the gimbal device, or 1-6 for non mavlink gimbals. Use 0 if no gimbal is associated with the camera.
  91. * @return length of the message in bytes (excluding serial stream start sign)
  92. */
  93. static inline uint16_t mavlink_msg_camera_information_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  94. uint32_t time_boot_ms, const uint8_t *vendor_name, const uint8_t *model_name, uint32_t firmware_version, float focal_length, float sensor_size_h, float sensor_size_v, uint16_t resolution_h, uint16_t resolution_v, uint8_t lens_id, uint32_t flags, uint16_t cam_definition_version, const char *cam_definition_uri, uint8_t gimbal_device_id)
  95. {
  96. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  97. char buf[MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN];
  98. _mav_put_uint32_t(buf, 0, time_boot_ms);
  99. _mav_put_uint32_t(buf, 4, firmware_version);
  100. _mav_put_float(buf, 8, focal_length);
  101. _mav_put_float(buf, 12, sensor_size_h);
  102. _mav_put_float(buf, 16, sensor_size_v);
  103. _mav_put_uint32_t(buf, 20, flags);
  104. _mav_put_uint16_t(buf, 24, resolution_h);
  105. _mav_put_uint16_t(buf, 26, resolution_v);
  106. _mav_put_uint16_t(buf, 28, cam_definition_version);
  107. _mav_put_uint8_t(buf, 94, lens_id);
  108. _mav_put_uint8_t(buf, 235, gimbal_device_id);
  109. _mav_put_uint8_t_array(buf, 30, vendor_name, 32);
  110. _mav_put_uint8_t_array(buf, 62, model_name, 32);
  111. _mav_put_char_array(buf, 95, cam_definition_uri, 140);
  112. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN);
  113. #else
  114. mavlink_camera_information_t packet;
  115. packet.time_boot_ms = time_boot_ms;
  116. packet.firmware_version = firmware_version;
  117. packet.focal_length = focal_length;
  118. packet.sensor_size_h = sensor_size_h;
  119. packet.sensor_size_v = sensor_size_v;
  120. packet.flags = flags;
  121. packet.resolution_h = resolution_h;
  122. packet.resolution_v = resolution_v;
  123. packet.cam_definition_version = cam_definition_version;
  124. packet.lens_id = lens_id;
  125. packet.gimbal_device_id = gimbal_device_id;
  126. mav_array_memcpy(packet.vendor_name, vendor_name, sizeof(uint8_t)*32);
  127. mav_array_memcpy(packet.model_name, model_name, sizeof(uint8_t)*32);
  128. mav_array_memcpy(packet.cam_definition_uri, cam_definition_uri, sizeof(char)*140);
  129. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN);
  130. #endif
  131. msg->msgid = MAVLINK_MSG_ID_CAMERA_INFORMATION;
  132. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC);
  133. }
  134. /**
  135. * @brief Pack a camera_information message on a channel
  136. * @param system_id ID of this system
  137. * @param component_id ID of this component (e.g. 200 for IMU)
  138. * @param chan The MAVLink channel this message will be sent over
  139. * @param msg The MAVLink message to compress the data into
  140. * @param time_boot_ms [ms] Timestamp (time since system boot).
  141. * @param vendor_name Name of the camera vendor
  142. * @param model_name Name of the camera model
  143. * @param firmware_version Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). Use 0 if not known.
  144. * @param focal_length [mm] Focal length. Use NaN if not known.
  145. * @param sensor_size_h [mm] Image sensor size horizontal. Use NaN if not known.
  146. * @param sensor_size_v [mm] Image sensor size vertical. Use NaN if not known.
  147. * @param resolution_h [pix] Horizontal image resolution. Use 0 if not known.
  148. * @param resolution_v [pix] Vertical image resolution. Use 0 if not known.
  149. * @param lens_id Reserved for a lens ID. Use 0 if not known.
  150. * @param flags Bitmap of camera capability flags.
  151. * @param cam_definition_version Camera definition version (iteration). Use 0 if not known.
  152. * @param cam_definition_uri Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). The definition file may be xz compressed, which will be indicated by the file extension .xml.xz (a GCS that implements the protocol must support decompressing the file). The string needs to be zero terminated. Use a zero-length string if not known.
  153. * @param gimbal_device_id Gimbal id of a gimbal associated with this camera. This is the component id of the gimbal device, or 1-6 for non mavlink gimbals. Use 0 if no gimbal is associated with the camera.
  154. * @return length of the message in bytes (excluding serial stream start sign)
  155. */
  156. static inline uint16_t mavlink_msg_camera_information_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  157. mavlink_message_t* msg,
  158. uint32_t time_boot_ms,const uint8_t *vendor_name,const uint8_t *model_name,uint32_t firmware_version,float focal_length,float sensor_size_h,float sensor_size_v,uint16_t resolution_h,uint16_t resolution_v,uint8_t lens_id,uint32_t flags,uint16_t cam_definition_version,const char *cam_definition_uri,uint8_t gimbal_device_id)
  159. {
  160. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  161. char buf[MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN];
  162. _mav_put_uint32_t(buf, 0, time_boot_ms);
  163. _mav_put_uint32_t(buf, 4, firmware_version);
  164. _mav_put_float(buf, 8, focal_length);
  165. _mav_put_float(buf, 12, sensor_size_h);
  166. _mav_put_float(buf, 16, sensor_size_v);
  167. _mav_put_uint32_t(buf, 20, flags);
  168. _mav_put_uint16_t(buf, 24, resolution_h);
  169. _mav_put_uint16_t(buf, 26, resolution_v);
  170. _mav_put_uint16_t(buf, 28, cam_definition_version);
  171. _mav_put_uint8_t(buf, 94, lens_id);
  172. _mav_put_uint8_t(buf, 235, gimbal_device_id);
  173. _mav_put_uint8_t_array(buf, 30, vendor_name, 32);
  174. _mav_put_uint8_t_array(buf, 62, model_name, 32);
  175. _mav_put_char_array(buf, 95, cam_definition_uri, 140);
  176. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN);
  177. #else
  178. mavlink_camera_information_t packet;
  179. packet.time_boot_ms = time_boot_ms;
  180. packet.firmware_version = firmware_version;
  181. packet.focal_length = focal_length;
  182. packet.sensor_size_h = sensor_size_h;
  183. packet.sensor_size_v = sensor_size_v;
  184. packet.flags = flags;
  185. packet.resolution_h = resolution_h;
  186. packet.resolution_v = resolution_v;
  187. packet.cam_definition_version = cam_definition_version;
  188. packet.lens_id = lens_id;
  189. packet.gimbal_device_id = gimbal_device_id;
  190. mav_array_memcpy(packet.vendor_name, vendor_name, sizeof(uint8_t)*32);
  191. mav_array_memcpy(packet.model_name, model_name, sizeof(uint8_t)*32);
  192. mav_array_memcpy(packet.cam_definition_uri, cam_definition_uri, sizeof(char)*140);
  193. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN);
  194. #endif
  195. msg->msgid = MAVLINK_MSG_ID_CAMERA_INFORMATION;
  196. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC);
  197. }
  198. /**
  199. * @brief Encode a camera_information struct
  200. *
  201. * @param system_id ID of this system
  202. * @param component_id ID of this component (e.g. 200 for IMU)
  203. * @param msg The MAVLink message to compress the data into
  204. * @param camera_information C-struct to read the message contents from
  205. */
  206. static inline uint16_t mavlink_msg_camera_information_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_information_t* camera_information)
  207. {
  208. return mavlink_msg_camera_information_pack(system_id, component_id, msg, camera_information->time_boot_ms, camera_information->vendor_name, camera_information->model_name, camera_information->firmware_version, camera_information->focal_length, camera_information->sensor_size_h, camera_information->sensor_size_v, camera_information->resolution_h, camera_information->resolution_v, camera_information->lens_id, camera_information->flags, camera_information->cam_definition_version, camera_information->cam_definition_uri, camera_information->gimbal_device_id);
  209. }
  210. /**
  211. * @brief Encode a camera_information struct on a channel
  212. *
  213. * @param system_id ID of this system
  214. * @param component_id ID of this component (e.g. 200 for IMU)
  215. * @param chan The MAVLink channel this message will be sent over
  216. * @param msg The MAVLink message to compress the data into
  217. * @param camera_information C-struct to read the message contents from
  218. */
  219. static inline uint16_t mavlink_msg_camera_information_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_information_t* camera_information)
  220. {
  221. return mavlink_msg_camera_information_pack_chan(system_id, component_id, chan, msg, camera_information->time_boot_ms, camera_information->vendor_name, camera_information->model_name, camera_information->firmware_version, camera_information->focal_length, camera_information->sensor_size_h, camera_information->sensor_size_v, camera_information->resolution_h, camera_information->resolution_v, camera_information->lens_id, camera_information->flags, camera_information->cam_definition_version, camera_information->cam_definition_uri, camera_information->gimbal_device_id);
  222. }
  223. /**
  224. * @brief Send a camera_information message
  225. * @param chan MAVLink channel to send the message
  226. *
  227. * @param time_boot_ms [ms] Timestamp (time since system boot).
  228. * @param vendor_name Name of the camera vendor
  229. * @param model_name Name of the camera model
  230. * @param firmware_version Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). Use 0 if not known.
  231. * @param focal_length [mm] Focal length. Use NaN if not known.
  232. * @param sensor_size_h [mm] Image sensor size horizontal. Use NaN if not known.
  233. * @param sensor_size_v [mm] Image sensor size vertical. Use NaN if not known.
  234. * @param resolution_h [pix] Horizontal image resolution. Use 0 if not known.
  235. * @param resolution_v [pix] Vertical image resolution. Use 0 if not known.
  236. * @param lens_id Reserved for a lens ID. Use 0 if not known.
  237. * @param flags Bitmap of camera capability flags.
  238. * @param cam_definition_version Camera definition version (iteration). Use 0 if not known.
  239. * @param cam_definition_uri Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). The definition file may be xz compressed, which will be indicated by the file extension .xml.xz (a GCS that implements the protocol must support decompressing the file). The string needs to be zero terminated. Use a zero-length string if not known.
  240. * @param gimbal_device_id Gimbal id of a gimbal associated with this camera. This is the component id of the gimbal device, or 1-6 for non mavlink gimbals. Use 0 if no gimbal is associated with the camera.
  241. */
  242. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  243. static inline void mavlink_msg_camera_information_send(mavlink_channel_t chan, uint32_t time_boot_ms, const uint8_t *vendor_name, const uint8_t *model_name, uint32_t firmware_version, float focal_length, float sensor_size_h, float sensor_size_v, uint16_t resolution_h, uint16_t resolution_v, uint8_t lens_id, uint32_t flags, uint16_t cam_definition_version, const char *cam_definition_uri, uint8_t gimbal_device_id)
  244. {
  245. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  246. char buf[MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN];
  247. _mav_put_uint32_t(buf, 0, time_boot_ms);
  248. _mav_put_uint32_t(buf, 4, firmware_version);
  249. _mav_put_float(buf, 8, focal_length);
  250. _mav_put_float(buf, 12, sensor_size_h);
  251. _mav_put_float(buf, 16, sensor_size_v);
  252. _mav_put_uint32_t(buf, 20, flags);
  253. _mav_put_uint16_t(buf, 24, resolution_h);
  254. _mav_put_uint16_t(buf, 26, resolution_v);
  255. _mav_put_uint16_t(buf, 28, cam_definition_version);
  256. _mav_put_uint8_t(buf, 94, lens_id);
  257. _mav_put_uint8_t(buf, 235, gimbal_device_id);
  258. _mav_put_uint8_t_array(buf, 30, vendor_name, 32);
  259. _mav_put_uint8_t_array(buf, 62, model_name, 32);
  260. _mav_put_char_array(buf, 95, cam_definition_uri, 140);
  261. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_INFORMATION, buf, MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC);
  262. #else
  263. mavlink_camera_information_t packet;
  264. packet.time_boot_ms = time_boot_ms;
  265. packet.firmware_version = firmware_version;
  266. packet.focal_length = focal_length;
  267. packet.sensor_size_h = sensor_size_h;
  268. packet.sensor_size_v = sensor_size_v;
  269. packet.flags = flags;
  270. packet.resolution_h = resolution_h;
  271. packet.resolution_v = resolution_v;
  272. packet.cam_definition_version = cam_definition_version;
  273. packet.lens_id = lens_id;
  274. packet.gimbal_device_id = gimbal_device_id;
  275. mav_array_memcpy(packet.vendor_name, vendor_name, sizeof(uint8_t)*32);
  276. mav_array_memcpy(packet.model_name, model_name, sizeof(uint8_t)*32);
  277. mav_array_memcpy(packet.cam_definition_uri, cam_definition_uri, sizeof(char)*140);
  278. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_INFORMATION, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC);
  279. #endif
  280. }
  281. /**
  282. * @brief Send a camera_information message
  283. * @param chan MAVLink channel to send the message
  284. * @param struct The MAVLink struct to serialize
  285. */
  286. static inline void mavlink_msg_camera_information_send_struct(mavlink_channel_t chan, const mavlink_camera_information_t* camera_information)
  287. {
  288. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  289. mavlink_msg_camera_information_send(chan, camera_information->time_boot_ms, camera_information->vendor_name, camera_information->model_name, camera_information->firmware_version, camera_information->focal_length, camera_information->sensor_size_h, camera_information->sensor_size_v, camera_information->resolution_h, camera_information->resolution_v, camera_information->lens_id, camera_information->flags, camera_information->cam_definition_version, camera_information->cam_definition_uri, camera_information->gimbal_device_id);
  290. #else
  291. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_INFORMATION, (const char *)camera_information, MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC);
  292. #endif
  293. }
  294. #if MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  295. /*
  296. This variant of _send() can be used to save stack space by re-using
  297. memory from the receive buffer. The caller provides a
  298. mavlink_message_t which is the size of a full mavlink message. This
  299. is usually the receive buffer for the channel, and allows a reply to an
  300. incoming message with minimum stack space usage.
  301. */
  302. static inline void mavlink_msg_camera_information_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, const uint8_t *vendor_name, const uint8_t *model_name, uint32_t firmware_version, float focal_length, float sensor_size_h, float sensor_size_v, uint16_t resolution_h, uint16_t resolution_v, uint8_t lens_id, uint32_t flags, uint16_t cam_definition_version, const char *cam_definition_uri, uint8_t gimbal_device_id)
  303. {
  304. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  305. char *buf = (char *)msgbuf;
  306. _mav_put_uint32_t(buf, 0, time_boot_ms);
  307. _mav_put_uint32_t(buf, 4, firmware_version);
  308. _mav_put_float(buf, 8, focal_length);
  309. _mav_put_float(buf, 12, sensor_size_h);
  310. _mav_put_float(buf, 16, sensor_size_v);
  311. _mav_put_uint32_t(buf, 20, flags);
  312. _mav_put_uint16_t(buf, 24, resolution_h);
  313. _mav_put_uint16_t(buf, 26, resolution_v);
  314. _mav_put_uint16_t(buf, 28, cam_definition_version);
  315. _mav_put_uint8_t(buf, 94, lens_id);
  316. _mav_put_uint8_t(buf, 235, gimbal_device_id);
  317. _mav_put_uint8_t_array(buf, 30, vendor_name, 32);
  318. _mav_put_uint8_t_array(buf, 62, model_name, 32);
  319. _mav_put_char_array(buf, 95, cam_definition_uri, 140);
  320. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_INFORMATION, buf, MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC);
  321. #else
  322. mavlink_camera_information_t *packet = (mavlink_camera_information_t *)msgbuf;
  323. packet->time_boot_ms = time_boot_ms;
  324. packet->firmware_version = firmware_version;
  325. packet->focal_length = focal_length;
  326. packet->sensor_size_h = sensor_size_h;
  327. packet->sensor_size_v = sensor_size_v;
  328. packet->flags = flags;
  329. packet->resolution_h = resolution_h;
  330. packet->resolution_v = resolution_v;
  331. packet->cam_definition_version = cam_definition_version;
  332. packet->lens_id = lens_id;
  333. packet->gimbal_device_id = gimbal_device_id;
  334. mav_array_memcpy(packet->vendor_name, vendor_name, sizeof(uint8_t)*32);
  335. mav_array_memcpy(packet->model_name, model_name, sizeof(uint8_t)*32);
  336. mav_array_memcpy(packet->cam_definition_uri, cam_definition_uri, sizeof(char)*140);
  337. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_INFORMATION, (const char *)packet, MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC);
  338. #endif
  339. }
  340. #endif
  341. #endif
  342. // MESSAGE CAMERA_INFORMATION UNPACKING
  343. /**
  344. * @brief Get field time_boot_ms from camera_information message
  345. *
  346. * @return [ms] Timestamp (time since system boot).
  347. */
  348. static inline uint32_t mavlink_msg_camera_information_get_time_boot_ms(const mavlink_message_t* msg)
  349. {
  350. return _MAV_RETURN_uint32_t(msg, 0);
  351. }
  352. /**
  353. * @brief Get field vendor_name from camera_information message
  354. *
  355. * @return Name of the camera vendor
  356. */
  357. static inline uint16_t mavlink_msg_camera_information_get_vendor_name(const mavlink_message_t* msg, uint8_t *vendor_name)
  358. {
  359. return _MAV_RETURN_uint8_t_array(msg, vendor_name, 32, 30);
  360. }
  361. /**
  362. * @brief Get field model_name from camera_information message
  363. *
  364. * @return Name of the camera model
  365. */
  366. static inline uint16_t mavlink_msg_camera_information_get_model_name(const mavlink_message_t* msg, uint8_t *model_name)
  367. {
  368. return _MAV_RETURN_uint8_t_array(msg, model_name, 32, 62);
  369. }
  370. /**
  371. * @brief Get field firmware_version from camera_information message
  372. *
  373. * @return Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). Use 0 if not known.
  374. */
  375. static inline uint32_t mavlink_msg_camera_information_get_firmware_version(const mavlink_message_t* msg)
  376. {
  377. return _MAV_RETURN_uint32_t(msg, 4);
  378. }
  379. /**
  380. * @brief Get field focal_length from camera_information message
  381. *
  382. * @return [mm] Focal length. Use NaN if not known.
  383. */
  384. static inline float mavlink_msg_camera_information_get_focal_length(const mavlink_message_t* msg)
  385. {
  386. return _MAV_RETURN_float(msg, 8);
  387. }
  388. /**
  389. * @brief Get field sensor_size_h from camera_information message
  390. *
  391. * @return [mm] Image sensor size horizontal. Use NaN if not known.
  392. */
  393. static inline float mavlink_msg_camera_information_get_sensor_size_h(const mavlink_message_t* msg)
  394. {
  395. return _MAV_RETURN_float(msg, 12);
  396. }
  397. /**
  398. * @brief Get field sensor_size_v from camera_information message
  399. *
  400. * @return [mm] Image sensor size vertical. Use NaN if not known.
  401. */
  402. static inline float mavlink_msg_camera_information_get_sensor_size_v(const mavlink_message_t* msg)
  403. {
  404. return _MAV_RETURN_float(msg, 16);
  405. }
  406. /**
  407. * @brief Get field resolution_h from camera_information message
  408. *
  409. * @return [pix] Horizontal image resolution. Use 0 if not known.
  410. */
  411. static inline uint16_t mavlink_msg_camera_information_get_resolution_h(const mavlink_message_t* msg)
  412. {
  413. return _MAV_RETURN_uint16_t(msg, 24);
  414. }
  415. /**
  416. * @brief Get field resolution_v from camera_information message
  417. *
  418. * @return [pix] Vertical image resolution. Use 0 if not known.
  419. */
  420. static inline uint16_t mavlink_msg_camera_information_get_resolution_v(const mavlink_message_t* msg)
  421. {
  422. return _MAV_RETURN_uint16_t(msg, 26);
  423. }
  424. /**
  425. * @brief Get field lens_id from camera_information message
  426. *
  427. * @return Reserved for a lens ID. Use 0 if not known.
  428. */
  429. static inline uint8_t mavlink_msg_camera_information_get_lens_id(const mavlink_message_t* msg)
  430. {
  431. return _MAV_RETURN_uint8_t(msg, 94);
  432. }
  433. /**
  434. * @brief Get field flags from camera_information message
  435. *
  436. * @return Bitmap of camera capability flags.
  437. */
  438. static inline uint32_t mavlink_msg_camera_information_get_flags(const mavlink_message_t* msg)
  439. {
  440. return _MAV_RETURN_uint32_t(msg, 20);
  441. }
  442. /**
  443. * @brief Get field cam_definition_version from camera_information message
  444. *
  445. * @return Camera definition version (iteration). Use 0 if not known.
  446. */
  447. static inline uint16_t mavlink_msg_camera_information_get_cam_definition_version(const mavlink_message_t* msg)
  448. {
  449. return _MAV_RETURN_uint16_t(msg, 28);
  450. }
  451. /**
  452. * @brief Get field cam_definition_uri from camera_information message
  453. *
  454. * @return Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). The definition file may be xz compressed, which will be indicated by the file extension .xml.xz (a GCS that implements the protocol must support decompressing the file). The string needs to be zero terminated. Use a zero-length string if not known.
  455. */
  456. static inline uint16_t mavlink_msg_camera_information_get_cam_definition_uri(const mavlink_message_t* msg, char *cam_definition_uri)
  457. {
  458. return _MAV_RETURN_char_array(msg, cam_definition_uri, 140, 95);
  459. }
  460. /**
  461. * @brief Get field gimbal_device_id from camera_information message
  462. *
  463. * @return Gimbal id of a gimbal associated with this camera. This is the component id of the gimbal device, or 1-6 for non mavlink gimbals. Use 0 if no gimbal is associated with the camera.
  464. */
  465. static inline uint8_t mavlink_msg_camera_information_get_gimbal_device_id(const mavlink_message_t* msg)
  466. {
  467. return _MAV_RETURN_uint8_t(msg, 235);
  468. }
  469. /**
  470. * @brief Decode a camera_information message into a struct
  471. *
  472. * @param msg The message to decode
  473. * @param camera_information C-struct to decode the message contents into
  474. */
  475. static inline void mavlink_msg_camera_information_decode(const mavlink_message_t* msg, mavlink_camera_information_t* camera_information)
  476. {
  477. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  478. camera_information->time_boot_ms = mavlink_msg_camera_information_get_time_boot_ms(msg);
  479. camera_information->firmware_version = mavlink_msg_camera_information_get_firmware_version(msg);
  480. camera_information->focal_length = mavlink_msg_camera_information_get_focal_length(msg);
  481. camera_information->sensor_size_h = mavlink_msg_camera_information_get_sensor_size_h(msg);
  482. camera_information->sensor_size_v = mavlink_msg_camera_information_get_sensor_size_v(msg);
  483. camera_information->flags = mavlink_msg_camera_information_get_flags(msg);
  484. camera_information->resolution_h = mavlink_msg_camera_information_get_resolution_h(msg);
  485. camera_information->resolution_v = mavlink_msg_camera_information_get_resolution_v(msg);
  486. camera_information->cam_definition_version = mavlink_msg_camera_information_get_cam_definition_version(msg);
  487. mavlink_msg_camera_information_get_vendor_name(msg, camera_information->vendor_name);
  488. mavlink_msg_camera_information_get_model_name(msg, camera_information->model_name);
  489. camera_information->lens_id = mavlink_msg_camera_information_get_lens_id(msg);
  490. mavlink_msg_camera_information_get_cam_definition_uri(msg, camera_information->cam_definition_uri);
  491. camera_information->gimbal_device_id = mavlink_msg_camera_information_get_gimbal_device_id(msg);
  492. #else
  493. uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN;
  494. memset(camera_information, 0, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN);
  495. memcpy(camera_information, _MAV_PAYLOAD(msg), len);
  496. #endif
  497. }