2
0

mavlink_msg_ais_vessel.h 31 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699
  1. #pragma once
  2. // MESSAGE AIS_VESSEL PACKING
  3. #define MAVLINK_MSG_ID_AIS_VESSEL 301
  4. typedef struct __mavlink_ais_vessel_t {
  5. uint32_t MMSI; /*< Mobile Marine Service Identifier, 9 decimal digits*/
  6. int32_t lat; /*< [degE7] Latitude*/
  7. int32_t lon; /*< [degE7] Longitude*/
  8. uint16_t COG; /*< [cdeg] Course over ground*/
  9. uint16_t heading; /*< [cdeg] True heading*/
  10. uint16_t velocity; /*< [cm/s] Speed over ground*/
  11. uint16_t dimension_bow; /*< [m] Distance from lat/lon location to bow*/
  12. uint16_t dimension_stern; /*< [m] Distance from lat/lon location to stern*/
  13. uint16_t tslc; /*< [s] Time since last communication in seconds*/
  14. uint16_t flags; /*< Bitmask to indicate various statuses including valid data fields*/
  15. int8_t turn_rate; /*< [cdeg/s] Turn rate*/
  16. uint8_t navigational_status; /*< Navigational status*/
  17. uint8_t type; /*< Type of vessels*/
  18. uint8_t dimension_port; /*< [m] Distance from lat/lon location to port side*/
  19. uint8_t dimension_starboard; /*< [m] Distance from lat/lon location to starboard side*/
  20. char callsign[7]; /*< The vessel callsign*/
  21. char name[20]; /*< The vessel name*/
  22. } mavlink_ais_vessel_t;
  23. #define MAVLINK_MSG_ID_AIS_VESSEL_LEN 58
  24. #define MAVLINK_MSG_ID_AIS_VESSEL_MIN_LEN 58
  25. #define MAVLINK_MSG_ID_301_LEN 58
  26. #define MAVLINK_MSG_ID_301_MIN_LEN 58
  27. #define MAVLINK_MSG_ID_AIS_VESSEL_CRC 243
  28. #define MAVLINK_MSG_ID_301_CRC 243
  29. #define MAVLINK_MSG_AIS_VESSEL_FIELD_CALLSIGN_LEN 7
  30. #define MAVLINK_MSG_AIS_VESSEL_FIELD_NAME_LEN 20
  31. #if MAVLINK_COMMAND_24BIT
  32. #define MAVLINK_MESSAGE_INFO_AIS_VESSEL { \
  33. 301, \
  34. "AIS_VESSEL", \
  35. 17, \
  36. { { "MMSI", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_ais_vessel_t, MMSI) }, \
  37. { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_ais_vessel_t, lat) }, \
  38. { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_ais_vessel_t, lon) }, \
  39. { "COG", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_ais_vessel_t, COG) }, \
  40. { "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_ais_vessel_t, heading) }, \
  41. { "velocity", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_ais_vessel_t, velocity) }, \
  42. { "turn_rate", NULL, MAVLINK_TYPE_INT8_T, 0, 26, offsetof(mavlink_ais_vessel_t, turn_rate) }, \
  43. { "navigational_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_ais_vessel_t, navigational_status) }, \
  44. { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_ais_vessel_t, type) }, \
  45. { "dimension_bow", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_ais_vessel_t, dimension_bow) }, \
  46. { "dimension_stern", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_ais_vessel_t, dimension_stern) }, \
  47. { "dimension_port", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_ais_vessel_t, dimension_port) }, \
  48. { "dimension_starboard", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_ais_vessel_t, dimension_starboard) }, \
  49. { "callsign", NULL, MAVLINK_TYPE_CHAR, 7, 31, offsetof(mavlink_ais_vessel_t, callsign) }, \
  50. { "name", NULL, MAVLINK_TYPE_CHAR, 20, 38, offsetof(mavlink_ais_vessel_t, name) }, \
  51. { "tslc", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_ais_vessel_t, tslc) }, \
  52. { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_ais_vessel_t, flags) }, \
  53. } \
  54. }
  55. #else
  56. #define MAVLINK_MESSAGE_INFO_AIS_VESSEL { \
  57. "AIS_VESSEL", \
  58. 17, \
  59. { { "MMSI", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_ais_vessel_t, MMSI) }, \
  60. { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_ais_vessel_t, lat) }, \
  61. { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_ais_vessel_t, lon) }, \
  62. { "COG", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_ais_vessel_t, COG) }, \
  63. { "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_ais_vessel_t, heading) }, \
  64. { "velocity", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_ais_vessel_t, velocity) }, \
  65. { "turn_rate", NULL, MAVLINK_TYPE_INT8_T, 0, 26, offsetof(mavlink_ais_vessel_t, turn_rate) }, \
  66. { "navigational_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_ais_vessel_t, navigational_status) }, \
  67. { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_ais_vessel_t, type) }, \
  68. { "dimension_bow", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_ais_vessel_t, dimension_bow) }, \
  69. { "dimension_stern", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_ais_vessel_t, dimension_stern) }, \
  70. { "dimension_port", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_ais_vessel_t, dimension_port) }, \
  71. { "dimension_starboard", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_ais_vessel_t, dimension_starboard) }, \
  72. { "callsign", NULL, MAVLINK_TYPE_CHAR, 7, 31, offsetof(mavlink_ais_vessel_t, callsign) }, \
  73. { "name", NULL, MAVLINK_TYPE_CHAR, 20, 38, offsetof(mavlink_ais_vessel_t, name) }, \
  74. { "tslc", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_ais_vessel_t, tslc) }, \
  75. { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_ais_vessel_t, flags) }, \
  76. } \
  77. }
  78. #endif
  79. /**
  80. * @brief Pack a ais_vessel message
  81. * @param system_id ID of this system
  82. * @param component_id ID of this component (e.g. 200 for IMU)
  83. * @param msg The MAVLink message to compress the data into
  84. *
  85. * @param MMSI Mobile Marine Service Identifier, 9 decimal digits
  86. * @param lat [degE7] Latitude
  87. * @param lon [degE7] Longitude
  88. * @param COG [cdeg] Course over ground
  89. * @param heading [cdeg] True heading
  90. * @param velocity [cm/s] Speed over ground
  91. * @param turn_rate [cdeg/s] Turn rate
  92. * @param navigational_status Navigational status
  93. * @param type Type of vessels
  94. * @param dimension_bow [m] Distance from lat/lon location to bow
  95. * @param dimension_stern [m] Distance from lat/lon location to stern
  96. * @param dimension_port [m] Distance from lat/lon location to port side
  97. * @param dimension_starboard [m] Distance from lat/lon location to starboard side
  98. * @param callsign The vessel callsign
  99. * @param name The vessel name
  100. * @param tslc [s] Time since last communication in seconds
  101. * @param flags Bitmask to indicate various statuses including valid data fields
  102. * @return length of the message in bytes (excluding serial stream start sign)
  103. */
  104. static inline uint16_t mavlink_msg_ais_vessel_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  105. uint32_t MMSI, int32_t lat, int32_t lon, uint16_t COG, uint16_t heading, uint16_t velocity, int8_t turn_rate, uint8_t navigational_status, uint8_t type, uint16_t dimension_bow, uint16_t dimension_stern, uint8_t dimension_port, uint8_t dimension_starboard, const char *callsign, const char *name, uint16_t tslc, uint16_t flags)
  106. {
  107. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  108. char buf[MAVLINK_MSG_ID_AIS_VESSEL_LEN];
  109. _mav_put_uint32_t(buf, 0, MMSI);
  110. _mav_put_int32_t(buf, 4, lat);
  111. _mav_put_int32_t(buf, 8, lon);
  112. _mav_put_uint16_t(buf, 12, COG);
  113. _mav_put_uint16_t(buf, 14, heading);
  114. _mav_put_uint16_t(buf, 16, velocity);
  115. _mav_put_uint16_t(buf, 18, dimension_bow);
  116. _mav_put_uint16_t(buf, 20, dimension_stern);
  117. _mav_put_uint16_t(buf, 22, tslc);
  118. _mav_put_uint16_t(buf, 24, flags);
  119. _mav_put_int8_t(buf, 26, turn_rate);
  120. _mav_put_uint8_t(buf, 27, navigational_status);
  121. _mav_put_uint8_t(buf, 28, type);
  122. _mav_put_uint8_t(buf, 29, dimension_port);
  123. _mav_put_uint8_t(buf, 30, dimension_starboard);
  124. _mav_put_char_array(buf, 31, callsign, 7);
  125. _mav_put_char_array(buf, 38, name, 20);
  126. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AIS_VESSEL_LEN);
  127. #else
  128. mavlink_ais_vessel_t packet;
  129. packet.MMSI = MMSI;
  130. packet.lat = lat;
  131. packet.lon = lon;
  132. packet.COG = COG;
  133. packet.heading = heading;
  134. packet.velocity = velocity;
  135. packet.dimension_bow = dimension_bow;
  136. packet.dimension_stern = dimension_stern;
  137. packet.tslc = tslc;
  138. packet.flags = flags;
  139. packet.turn_rate = turn_rate;
  140. packet.navigational_status = navigational_status;
  141. packet.type = type;
  142. packet.dimension_port = dimension_port;
  143. packet.dimension_starboard = dimension_starboard;
  144. mav_array_memcpy(packet.callsign, callsign, sizeof(char)*7);
  145. mav_array_memcpy(packet.name, name, sizeof(char)*20);
  146. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AIS_VESSEL_LEN);
  147. #endif
  148. msg->msgid = MAVLINK_MSG_ID_AIS_VESSEL;
  149. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AIS_VESSEL_MIN_LEN, MAVLINK_MSG_ID_AIS_VESSEL_LEN, MAVLINK_MSG_ID_AIS_VESSEL_CRC);
  150. }
  151. /**
  152. * @brief Pack a ais_vessel message
  153. * @param system_id ID of this system
  154. * @param component_id ID of this component (e.g. 200 for IMU)
  155. * @param status MAVLink status structure
  156. * @param msg The MAVLink message to compress the data into
  157. *
  158. * @param MMSI Mobile Marine Service Identifier, 9 decimal digits
  159. * @param lat [degE7] Latitude
  160. * @param lon [degE7] Longitude
  161. * @param COG [cdeg] Course over ground
  162. * @param heading [cdeg] True heading
  163. * @param velocity [cm/s] Speed over ground
  164. * @param turn_rate [cdeg/s] Turn rate
  165. * @param navigational_status Navigational status
  166. * @param type Type of vessels
  167. * @param dimension_bow [m] Distance from lat/lon location to bow
  168. * @param dimension_stern [m] Distance from lat/lon location to stern
  169. * @param dimension_port [m] Distance from lat/lon location to port side
  170. * @param dimension_starboard [m] Distance from lat/lon location to starboard side
  171. * @param callsign The vessel callsign
  172. * @param name The vessel name
  173. * @param tslc [s] Time since last communication in seconds
  174. * @param flags Bitmask to indicate various statuses including valid data fields
  175. * @return length of the message in bytes (excluding serial stream start sign)
  176. */
  177. static inline uint16_t mavlink_msg_ais_vessel_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
  178. uint32_t MMSI, int32_t lat, int32_t lon, uint16_t COG, uint16_t heading, uint16_t velocity, int8_t turn_rate, uint8_t navigational_status, uint8_t type, uint16_t dimension_bow, uint16_t dimension_stern, uint8_t dimension_port, uint8_t dimension_starboard, const char *callsign, const char *name, uint16_t tslc, uint16_t flags)
  179. {
  180. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  181. char buf[MAVLINK_MSG_ID_AIS_VESSEL_LEN];
  182. _mav_put_uint32_t(buf, 0, MMSI);
  183. _mav_put_int32_t(buf, 4, lat);
  184. _mav_put_int32_t(buf, 8, lon);
  185. _mav_put_uint16_t(buf, 12, COG);
  186. _mav_put_uint16_t(buf, 14, heading);
  187. _mav_put_uint16_t(buf, 16, velocity);
  188. _mav_put_uint16_t(buf, 18, dimension_bow);
  189. _mav_put_uint16_t(buf, 20, dimension_stern);
  190. _mav_put_uint16_t(buf, 22, tslc);
  191. _mav_put_uint16_t(buf, 24, flags);
  192. _mav_put_int8_t(buf, 26, turn_rate);
  193. _mav_put_uint8_t(buf, 27, navigational_status);
  194. _mav_put_uint8_t(buf, 28, type);
  195. _mav_put_uint8_t(buf, 29, dimension_port);
  196. _mav_put_uint8_t(buf, 30, dimension_starboard);
  197. _mav_put_char_array(buf, 31, callsign, 7);
  198. _mav_put_char_array(buf, 38, name, 20);
  199. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AIS_VESSEL_LEN);
  200. #else
  201. mavlink_ais_vessel_t packet;
  202. packet.MMSI = MMSI;
  203. packet.lat = lat;
  204. packet.lon = lon;
  205. packet.COG = COG;
  206. packet.heading = heading;
  207. packet.velocity = velocity;
  208. packet.dimension_bow = dimension_bow;
  209. packet.dimension_stern = dimension_stern;
  210. packet.tslc = tslc;
  211. packet.flags = flags;
  212. packet.turn_rate = turn_rate;
  213. packet.navigational_status = navigational_status;
  214. packet.type = type;
  215. packet.dimension_port = dimension_port;
  216. packet.dimension_starboard = dimension_starboard;
  217. mav_array_memcpy(packet.callsign, callsign, sizeof(char)*7);
  218. mav_array_memcpy(packet.name, name, sizeof(char)*20);
  219. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AIS_VESSEL_LEN);
  220. #endif
  221. msg->msgid = MAVLINK_MSG_ID_AIS_VESSEL;
  222. #if MAVLINK_CRC_EXTRA
  223. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_AIS_VESSEL_MIN_LEN, MAVLINK_MSG_ID_AIS_VESSEL_LEN, MAVLINK_MSG_ID_AIS_VESSEL_CRC);
  224. #else
  225. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_AIS_VESSEL_MIN_LEN, MAVLINK_MSG_ID_AIS_VESSEL_LEN);
  226. #endif
  227. }
  228. /**
  229. * @brief Pack a ais_vessel message on a channel
  230. * @param system_id ID of this system
  231. * @param component_id ID of this component (e.g. 200 for IMU)
  232. * @param chan The MAVLink channel this message will be sent over
  233. * @param msg The MAVLink message to compress the data into
  234. * @param MMSI Mobile Marine Service Identifier, 9 decimal digits
  235. * @param lat [degE7] Latitude
  236. * @param lon [degE7] Longitude
  237. * @param COG [cdeg] Course over ground
  238. * @param heading [cdeg] True heading
  239. * @param velocity [cm/s] Speed over ground
  240. * @param turn_rate [cdeg/s] Turn rate
  241. * @param navigational_status Navigational status
  242. * @param type Type of vessels
  243. * @param dimension_bow [m] Distance from lat/lon location to bow
  244. * @param dimension_stern [m] Distance from lat/lon location to stern
  245. * @param dimension_port [m] Distance from lat/lon location to port side
  246. * @param dimension_starboard [m] Distance from lat/lon location to starboard side
  247. * @param callsign The vessel callsign
  248. * @param name The vessel name
  249. * @param tslc [s] Time since last communication in seconds
  250. * @param flags Bitmask to indicate various statuses including valid data fields
  251. * @return length of the message in bytes (excluding serial stream start sign)
  252. */
  253. static inline uint16_t mavlink_msg_ais_vessel_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  254. mavlink_message_t* msg,
  255. uint32_t MMSI,int32_t lat,int32_t lon,uint16_t COG,uint16_t heading,uint16_t velocity,int8_t turn_rate,uint8_t navigational_status,uint8_t type,uint16_t dimension_bow,uint16_t dimension_stern,uint8_t dimension_port,uint8_t dimension_starboard,const char *callsign,const char *name,uint16_t tslc,uint16_t flags)
  256. {
  257. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  258. char buf[MAVLINK_MSG_ID_AIS_VESSEL_LEN];
  259. _mav_put_uint32_t(buf, 0, MMSI);
  260. _mav_put_int32_t(buf, 4, lat);
  261. _mav_put_int32_t(buf, 8, lon);
  262. _mav_put_uint16_t(buf, 12, COG);
  263. _mav_put_uint16_t(buf, 14, heading);
  264. _mav_put_uint16_t(buf, 16, velocity);
  265. _mav_put_uint16_t(buf, 18, dimension_bow);
  266. _mav_put_uint16_t(buf, 20, dimension_stern);
  267. _mav_put_uint16_t(buf, 22, tslc);
  268. _mav_put_uint16_t(buf, 24, flags);
  269. _mav_put_int8_t(buf, 26, turn_rate);
  270. _mav_put_uint8_t(buf, 27, navigational_status);
  271. _mav_put_uint8_t(buf, 28, type);
  272. _mav_put_uint8_t(buf, 29, dimension_port);
  273. _mav_put_uint8_t(buf, 30, dimension_starboard);
  274. _mav_put_char_array(buf, 31, callsign, 7);
  275. _mav_put_char_array(buf, 38, name, 20);
  276. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AIS_VESSEL_LEN);
  277. #else
  278. mavlink_ais_vessel_t packet;
  279. packet.MMSI = MMSI;
  280. packet.lat = lat;
  281. packet.lon = lon;
  282. packet.COG = COG;
  283. packet.heading = heading;
  284. packet.velocity = velocity;
  285. packet.dimension_bow = dimension_bow;
  286. packet.dimension_stern = dimension_stern;
  287. packet.tslc = tslc;
  288. packet.flags = flags;
  289. packet.turn_rate = turn_rate;
  290. packet.navigational_status = navigational_status;
  291. packet.type = type;
  292. packet.dimension_port = dimension_port;
  293. packet.dimension_starboard = dimension_starboard;
  294. mav_array_memcpy(packet.callsign, callsign, sizeof(char)*7);
  295. mav_array_memcpy(packet.name, name, sizeof(char)*20);
  296. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AIS_VESSEL_LEN);
  297. #endif
  298. msg->msgid = MAVLINK_MSG_ID_AIS_VESSEL;
  299. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AIS_VESSEL_MIN_LEN, MAVLINK_MSG_ID_AIS_VESSEL_LEN, MAVLINK_MSG_ID_AIS_VESSEL_CRC);
  300. }
  301. /**
  302. * @brief Encode a ais_vessel struct
  303. *
  304. * @param system_id ID of this system
  305. * @param component_id ID of this component (e.g. 200 for IMU)
  306. * @param msg The MAVLink message to compress the data into
  307. * @param ais_vessel C-struct to read the message contents from
  308. */
  309. static inline uint16_t mavlink_msg_ais_vessel_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ais_vessel_t* ais_vessel)
  310. {
  311. return mavlink_msg_ais_vessel_pack(system_id, component_id, msg, ais_vessel->MMSI, ais_vessel->lat, ais_vessel->lon, ais_vessel->COG, ais_vessel->heading, ais_vessel->velocity, ais_vessel->turn_rate, ais_vessel->navigational_status, ais_vessel->type, ais_vessel->dimension_bow, ais_vessel->dimension_stern, ais_vessel->dimension_port, ais_vessel->dimension_starboard, ais_vessel->callsign, ais_vessel->name, ais_vessel->tslc, ais_vessel->flags);
  312. }
  313. /**
  314. * @brief Encode a ais_vessel struct on a channel
  315. *
  316. * @param system_id ID of this system
  317. * @param component_id ID of this component (e.g. 200 for IMU)
  318. * @param chan The MAVLink channel this message will be sent over
  319. * @param msg The MAVLink message to compress the data into
  320. * @param ais_vessel C-struct to read the message contents from
  321. */
  322. static inline uint16_t mavlink_msg_ais_vessel_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ais_vessel_t* ais_vessel)
  323. {
  324. return mavlink_msg_ais_vessel_pack_chan(system_id, component_id, chan, msg, ais_vessel->MMSI, ais_vessel->lat, ais_vessel->lon, ais_vessel->COG, ais_vessel->heading, ais_vessel->velocity, ais_vessel->turn_rate, ais_vessel->navigational_status, ais_vessel->type, ais_vessel->dimension_bow, ais_vessel->dimension_stern, ais_vessel->dimension_port, ais_vessel->dimension_starboard, ais_vessel->callsign, ais_vessel->name, ais_vessel->tslc, ais_vessel->flags);
  325. }
  326. /**
  327. * @brief Encode a ais_vessel struct with provided status structure
  328. *
  329. * @param system_id ID of this system
  330. * @param component_id ID of this component (e.g. 200 for IMU)
  331. * @param status MAVLink status structure
  332. * @param msg The MAVLink message to compress the data into
  333. * @param ais_vessel C-struct to read the message contents from
  334. */
  335. static inline uint16_t mavlink_msg_ais_vessel_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_ais_vessel_t* ais_vessel)
  336. {
  337. return mavlink_msg_ais_vessel_pack_status(system_id, component_id, _status, msg, ais_vessel->MMSI, ais_vessel->lat, ais_vessel->lon, ais_vessel->COG, ais_vessel->heading, ais_vessel->velocity, ais_vessel->turn_rate, ais_vessel->navigational_status, ais_vessel->type, ais_vessel->dimension_bow, ais_vessel->dimension_stern, ais_vessel->dimension_port, ais_vessel->dimension_starboard, ais_vessel->callsign, ais_vessel->name, ais_vessel->tslc, ais_vessel->flags);
  338. }
  339. /**
  340. * @brief Send a ais_vessel message
  341. * @param chan MAVLink channel to send the message
  342. *
  343. * @param MMSI Mobile Marine Service Identifier, 9 decimal digits
  344. * @param lat [degE7] Latitude
  345. * @param lon [degE7] Longitude
  346. * @param COG [cdeg] Course over ground
  347. * @param heading [cdeg] True heading
  348. * @param velocity [cm/s] Speed over ground
  349. * @param turn_rate [cdeg/s] Turn rate
  350. * @param navigational_status Navigational status
  351. * @param type Type of vessels
  352. * @param dimension_bow [m] Distance from lat/lon location to bow
  353. * @param dimension_stern [m] Distance from lat/lon location to stern
  354. * @param dimension_port [m] Distance from lat/lon location to port side
  355. * @param dimension_starboard [m] Distance from lat/lon location to starboard side
  356. * @param callsign The vessel callsign
  357. * @param name The vessel name
  358. * @param tslc [s] Time since last communication in seconds
  359. * @param flags Bitmask to indicate various statuses including valid data fields
  360. */
  361. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  362. static inline void mavlink_msg_ais_vessel_send(mavlink_channel_t chan, uint32_t MMSI, int32_t lat, int32_t lon, uint16_t COG, uint16_t heading, uint16_t velocity, int8_t turn_rate, uint8_t navigational_status, uint8_t type, uint16_t dimension_bow, uint16_t dimension_stern, uint8_t dimension_port, uint8_t dimension_starboard, const char *callsign, const char *name, uint16_t tslc, uint16_t flags)
  363. {
  364. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  365. char buf[MAVLINK_MSG_ID_AIS_VESSEL_LEN];
  366. _mav_put_uint32_t(buf, 0, MMSI);
  367. _mav_put_int32_t(buf, 4, lat);
  368. _mav_put_int32_t(buf, 8, lon);
  369. _mav_put_uint16_t(buf, 12, COG);
  370. _mav_put_uint16_t(buf, 14, heading);
  371. _mav_put_uint16_t(buf, 16, velocity);
  372. _mav_put_uint16_t(buf, 18, dimension_bow);
  373. _mav_put_uint16_t(buf, 20, dimension_stern);
  374. _mav_put_uint16_t(buf, 22, tslc);
  375. _mav_put_uint16_t(buf, 24, flags);
  376. _mav_put_int8_t(buf, 26, turn_rate);
  377. _mav_put_uint8_t(buf, 27, navigational_status);
  378. _mav_put_uint8_t(buf, 28, type);
  379. _mav_put_uint8_t(buf, 29, dimension_port);
  380. _mav_put_uint8_t(buf, 30, dimension_starboard);
  381. _mav_put_char_array(buf, 31, callsign, 7);
  382. _mav_put_char_array(buf, 38, name, 20);
  383. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIS_VESSEL, buf, MAVLINK_MSG_ID_AIS_VESSEL_MIN_LEN, MAVLINK_MSG_ID_AIS_VESSEL_LEN, MAVLINK_MSG_ID_AIS_VESSEL_CRC);
  384. #else
  385. mavlink_ais_vessel_t packet;
  386. packet.MMSI = MMSI;
  387. packet.lat = lat;
  388. packet.lon = lon;
  389. packet.COG = COG;
  390. packet.heading = heading;
  391. packet.velocity = velocity;
  392. packet.dimension_bow = dimension_bow;
  393. packet.dimension_stern = dimension_stern;
  394. packet.tslc = tslc;
  395. packet.flags = flags;
  396. packet.turn_rate = turn_rate;
  397. packet.navigational_status = navigational_status;
  398. packet.type = type;
  399. packet.dimension_port = dimension_port;
  400. packet.dimension_starboard = dimension_starboard;
  401. mav_array_memcpy(packet.callsign, callsign, sizeof(char)*7);
  402. mav_array_memcpy(packet.name, name, sizeof(char)*20);
  403. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIS_VESSEL, (const char *)&packet, MAVLINK_MSG_ID_AIS_VESSEL_MIN_LEN, MAVLINK_MSG_ID_AIS_VESSEL_LEN, MAVLINK_MSG_ID_AIS_VESSEL_CRC);
  404. #endif
  405. }
  406. /**
  407. * @brief Send a ais_vessel message
  408. * @param chan MAVLink channel to send the message
  409. * @param struct The MAVLink struct to serialize
  410. */
  411. static inline void mavlink_msg_ais_vessel_send_struct(mavlink_channel_t chan, const mavlink_ais_vessel_t* ais_vessel)
  412. {
  413. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  414. mavlink_msg_ais_vessel_send(chan, ais_vessel->MMSI, ais_vessel->lat, ais_vessel->lon, ais_vessel->COG, ais_vessel->heading, ais_vessel->velocity, ais_vessel->turn_rate, ais_vessel->navigational_status, ais_vessel->type, ais_vessel->dimension_bow, ais_vessel->dimension_stern, ais_vessel->dimension_port, ais_vessel->dimension_starboard, ais_vessel->callsign, ais_vessel->name, ais_vessel->tslc, ais_vessel->flags);
  415. #else
  416. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIS_VESSEL, (const char *)ais_vessel, MAVLINK_MSG_ID_AIS_VESSEL_MIN_LEN, MAVLINK_MSG_ID_AIS_VESSEL_LEN, MAVLINK_MSG_ID_AIS_VESSEL_CRC);
  417. #endif
  418. }
  419. #if MAVLINK_MSG_ID_AIS_VESSEL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  420. /*
  421. This variant of _send() can be used to save stack space by re-using
  422. memory from the receive buffer. The caller provides a
  423. mavlink_message_t which is the size of a full mavlink message. This
  424. is usually the receive buffer for the channel, and allows a reply to an
  425. incoming message with minimum stack space usage.
  426. */
  427. static inline void mavlink_msg_ais_vessel_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t MMSI, int32_t lat, int32_t lon, uint16_t COG, uint16_t heading, uint16_t velocity, int8_t turn_rate, uint8_t navigational_status, uint8_t type, uint16_t dimension_bow, uint16_t dimension_stern, uint8_t dimension_port, uint8_t dimension_starboard, const char *callsign, const char *name, uint16_t tslc, uint16_t flags)
  428. {
  429. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  430. char *buf = (char *)msgbuf;
  431. _mav_put_uint32_t(buf, 0, MMSI);
  432. _mav_put_int32_t(buf, 4, lat);
  433. _mav_put_int32_t(buf, 8, lon);
  434. _mav_put_uint16_t(buf, 12, COG);
  435. _mav_put_uint16_t(buf, 14, heading);
  436. _mav_put_uint16_t(buf, 16, velocity);
  437. _mav_put_uint16_t(buf, 18, dimension_bow);
  438. _mav_put_uint16_t(buf, 20, dimension_stern);
  439. _mav_put_uint16_t(buf, 22, tslc);
  440. _mav_put_uint16_t(buf, 24, flags);
  441. _mav_put_int8_t(buf, 26, turn_rate);
  442. _mav_put_uint8_t(buf, 27, navigational_status);
  443. _mav_put_uint8_t(buf, 28, type);
  444. _mav_put_uint8_t(buf, 29, dimension_port);
  445. _mav_put_uint8_t(buf, 30, dimension_starboard);
  446. _mav_put_char_array(buf, 31, callsign, 7);
  447. _mav_put_char_array(buf, 38, name, 20);
  448. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIS_VESSEL, buf, MAVLINK_MSG_ID_AIS_VESSEL_MIN_LEN, MAVLINK_MSG_ID_AIS_VESSEL_LEN, MAVLINK_MSG_ID_AIS_VESSEL_CRC);
  449. #else
  450. mavlink_ais_vessel_t *packet = (mavlink_ais_vessel_t *)msgbuf;
  451. packet->MMSI = MMSI;
  452. packet->lat = lat;
  453. packet->lon = lon;
  454. packet->COG = COG;
  455. packet->heading = heading;
  456. packet->velocity = velocity;
  457. packet->dimension_bow = dimension_bow;
  458. packet->dimension_stern = dimension_stern;
  459. packet->tslc = tslc;
  460. packet->flags = flags;
  461. packet->turn_rate = turn_rate;
  462. packet->navigational_status = navigational_status;
  463. packet->type = type;
  464. packet->dimension_port = dimension_port;
  465. packet->dimension_starboard = dimension_starboard;
  466. mav_array_memcpy(packet->callsign, callsign, sizeof(char)*7);
  467. mav_array_memcpy(packet->name, name, sizeof(char)*20);
  468. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIS_VESSEL, (const char *)packet, MAVLINK_MSG_ID_AIS_VESSEL_MIN_LEN, MAVLINK_MSG_ID_AIS_VESSEL_LEN, MAVLINK_MSG_ID_AIS_VESSEL_CRC);
  469. #endif
  470. }
  471. #endif
  472. #endif
  473. // MESSAGE AIS_VESSEL UNPACKING
  474. /**
  475. * @brief Get field MMSI from ais_vessel message
  476. *
  477. * @return Mobile Marine Service Identifier, 9 decimal digits
  478. */
  479. static inline uint32_t mavlink_msg_ais_vessel_get_MMSI(const mavlink_message_t* msg)
  480. {
  481. return _MAV_RETURN_uint32_t(msg, 0);
  482. }
  483. /**
  484. * @brief Get field lat from ais_vessel message
  485. *
  486. * @return [degE7] Latitude
  487. */
  488. static inline int32_t mavlink_msg_ais_vessel_get_lat(const mavlink_message_t* msg)
  489. {
  490. return _MAV_RETURN_int32_t(msg, 4);
  491. }
  492. /**
  493. * @brief Get field lon from ais_vessel message
  494. *
  495. * @return [degE7] Longitude
  496. */
  497. static inline int32_t mavlink_msg_ais_vessel_get_lon(const mavlink_message_t* msg)
  498. {
  499. return _MAV_RETURN_int32_t(msg, 8);
  500. }
  501. /**
  502. * @brief Get field COG from ais_vessel message
  503. *
  504. * @return [cdeg] Course over ground
  505. */
  506. static inline uint16_t mavlink_msg_ais_vessel_get_COG(const mavlink_message_t* msg)
  507. {
  508. return _MAV_RETURN_uint16_t(msg, 12);
  509. }
  510. /**
  511. * @brief Get field heading from ais_vessel message
  512. *
  513. * @return [cdeg] True heading
  514. */
  515. static inline uint16_t mavlink_msg_ais_vessel_get_heading(const mavlink_message_t* msg)
  516. {
  517. return _MAV_RETURN_uint16_t(msg, 14);
  518. }
  519. /**
  520. * @brief Get field velocity from ais_vessel message
  521. *
  522. * @return [cm/s] Speed over ground
  523. */
  524. static inline uint16_t mavlink_msg_ais_vessel_get_velocity(const mavlink_message_t* msg)
  525. {
  526. return _MAV_RETURN_uint16_t(msg, 16);
  527. }
  528. /**
  529. * @brief Get field turn_rate from ais_vessel message
  530. *
  531. * @return [cdeg/s] Turn rate
  532. */
  533. static inline int8_t mavlink_msg_ais_vessel_get_turn_rate(const mavlink_message_t* msg)
  534. {
  535. return _MAV_RETURN_int8_t(msg, 26);
  536. }
  537. /**
  538. * @brief Get field navigational_status from ais_vessel message
  539. *
  540. * @return Navigational status
  541. */
  542. static inline uint8_t mavlink_msg_ais_vessel_get_navigational_status(const mavlink_message_t* msg)
  543. {
  544. return _MAV_RETURN_uint8_t(msg, 27);
  545. }
  546. /**
  547. * @brief Get field type from ais_vessel message
  548. *
  549. * @return Type of vessels
  550. */
  551. static inline uint8_t mavlink_msg_ais_vessel_get_type(const mavlink_message_t* msg)
  552. {
  553. return _MAV_RETURN_uint8_t(msg, 28);
  554. }
  555. /**
  556. * @brief Get field dimension_bow from ais_vessel message
  557. *
  558. * @return [m] Distance from lat/lon location to bow
  559. */
  560. static inline uint16_t mavlink_msg_ais_vessel_get_dimension_bow(const mavlink_message_t* msg)
  561. {
  562. return _MAV_RETURN_uint16_t(msg, 18);
  563. }
  564. /**
  565. * @brief Get field dimension_stern from ais_vessel message
  566. *
  567. * @return [m] Distance from lat/lon location to stern
  568. */
  569. static inline uint16_t mavlink_msg_ais_vessel_get_dimension_stern(const mavlink_message_t* msg)
  570. {
  571. return _MAV_RETURN_uint16_t(msg, 20);
  572. }
  573. /**
  574. * @brief Get field dimension_port from ais_vessel message
  575. *
  576. * @return [m] Distance from lat/lon location to port side
  577. */
  578. static inline uint8_t mavlink_msg_ais_vessel_get_dimension_port(const mavlink_message_t* msg)
  579. {
  580. return _MAV_RETURN_uint8_t(msg, 29);
  581. }
  582. /**
  583. * @brief Get field dimension_starboard from ais_vessel message
  584. *
  585. * @return [m] Distance from lat/lon location to starboard side
  586. */
  587. static inline uint8_t mavlink_msg_ais_vessel_get_dimension_starboard(const mavlink_message_t* msg)
  588. {
  589. return _MAV_RETURN_uint8_t(msg, 30);
  590. }
  591. /**
  592. * @brief Get field callsign from ais_vessel message
  593. *
  594. * @return The vessel callsign
  595. */
  596. static inline uint16_t mavlink_msg_ais_vessel_get_callsign(const mavlink_message_t* msg, char *callsign)
  597. {
  598. return _MAV_RETURN_char_array(msg, callsign, 7, 31);
  599. }
  600. /**
  601. * @brief Get field name from ais_vessel message
  602. *
  603. * @return The vessel name
  604. */
  605. static inline uint16_t mavlink_msg_ais_vessel_get_name(const mavlink_message_t* msg, char *name)
  606. {
  607. return _MAV_RETURN_char_array(msg, name, 20, 38);
  608. }
  609. /**
  610. * @brief Get field tslc from ais_vessel message
  611. *
  612. * @return [s] Time since last communication in seconds
  613. */
  614. static inline uint16_t mavlink_msg_ais_vessel_get_tslc(const mavlink_message_t* msg)
  615. {
  616. return _MAV_RETURN_uint16_t(msg, 22);
  617. }
  618. /**
  619. * @brief Get field flags from ais_vessel message
  620. *
  621. * @return Bitmask to indicate various statuses including valid data fields
  622. */
  623. static inline uint16_t mavlink_msg_ais_vessel_get_flags(const mavlink_message_t* msg)
  624. {
  625. return _MAV_RETURN_uint16_t(msg, 24);
  626. }
  627. /**
  628. * @brief Decode a ais_vessel message into a struct
  629. *
  630. * @param msg The message to decode
  631. * @param ais_vessel C-struct to decode the message contents into
  632. */
  633. static inline void mavlink_msg_ais_vessel_decode(const mavlink_message_t* msg, mavlink_ais_vessel_t* ais_vessel)
  634. {
  635. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  636. ais_vessel->MMSI = mavlink_msg_ais_vessel_get_MMSI(msg);
  637. ais_vessel->lat = mavlink_msg_ais_vessel_get_lat(msg);
  638. ais_vessel->lon = mavlink_msg_ais_vessel_get_lon(msg);
  639. ais_vessel->COG = mavlink_msg_ais_vessel_get_COG(msg);
  640. ais_vessel->heading = mavlink_msg_ais_vessel_get_heading(msg);
  641. ais_vessel->velocity = mavlink_msg_ais_vessel_get_velocity(msg);
  642. ais_vessel->dimension_bow = mavlink_msg_ais_vessel_get_dimension_bow(msg);
  643. ais_vessel->dimension_stern = mavlink_msg_ais_vessel_get_dimension_stern(msg);
  644. ais_vessel->tslc = mavlink_msg_ais_vessel_get_tslc(msg);
  645. ais_vessel->flags = mavlink_msg_ais_vessel_get_flags(msg);
  646. ais_vessel->turn_rate = mavlink_msg_ais_vessel_get_turn_rate(msg);
  647. ais_vessel->navigational_status = mavlink_msg_ais_vessel_get_navigational_status(msg);
  648. ais_vessel->type = mavlink_msg_ais_vessel_get_type(msg);
  649. ais_vessel->dimension_port = mavlink_msg_ais_vessel_get_dimension_port(msg);
  650. ais_vessel->dimension_starboard = mavlink_msg_ais_vessel_get_dimension_starboard(msg);
  651. mavlink_msg_ais_vessel_get_callsign(msg, ais_vessel->callsign);
  652. mavlink_msg_ais_vessel_get_name(msg, ais_vessel->name);
  653. #else
  654. uint8_t len = msg->len < MAVLINK_MSG_ID_AIS_VESSEL_LEN? msg->len : MAVLINK_MSG_ID_AIS_VESSEL_LEN;
  655. memset(ais_vessel, 0, MAVLINK_MSG_ID_AIS_VESSEL_LEN);
  656. memcpy(ais_vessel, _MAV_PAYLOAD(msg), len);
  657. #endif
  658. }