mavlink_msg_camera_image_captured.h 27 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531
  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
  117. * @param system_id ID of this system
  118. * @param component_id ID of this component (e.g. 200 for IMU)
  119. * @param status MAVLink status structure
  120. * @param msg The MAVLink message to compress the data into
  121. *
  122. * @param time_boot_ms [ms] Timestamp (time since system boot).
  123. * @param time_utc [us] Timestamp (time since UNIX epoch) in UTC. 0 for unknown.
  124. * @param camera_id Deprecated/unused. Component IDs are used to differentiate multiple cameras.
  125. * @param lat [degE7] Latitude where image was taken
  126. * @param lon [degE7] Longitude where capture was taken
  127. * @param alt [mm] Altitude (MSL) where image was taken
  128. * @param relative_alt [mm] Altitude above ground
  129. * @param q Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
  130. * @param image_index Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1)
  131. * @param capture_result Boolean indicating success (1) or failure (0) while capturing this image.
  132. * @param file_url URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface.
  133. * @return length of the message in bytes (excluding serial stream start sign)
  134. */
  135. static inline uint16_t mavlink_msg_camera_image_captured_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, 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. #if MAVLINK_CRC_EXTRA
  169. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC);
  170. #else
  171. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN);
  172. #endif
  173. }
  174. /**
  175. * @brief Pack a camera_image_captured message on a channel
  176. * @param system_id ID of this system
  177. * @param component_id ID of this component (e.g. 200 for IMU)
  178. * @param chan The MAVLink channel this message will be sent over
  179. * @param msg The MAVLink message to compress the data into
  180. * @param time_boot_ms [ms] Timestamp (time since system boot).
  181. * @param time_utc [us] Timestamp (time since UNIX epoch) in UTC. 0 for unknown.
  182. * @param camera_id Deprecated/unused. Component IDs are used to differentiate multiple cameras.
  183. * @param lat [degE7] Latitude where image was taken
  184. * @param lon [degE7] Longitude where capture was taken
  185. * @param alt [mm] Altitude (MSL) where image was taken
  186. * @param relative_alt [mm] Altitude above ground
  187. * @param q Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
  188. * @param image_index Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1)
  189. * @param capture_result Boolean indicating success (1) or failure (0) while capturing this image.
  190. * @param file_url URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface.
  191. * @return length of the message in bytes (excluding serial stream start sign)
  192. */
  193. static inline uint16_t mavlink_msg_camera_image_captured_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  194. mavlink_message_t* msg,
  195. 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)
  196. {
  197. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  198. char buf[MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN];
  199. _mav_put_uint64_t(buf, 0, time_utc);
  200. _mav_put_uint32_t(buf, 8, time_boot_ms);
  201. _mav_put_int32_t(buf, 12, lat);
  202. _mav_put_int32_t(buf, 16, lon);
  203. _mav_put_int32_t(buf, 20, alt);
  204. _mav_put_int32_t(buf, 24, relative_alt);
  205. _mav_put_int32_t(buf, 44, image_index);
  206. _mav_put_uint8_t(buf, 48, camera_id);
  207. _mav_put_int8_t(buf, 49, capture_result);
  208. _mav_put_float_array(buf, 28, q, 4);
  209. _mav_put_char_array(buf, 50, file_url, 205);
  210. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN);
  211. #else
  212. mavlink_camera_image_captured_t packet;
  213. packet.time_utc = time_utc;
  214. packet.time_boot_ms = time_boot_ms;
  215. packet.lat = lat;
  216. packet.lon = lon;
  217. packet.alt = alt;
  218. packet.relative_alt = relative_alt;
  219. packet.image_index = image_index;
  220. packet.camera_id = camera_id;
  221. packet.capture_result = capture_result;
  222. mav_array_memcpy(packet.q, q, sizeof(float)*4);
  223. mav_array_memcpy(packet.file_url, file_url, sizeof(char)*205);
  224. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN);
  225. #endif
  226. msg->msgid = MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED;
  227. 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);
  228. }
  229. /**
  230. * @brief Encode a camera_image_captured struct
  231. *
  232. * @param system_id ID of this system
  233. * @param component_id ID of this component (e.g. 200 for IMU)
  234. * @param msg The MAVLink message to compress the data into
  235. * @param camera_image_captured C-struct to read the message contents from
  236. */
  237. 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)
  238. {
  239. 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);
  240. }
  241. /**
  242. * @brief Encode a camera_image_captured struct on a channel
  243. *
  244. * @param system_id ID of this system
  245. * @param component_id ID of this component (e.g. 200 for IMU)
  246. * @param chan The MAVLink channel this message will be sent over
  247. * @param msg The MAVLink message to compress the data into
  248. * @param camera_image_captured C-struct to read the message contents from
  249. */
  250. 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)
  251. {
  252. 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);
  253. }
  254. /**
  255. * @brief Encode a camera_image_captured struct with provided status structure
  256. *
  257. * @param system_id ID of this system
  258. * @param component_id ID of this component (e.g. 200 for IMU)
  259. * @param status MAVLink status structure
  260. * @param msg The MAVLink message to compress the data into
  261. * @param camera_image_captured C-struct to read the message contents from
  262. */
  263. static inline uint16_t mavlink_msg_camera_image_captured_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_camera_image_captured_t* camera_image_captured)
  264. {
  265. return mavlink_msg_camera_image_captured_pack_status(system_id, component_id, _status, 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);
  266. }
  267. /**
  268. * @brief Send a camera_image_captured message
  269. * @param chan MAVLink channel to send the message
  270. *
  271. * @param time_boot_ms [ms] Timestamp (time since system boot).
  272. * @param time_utc [us] Timestamp (time since UNIX epoch) in UTC. 0 for unknown.
  273. * @param camera_id Deprecated/unused. Component IDs are used to differentiate multiple cameras.
  274. * @param lat [degE7] Latitude where image was taken
  275. * @param lon [degE7] Longitude where capture was taken
  276. * @param alt [mm] Altitude (MSL) where image was taken
  277. * @param relative_alt [mm] Altitude above ground
  278. * @param q Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
  279. * @param image_index Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1)
  280. * @param capture_result Boolean indicating success (1) or failure (0) while capturing this image.
  281. * @param file_url URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface.
  282. */
  283. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  284. 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)
  285. {
  286. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  287. char buf[MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN];
  288. _mav_put_uint64_t(buf, 0, time_utc);
  289. _mav_put_uint32_t(buf, 8, time_boot_ms);
  290. _mav_put_int32_t(buf, 12, lat);
  291. _mav_put_int32_t(buf, 16, lon);
  292. _mav_put_int32_t(buf, 20, alt);
  293. _mav_put_int32_t(buf, 24, relative_alt);
  294. _mav_put_int32_t(buf, 44, image_index);
  295. _mav_put_uint8_t(buf, 48, camera_id);
  296. _mav_put_int8_t(buf, 49, capture_result);
  297. _mav_put_float_array(buf, 28, q, 4);
  298. _mav_put_char_array(buf, 50, file_url, 205);
  299. _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);
  300. #else
  301. mavlink_camera_image_captured_t packet;
  302. packet.time_utc = time_utc;
  303. packet.time_boot_ms = time_boot_ms;
  304. packet.lat = lat;
  305. packet.lon = lon;
  306. packet.alt = alt;
  307. packet.relative_alt = relative_alt;
  308. packet.image_index = image_index;
  309. packet.camera_id = camera_id;
  310. packet.capture_result = capture_result;
  311. mav_array_memcpy(packet.q, q, sizeof(float)*4);
  312. mav_array_memcpy(packet.file_url, file_url, sizeof(char)*205);
  313. _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);
  314. #endif
  315. }
  316. /**
  317. * @brief Send a camera_image_captured message
  318. * @param chan MAVLink channel to send the message
  319. * @param struct The MAVLink struct to serialize
  320. */
  321. static inline void mavlink_msg_camera_image_captured_send_struct(mavlink_channel_t chan, const mavlink_camera_image_captured_t* camera_image_captured)
  322. {
  323. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  324. 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);
  325. #else
  326. _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);
  327. #endif
  328. }
  329. #if MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  330. /*
  331. This variant of _send() can be used to save stack space by re-using
  332. memory from the receive buffer. The caller provides a
  333. mavlink_message_t which is the size of a full mavlink message. This
  334. is usually the receive buffer for the channel, and allows a reply to an
  335. incoming message with minimum stack space usage.
  336. */
  337. 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)
  338. {
  339. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  340. char *buf = (char *)msgbuf;
  341. _mav_put_uint64_t(buf, 0, time_utc);
  342. _mav_put_uint32_t(buf, 8, time_boot_ms);
  343. _mav_put_int32_t(buf, 12, lat);
  344. _mav_put_int32_t(buf, 16, lon);
  345. _mav_put_int32_t(buf, 20, alt);
  346. _mav_put_int32_t(buf, 24, relative_alt);
  347. _mav_put_int32_t(buf, 44, image_index);
  348. _mav_put_uint8_t(buf, 48, camera_id);
  349. _mav_put_int8_t(buf, 49, capture_result);
  350. _mav_put_float_array(buf, 28, q, 4);
  351. _mav_put_char_array(buf, 50, file_url, 205);
  352. _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);
  353. #else
  354. mavlink_camera_image_captured_t *packet = (mavlink_camera_image_captured_t *)msgbuf;
  355. packet->time_utc = time_utc;
  356. packet->time_boot_ms = time_boot_ms;
  357. packet->lat = lat;
  358. packet->lon = lon;
  359. packet->alt = alt;
  360. packet->relative_alt = relative_alt;
  361. packet->image_index = image_index;
  362. packet->camera_id = camera_id;
  363. packet->capture_result = capture_result;
  364. mav_array_memcpy(packet->q, q, sizeof(float)*4);
  365. mav_array_memcpy(packet->file_url, file_url, sizeof(char)*205);
  366. _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);
  367. #endif
  368. }
  369. #endif
  370. #endif
  371. // MESSAGE CAMERA_IMAGE_CAPTURED UNPACKING
  372. /**
  373. * @brief Get field time_boot_ms from camera_image_captured message
  374. *
  375. * @return [ms] Timestamp (time since system boot).
  376. */
  377. static inline uint32_t mavlink_msg_camera_image_captured_get_time_boot_ms(const mavlink_message_t* msg)
  378. {
  379. return _MAV_RETURN_uint32_t(msg, 8);
  380. }
  381. /**
  382. * @brief Get field time_utc from camera_image_captured message
  383. *
  384. * @return [us] Timestamp (time since UNIX epoch) in UTC. 0 for unknown.
  385. */
  386. static inline uint64_t mavlink_msg_camera_image_captured_get_time_utc(const mavlink_message_t* msg)
  387. {
  388. return _MAV_RETURN_uint64_t(msg, 0);
  389. }
  390. /**
  391. * @brief Get field camera_id from camera_image_captured message
  392. *
  393. * @return Deprecated/unused. Component IDs are used to differentiate multiple cameras.
  394. */
  395. static inline uint8_t mavlink_msg_camera_image_captured_get_camera_id(const mavlink_message_t* msg)
  396. {
  397. return _MAV_RETURN_uint8_t(msg, 48);
  398. }
  399. /**
  400. * @brief Get field lat from camera_image_captured message
  401. *
  402. * @return [degE7] Latitude where image was taken
  403. */
  404. static inline int32_t mavlink_msg_camera_image_captured_get_lat(const mavlink_message_t* msg)
  405. {
  406. return _MAV_RETURN_int32_t(msg, 12);
  407. }
  408. /**
  409. * @brief Get field lon from camera_image_captured message
  410. *
  411. * @return [degE7] Longitude where capture was taken
  412. */
  413. static inline int32_t mavlink_msg_camera_image_captured_get_lon(const mavlink_message_t* msg)
  414. {
  415. return _MAV_RETURN_int32_t(msg, 16);
  416. }
  417. /**
  418. * @brief Get field alt from camera_image_captured message
  419. *
  420. * @return [mm] Altitude (MSL) where image was taken
  421. */
  422. static inline int32_t mavlink_msg_camera_image_captured_get_alt(const mavlink_message_t* msg)
  423. {
  424. return _MAV_RETURN_int32_t(msg, 20);
  425. }
  426. /**
  427. * @brief Get field relative_alt from camera_image_captured message
  428. *
  429. * @return [mm] Altitude above ground
  430. */
  431. static inline int32_t mavlink_msg_camera_image_captured_get_relative_alt(const mavlink_message_t* msg)
  432. {
  433. return _MAV_RETURN_int32_t(msg, 24);
  434. }
  435. /**
  436. * @brief Get field q from camera_image_captured message
  437. *
  438. * @return Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
  439. */
  440. static inline uint16_t mavlink_msg_camera_image_captured_get_q(const mavlink_message_t* msg, float *q)
  441. {
  442. return _MAV_RETURN_float_array(msg, q, 4, 28);
  443. }
  444. /**
  445. * @brief Get field image_index from camera_image_captured message
  446. *
  447. * @return Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1)
  448. */
  449. static inline int32_t mavlink_msg_camera_image_captured_get_image_index(const mavlink_message_t* msg)
  450. {
  451. return _MAV_RETURN_int32_t(msg, 44);
  452. }
  453. /**
  454. * @brief Get field capture_result from camera_image_captured message
  455. *
  456. * @return Boolean indicating success (1) or failure (0) while capturing this image.
  457. */
  458. static inline int8_t mavlink_msg_camera_image_captured_get_capture_result(const mavlink_message_t* msg)
  459. {
  460. return _MAV_RETURN_int8_t(msg, 49);
  461. }
  462. /**
  463. * @brief Get field file_url from camera_image_captured message
  464. *
  465. * @return URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface.
  466. */
  467. static inline uint16_t mavlink_msg_camera_image_captured_get_file_url(const mavlink_message_t* msg, char *file_url)
  468. {
  469. return _MAV_RETURN_char_array(msg, file_url, 205, 50);
  470. }
  471. /**
  472. * @brief Decode a camera_image_captured message into a struct
  473. *
  474. * @param msg The message to decode
  475. * @param camera_image_captured C-struct to decode the message contents into
  476. */
  477. static inline void mavlink_msg_camera_image_captured_decode(const mavlink_message_t* msg, mavlink_camera_image_captured_t* camera_image_captured)
  478. {
  479. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  480. camera_image_captured->time_utc = mavlink_msg_camera_image_captured_get_time_utc(msg);
  481. camera_image_captured->time_boot_ms = mavlink_msg_camera_image_captured_get_time_boot_ms(msg);
  482. camera_image_captured->lat = mavlink_msg_camera_image_captured_get_lat(msg);
  483. camera_image_captured->lon = mavlink_msg_camera_image_captured_get_lon(msg);
  484. camera_image_captured->alt = mavlink_msg_camera_image_captured_get_alt(msg);
  485. camera_image_captured->relative_alt = mavlink_msg_camera_image_captured_get_relative_alt(msg);
  486. mavlink_msg_camera_image_captured_get_q(msg, camera_image_captured->q);
  487. camera_image_captured->image_index = mavlink_msg_camera_image_captured_get_image_index(msg);
  488. camera_image_captured->camera_id = mavlink_msg_camera_image_captured_get_camera_id(msg);
  489. camera_image_captured->capture_result = mavlink_msg_camera_image_captured_get_capture_result(msg);
  490. mavlink_msg_camera_image_captured_get_file_url(msg, camera_image_captured->file_url);
  491. #else
  492. uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN;
  493. memset(camera_image_captured, 0, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN);
  494. memcpy(camera_image_captured, _MAV_PAYLOAD(msg), len);
  495. #endif
  496. }