mavlink_msg_camera_image_captured.h 23 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456
  1. #pragma once
  2. // MESSAGE CAMERA_IMAGE_CAPTURED PACKING
  3. #define MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED 263
  4. typedef struct __mavlink_camera_image_captured_t {
  5. uint64_t time_utc; /*< [us] Timestamp (time since UNIX epoch) in UTC. 0 for unknown.*/
  6. uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
  7. int32_t lat; /*< [degE7] Latitude where image was taken*/
  8. int32_t lon; /*< [degE7] Longitude where capture was taken*/
  9. int32_t alt; /*< [mm] Altitude (MSL) where image was taken*/
  10. int32_t relative_alt; /*< [mm] Altitude above ground*/
  11. float q[4]; /*< Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/
  12. int32_t image_index; /*< Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1)*/
  13. uint8_t camera_id; /*< Deprecated/unused. Component IDs are used to differentiate multiple cameras.*/
  14. int8_t capture_result; /*< Boolean indicating success (1) or failure (0) while capturing this image.*/
  15. char file_url[205]; /*< URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface.*/
  16. } mavlink_camera_image_captured_t;
  17. #define MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN 255
  18. #define MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN 255
  19. #define MAVLINK_MSG_ID_263_LEN 255
  20. #define MAVLINK_MSG_ID_263_MIN_LEN 255
  21. #define MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC 133
  22. #define MAVLINK_MSG_ID_263_CRC 133
  23. #define MAVLINK_MSG_CAMERA_IMAGE_CAPTURED_FIELD_Q_LEN 4
  24. #define MAVLINK_MSG_CAMERA_IMAGE_CAPTURED_FIELD_FILE_URL_LEN 205
  25. #if MAVLINK_COMMAND_24BIT
  26. #define MAVLINK_MESSAGE_INFO_CAMERA_IMAGE_CAPTURED { \
  27. 263, \
  28. "CAMERA_IMAGE_CAPTURED", \
  29. 11, \
  30. { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_camera_image_captured_t, time_boot_ms) }, \
  31. { "time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_image_captured_t, time_utc) }, \
  32. { "camera_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_camera_image_captured_t, camera_id) }, \
  33. { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_camera_image_captured_t, lat) }, \
  34. { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_camera_image_captured_t, lon) }, \
  35. { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_camera_image_captured_t, alt) }, \
  36. { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_camera_image_captured_t, relative_alt) }, \
  37. { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 28, offsetof(mavlink_camera_image_captured_t, q) }, \
  38. { "image_index", NULL, MAVLINK_TYPE_INT32_T, 0, 44, offsetof(mavlink_camera_image_captured_t, image_index) }, \
  39. { "capture_result", NULL, MAVLINK_TYPE_INT8_T, 0, 49, offsetof(mavlink_camera_image_captured_t, capture_result) }, \
  40. { "file_url", NULL, MAVLINK_TYPE_CHAR, 205, 50, offsetof(mavlink_camera_image_captured_t, file_url) }, \
  41. } \
  42. }
  43. #else
  44. #define MAVLINK_MESSAGE_INFO_CAMERA_IMAGE_CAPTURED { \
  45. "CAMERA_IMAGE_CAPTURED", \
  46. 11, \
  47. { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_camera_image_captured_t, time_boot_ms) }, \
  48. { "time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_image_captured_t, time_utc) }, \
  49. { "camera_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_camera_image_captured_t, camera_id) }, \
  50. { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_camera_image_captured_t, lat) }, \
  51. { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_camera_image_captured_t, lon) }, \
  52. { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_camera_image_captured_t, alt) }, \
  53. { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_camera_image_captured_t, relative_alt) }, \
  54. { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 28, offsetof(mavlink_camera_image_captured_t, q) }, \
  55. { "image_index", NULL, MAVLINK_TYPE_INT32_T, 0, 44, offsetof(mavlink_camera_image_captured_t, image_index) }, \
  56. { "capture_result", NULL, MAVLINK_TYPE_INT8_T, 0, 49, offsetof(mavlink_camera_image_captured_t, capture_result) }, \
  57. { "file_url", NULL, MAVLINK_TYPE_CHAR, 205, 50, offsetof(mavlink_camera_image_captured_t, file_url) }, \
  58. } \
  59. }
  60. #endif
  61. /**
  62. * @brief Pack a camera_image_captured message
  63. * @param system_id ID of this system
  64. * @param component_id ID of this component (e.g. 200 for IMU)
  65. * @param msg The MAVLink message to compress the data into
  66. *
  67. * @param time_boot_ms [ms] Timestamp (time since system boot).
  68. * @param time_utc [us] Timestamp (time since UNIX epoch) in UTC. 0 for unknown.
  69. * @param camera_id Deprecated/unused. Component IDs are used to differentiate multiple cameras.
  70. * @param lat [degE7] Latitude where image was taken
  71. * @param lon [degE7] Longitude where capture was taken
  72. * @param alt [mm] Altitude (MSL) where image was taken
  73. * @param relative_alt [mm] Altitude above ground
  74. * @param q Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
  75. * @param image_index Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1)
  76. * @param capture_result Boolean indicating success (1) or failure (0) while capturing this image.
  77. * @param file_url URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface.
  78. * @return length of the message in bytes (excluding serial stream start sign)
  79. */
  80. static inline uint16_t mavlink_msg_camera_image_captured_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  81. uint32_t time_boot_ms, uint64_t time_utc, uint8_t camera_id, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, const float *q, int32_t image_index, int8_t capture_result, const char *file_url)
  82. {
  83. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  84. char buf[MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN];
  85. _mav_put_uint64_t(buf, 0, time_utc);
  86. _mav_put_uint32_t(buf, 8, time_boot_ms);
  87. _mav_put_int32_t(buf, 12, lat);
  88. _mav_put_int32_t(buf, 16, lon);
  89. _mav_put_int32_t(buf, 20, alt);
  90. _mav_put_int32_t(buf, 24, relative_alt);
  91. _mav_put_int32_t(buf, 44, image_index);
  92. _mav_put_uint8_t(buf, 48, camera_id);
  93. _mav_put_int8_t(buf, 49, capture_result);
  94. _mav_put_float_array(buf, 28, q, 4);
  95. _mav_put_char_array(buf, 50, file_url, 205);
  96. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN);
  97. #else
  98. mavlink_camera_image_captured_t packet;
  99. packet.time_utc = time_utc;
  100. packet.time_boot_ms = time_boot_ms;
  101. packet.lat = lat;
  102. packet.lon = lon;
  103. packet.alt = alt;
  104. packet.relative_alt = relative_alt;
  105. packet.image_index = image_index;
  106. packet.camera_id = camera_id;
  107. packet.capture_result = capture_result;
  108. mav_array_memcpy(packet.q, q, sizeof(float)*4);
  109. mav_array_memcpy(packet.file_url, file_url, sizeof(char)*205);
  110. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN);
  111. #endif
  112. msg->msgid = MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED;
  113. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC);
  114. }
  115. /**
  116. * @brief Pack a camera_image_captured message on a channel
  117. * @param system_id ID of this system
  118. * @param component_id ID of this component (e.g. 200 for IMU)
  119. * @param chan The MAVLink channel this message will be sent over
  120. * @param msg The MAVLink message to compress the data into
  121. * @param time_boot_ms [ms] Timestamp (time since system boot).
  122. * @param time_utc [us] Timestamp (time since UNIX epoch) in UTC. 0 for unknown.
  123. * @param camera_id Deprecated/unused. Component IDs are used to differentiate multiple cameras.
  124. * @param lat [degE7] Latitude where image was taken
  125. * @param lon [degE7] Longitude where capture was taken
  126. * @param alt [mm] Altitude (MSL) where image was taken
  127. * @param relative_alt [mm] Altitude above ground
  128. * @param q Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
  129. * @param image_index Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1)
  130. * @param capture_result Boolean indicating success (1) or failure (0) while capturing this image.
  131. * @param file_url URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface.
  132. * @return length of the message in bytes (excluding serial stream start sign)
  133. */
  134. static inline uint16_t mavlink_msg_camera_image_captured_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  135. mavlink_message_t* msg,
  136. uint32_t time_boot_ms,uint64_t time_utc,uint8_t camera_id,int32_t lat,int32_t lon,int32_t alt,int32_t relative_alt,const float *q,int32_t image_index,int8_t capture_result,const char *file_url)
  137. {
  138. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  139. char buf[MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN];
  140. _mav_put_uint64_t(buf, 0, time_utc);
  141. _mav_put_uint32_t(buf, 8, time_boot_ms);
  142. _mav_put_int32_t(buf, 12, lat);
  143. _mav_put_int32_t(buf, 16, lon);
  144. _mav_put_int32_t(buf, 20, alt);
  145. _mav_put_int32_t(buf, 24, relative_alt);
  146. _mav_put_int32_t(buf, 44, image_index);
  147. _mav_put_uint8_t(buf, 48, camera_id);
  148. _mav_put_int8_t(buf, 49, capture_result);
  149. _mav_put_float_array(buf, 28, q, 4);
  150. _mav_put_char_array(buf, 50, file_url, 205);
  151. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN);
  152. #else
  153. mavlink_camera_image_captured_t packet;
  154. packet.time_utc = time_utc;
  155. packet.time_boot_ms = time_boot_ms;
  156. packet.lat = lat;
  157. packet.lon = lon;
  158. packet.alt = alt;
  159. packet.relative_alt = relative_alt;
  160. packet.image_index = image_index;
  161. packet.camera_id = camera_id;
  162. packet.capture_result = capture_result;
  163. mav_array_memcpy(packet.q, q, sizeof(float)*4);
  164. mav_array_memcpy(packet.file_url, file_url, sizeof(char)*205);
  165. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN);
  166. #endif
  167. msg->msgid = MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED;
  168. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC);
  169. }
  170. /**
  171. * @brief Encode a camera_image_captured struct
  172. *
  173. * @param system_id ID of this system
  174. * @param component_id ID of this component (e.g. 200 for IMU)
  175. * @param msg The MAVLink message to compress the data into
  176. * @param camera_image_captured C-struct to read the message contents from
  177. */
  178. static inline uint16_t mavlink_msg_camera_image_captured_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_image_captured_t* camera_image_captured)
  179. {
  180. return mavlink_msg_camera_image_captured_pack(system_id, component_id, msg, camera_image_captured->time_boot_ms, camera_image_captured->time_utc, camera_image_captured->camera_id, camera_image_captured->lat, camera_image_captured->lon, camera_image_captured->alt, camera_image_captured->relative_alt, camera_image_captured->q, camera_image_captured->image_index, camera_image_captured->capture_result, camera_image_captured->file_url);
  181. }
  182. /**
  183. * @brief Encode a camera_image_captured struct on a channel
  184. *
  185. * @param system_id ID of this system
  186. * @param component_id ID of this component (e.g. 200 for IMU)
  187. * @param chan The MAVLink channel this message will be sent over
  188. * @param msg The MAVLink message to compress the data into
  189. * @param camera_image_captured C-struct to read the message contents from
  190. */
  191. static inline uint16_t mavlink_msg_camera_image_captured_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_image_captured_t* camera_image_captured)
  192. {
  193. return mavlink_msg_camera_image_captured_pack_chan(system_id, component_id, chan, msg, camera_image_captured->time_boot_ms, camera_image_captured->time_utc, camera_image_captured->camera_id, camera_image_captured->lat, camera_image_captured->lon, camera_image_captured->alt, camera_image_captured->relative_alt, camera_image_captured->q, camera_image_captured->image_index, camera_image_captured->capture_result, camera_image_captured->file_url);
  194. }
  195. /**
  196. * @brief Send a camera_image_captured message
  197. * @param chan MAVLink channel to send the message
  198. *
  199. * @param time_boot_ms [ms] Timestamp (time since system boot).
  200. * @param time_utc [us] Timestamp (time since UNIX epoch) in UTC. 0 for unknown.
  201. * @param camera_id Deprecated/unused. Component IDs are used to differentiate multiple cameras.
  202. * @param lat [degE7] Latitude where image was taken
  203. * @param lon [degE7] Longitude where capture was taken
  204. * @param alt [mm] Altitude (MSL) where image was taken
  205. * @param relative_alt [mm] Altitude above ground
  206. * @param q Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
  207. * @param image_index Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1)
  208. * @param capture_result Boolean indicating success (1) or failure (0) while capturing this image.
  209. * @param file_url URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface.
  210. */
  211. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  212. static inline void mavlink_msg_camera_image_captured_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t time_utc, uint8_t camera_id, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, const float *q, int32_t image_index, int8_t capture_result, const char *file_url)
  213. {
  214. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  215. char buf[MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN];
  216. _mav_put_uint64_t(buf, 0, time_utc);
  217. _mav_put_uint32_t(buf, 8, time_boot_ms);
  218. _mav_put_int32_t(buf, 12, lat);
  219. _mav_put_int32_t(buf, 16, lon);
  220. _mav_put_int32_t(buf, 20, alt);
  221. _mav_put_int32_t(buf, 24, relative_alt);
  222. _mav_put_int32_t(buf, 44, image_index);
  223. _mav_put_uint8_t(buf, 48, camera_id);
  224. _mav_put_int8_t(buf, 49, capture_result);
  225. _mav_put_float_array(buf, 28, q, 4);
  226. _mav_put_char_array(buf, 50, file_url, 205);
  227. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED, buf, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC);
  228. #else
  229. mavlink_camera_image_captured_t packet;
  230. packet.time_utc = time_utc;
  231. packet.time_boot_ms = time_boot_ms;
  232. packet.lat = lat;
  233. packet.lon = lon;
  234. packet.alt = alt;
  235. packet.relative_alt = relative_alt;
  236. packet.image_index = image_index;
  237. packet.camera_id = camera_id;
  238. packet.capture_result = capture_result;
  239. mav_array_memcpy(packet.q, q, sizeof(float)*4);
  240. mav_array_memcpy(packet.file_url, file_url, sizeof(char)*205);
  241. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC);
  242. #endif
  243. }
  244. /**
  245. * @brief Send a camera_image_captured message
  246. * @param chan MAVLink channel to send the message
  247. * @param struct The MAVLink struct to serialize
  248. */
  249. static inline void mavlink_msg_camera_image_captured_send_struct(mavlink_channel_t chan, const mavlink_camera_image_captured_t* camera_image_captured)
  250. {
  251. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  252. mavlink_msg_camera_image_captured_send(chan, camera_image_captured->time_boot_ms, camera_image_captured->time_utc, camera_image_captured->camera_id, camera_image_captured->lat, camera_image_captured->lon, camera_image_captured->alt, camera_image_captured->relative_alt, camera_image_captured->q, camera_image_captured->image_index, camera_image_captured->capture_result, camera_image_captured->file_url);
  253. #else
  254. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED, (const char *)camera_image_captured, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC);
  255. #endif
  256. }
  257. #if MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  258. /*
  259. This variant of _send() can be used to save stack space by re-using
  260. memory from the receive buffer. The caller provides a
  261. mavlink_message_t which is the size of a full mavlink message. This
  262. is usually the receive buffer for the channel, and allows a reply to an
  263. incoming message with minimum stack space usage.
  264. */
  265. static inline void mavlink_msg_camera_image_captured_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t time_utc, uint8_t camera_id, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, const float *q, int32_t image_index, int8_t capture_result, const char *file_url)
  266. {
  267. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  268. char *buf = (char *)msgbuf;
  269. _mav_put_uint64_t(buf, 0, time_utc);
  270. _mav_put_uint32_t(buf, 8, time_boot_ms);
  271. _mav_put_int32_t(buf, 12, lat);
  272. _mav_put_int32_t(buf, 16, lon);
  273. _mav_put_int32_t(buf, 20, alt);
  274. _mav_put_int32_t(buf, 24, relative_alt);
  275. _mav_put_int32_t(buf, 44, image_index);
  276. _mav_put_uint8_t(buf, 48, camera_id);
  277. _mav_put_int8_t(buf, 49, capture_result);
  278. _mav_put_float_array(buf, 28, q, 4);
  279. _mav_put_char_array(buf, 50, file_url, 205);
  280. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED, buf, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC);
  281. #else
  282. mavlink_camera_image_captured_t *packet = (mavlink_camera_image_captured_t *)msgbuf;
  283. packet->time_utc = time_utc;
  284. packet->time_boot_ms = time_boot_ms;
  285. packet->lat = lat;
  286. packet->lon = lon;
  287. packet->alt = alt;
  288. packet->relative_alt = relative_alt;
  289. packet->image_index = image_index;
  290. packet->camera_id = camera_id;
  291. packet->capture_result = capture_result;
  292. mav_array_memcpy(packet->q, q, sizeof(float)*4);
  293. mav_array_memcpy(packet->file_url, file_url, sizeof(char)*205);
  294. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED, (const char *)packet, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC);
  295. #endif
  296. }
  297. #endif
  298. #endif
  299. // MESSAGE CAMERA_IMAGE_CAPTURED UNPACKING
  300. /**
  301. * @brief Get field time_boot_ms from camera_image_captured message
  302. *
  303. * @return [ms] Timestamp (time since system boot).
  304. */
  305. static inline uint32_t mavlink_msg_camera_image_captured_get_time_boot_ms(const mavlink_message_t* msg)
  306. {
  307. return _MAV_RETURN_uint32_t(msg, 8);
  308. }
  309. /**
  310. * @brief Get field time_utc from camera_image_captured message
  311. *
  312. * @return [us] Timestamp (time since UNIX epoch) in UTC. 0 for unknown.
  313. */
  314. static inline uint64_t mavlink_msg_camera_image_captured_get_time_utc(const mavlink_message_t* msg)
  315. {
  316. return _MAV_RETURN_uint64_t(msg, 0);
  317. }
  318. /**
  319. * @brief Get field camera_id from camera_image_captured message
  320. *
  321. * @return Deprecated/unused. Component IDs are used to differentiate multiple cameras.
  322. */
  323. static inline uint8_t mavlink_msg_camera_image_captured_get_camera_id(const mavlink_message_t* msg)
  324. {
  325. return _MAV_RETURN_uint8_t(msg, 48);
  326. }
  327. /**
  328. * @brief Get field lat from camera_image_captured message
  329. *
  330. * @return [degE7] Latitude where image was taken
  331. */
  332. static inline int32_t mavlink_msg_camera_image_captured_get_lat(const mavlink_message_t* msg)
  333. {
  334. return _MAV_RETURN_int32_t(msg, 12);
  335. }
  336. /**
  337. * @brief Get field lon from camera_image_captured message
  338. *
  339. * @return [degE7] Longitude where capture was taken
  340. */
  341. static inline int32_t mavlink_msg_camera_image_captured_get_lon(const mavlink_message_t* msg)
  342. {
  343. return _MAV_RETURN_int32_t(msg, 16);
  344. }
  345. /**
  346. * @brief Get field alt from camera_image_captured message
  347. *
  348. * @return [mm] Altitude (MSL) where image was taken
  349. */
  350. static inline int32_t mavlink_msg_camera_image_captured_get_alt(const mavlink_message_t* msg)
  351. {
  352. return _MAV_RETURN_int32_t(msg, 20);
  353. }
  354. /**
  355. * @brief Get field relative_alt from camera_image_captured message
  356. *
  357. * @return [mm] Altitude above ground
  358. */
  359. static inline int32_t mavlink_msg_camera_image_captured_get_relative_alt(const mavlink_message_t* msg)
  360. {
  361. return _MAV_RETURN_int32_t(msg, 24);
  362. }
  363. /**
  364. * @brief Get field q from camera_image_captured message
  365. *
  366. * @return Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
  367. */
  368. static inline uint16_t mavlink_msg_camera_image_captured_get_q(const mavlink_message_t* msg, float *q)
  369. {
  370. return _MAV_RETURN_float_array(msg, q, 4, 28);
  371. }
  372. /**
  373. * @brief Get field image_index from camera_image_captured message
  374. *
  375. * @return Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1)
  376. */
  377. static inline int32_t mavlink_msg_camera_image_captured_get_image_index(const mavlink_message_t* msg)
  378. {
  379. return _MAV_RETURN_int32_t(msg, 44);
  380. }
  381. /**
  382. * @brief Get field capture_result from camera_image_captured message
  383. *
  384. * @return Boolean indicating success (1) or failure (0) while capturing this image.
  385. */
  386. static inline int8_t mavlink_msg_camera_image_captured_get_capture_result(const mavlink_message_t* msg)
  387. {
  388. return _MAV_RETURN_int8_t(msg, 49);
  389. }
  390. /**
  391. * @brief Get field file_url from camera_image_captured message
  392. *
  393. * @return URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface.
  394. */
  395. static inline uint16_t mavlink_msg_camera_image_captured_get_file_url(const mavlink_message_t* msg, char *file_url)
  396. {
  397. return _MAV_RETURN_char_array(msg, file_url, 205, 50);
  398. }
  399. /**
  400. * @brief Decode a camera_image_captured message into a struct
  401. *
  402. * @param msg The message to decode
  403. * @param camera_image_captured C-struct to decode the message contents into
  404. */
  405. static inline void mavlink_msg_camera_image_captured_decode(const mavlink_message_t* msg, mavlink_camera_image_captured_t* camera_image_captured)
  406. {
  407. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  408. camera_image_captured->time_utc = mavlink_msg_camera_image_captured_get_time_utc(msg);
  409. camera_image_captured->time_boot_ms = mavlink_msg_camera_image_captured_get_time_boot_ms(msg);
  410. camera_image_captured->lat = mavlink_msg_camera_image_captured_get_lat(msg);
  411. camera_image_captured->lon = mavlink_msg_camera_image_captured_get_lon(msg);
  412. camera_image_captured->alt = mavlink_msg_camera_image_captured_get_alt(msg);
  413. camera_image_captured->relative_alt = mavlink_msg_camera_image_captured_get_relative_alt(msg);
  414. mavlink_msg_camera_image_captured_get_q(msg, camera_image_captured->q);
  415. camera_image_captured->image_index = mavlink_msg_camera_image_captured_get_image_index(msg);
  416. camera_image_captured->camera_id = mavlink_msg_camera_image_captured_get_camera_id(msg);
  417. camera_image_captured->capture_result = mavlink_msg_camera_image_captured_get_capture_result(msg);
  418. mavlink_msg_camera_image_captured_get_file_url(msg, camera_image_captured->file_url);
  419. #else
  420. uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN;
  421. memset(camera_image_captured, 0, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN);
  422. memcpy(camera_image_captured, _MAV_PAYLOAD(msg), len);
  423. #endif
  424. }