mavlink_msg_link_node_status.h 26 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559
  1. #pragma once
  2. // MESSAGE LINK_NODE_STATUS PACKING
  3. #define MAVLINK_MSG_ID_LINK_NODE_STATUS 8
  4. typedef struct __mavlink_link_node_status_t {
  5. uint64_t timestamp; /*< [ms] Timestamp (time since system boot).*/
  6. uint32_t tx_rate; /*< [bytes/s] Transmit rate*/
  7. uint32_t rx_rate; /*< [bytes/s] Receive rate*/
  8. uint32_t messages_sent; /*< Messages sent*/
  9. uint32_t messages_received; /*< Messages received (estimated from counting seq)*/
  10. uint32_t messages_lost; /*< Messages lost (estimated from counting seq)*/
  11. uint16_t rx_parse_err; /*< [bytes] Number of bytes that could not be parsed correctly.*/
  12. uint16_t tx_overflows; /*< [bytes] Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX*/
  13. uint16_t rx_overflows; /*< [bytes] Receive buffer overflows. This number wraps around as it reaches UINT16_MAX*/
  14. uint8_t tx_buf; /*< [%] Remaining free transmit buffer space*/
  15. uint8_t rx_buf; /*< [%] Remaining free receive buffer space*/
  16. } mavlink_link_node_status_t;
  17. #define MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN 36
  18. #define MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN 36
  19. #define MAVLINK_MSG_ID_8_LEN 36
  20. #define MAVLINK_MSG_ID_8_MIN_LEN 36
  21. #define MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC 117
  22. #define MAVLINK_MSG_ID_8_CRC 117
  23. #if MAVLINK_COMMAND_24BIT
  24. #define MAVLINK_MESSAGE_INFO_LINK_NODE_STATUS { \
  25. 8, \
  26. "LINK_NODE_STATUS", \
  27. 11, \
  28. { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_link_node_status_t, timestamp) }, \
  29. { "tx_buf", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_link_node_status_t, tx_buf) }, \
  30. { "rx_buf", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_link_node_status_t, rx_buf) }, \
  31. { "tx_rate", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_link_node_status_t, tx_rate) }, \
  32. { "rx_rate", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_link_node_status_t, rx_rate) }, \
  33. { "rx_parse_err", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_link_node_status_t, rx_parse_err) }, \
  34. { "tx_overflows", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_link_node_status_t, tx_overflows) }, \
  35. { "rx_overflows", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_link_node_status_t, rx_overflows) }, \
  36. { "messages_sent", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_link_node_status_t, messages_sent) }, \
  37. { "messages_received", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_link_node_status_t, messages_received) }, \
  38. { "messages_lost", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_link_node_status_t, messages_lost) }, \
  39. } \
  40. }
  41. #else
  42. #define MAVLINK_MESSAGE_INFO_LINK_NODE_STATUS { \
  43. "LINK_NODE_STATUS", \
  44. 11, \
  45. { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_link_node_status_t, timestamp) }, \
  46. { "tx_buf", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_link_node_status_t, tx_buf) }, \
  47. { "rx_buf", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_link_node_status_t, rx_buf) }, \
  48. { "tx_rate", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_link_node_status_t, tx_rate) }, \
  49. { "rx_rate", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_link_node_status_t, rx_rate) }, \
  50. { "rx_parse_err", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_link_node_status_t, rx_parse_err) }, \
  51. { "tx_overflows", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_link_node_status_t, tx_overflows) }, \
  52. { "rx_overflows", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_link_node_status_t, rx_overflows) }, \
  53. { "messages_sent", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_link_node_status_t, messages_sent) }, \
  54. { "messages_received", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_link_node_status_t, messages_received) }, \
  55. { "messages_lost", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_link_node_status_t, messages_lost) }, \
  56. } \
  57. }
  58. #endif
  59. /**
  60. * @brief Pack a link_node_status message
  61. * @param system_id ID of this system
  62. * @param component_id ID of this component (e.g. 200 for IMU)
  63. * @param msg The MAVLink message to compress the data into
  64. *
  65. * @param timestamp [ms] Timestamp (time since system boot).
  66. * @param tx_buf [%] Remaining free transmit buffer space
  67. * @param rx_buf [%] Remaining free receive buffer space
  68. * @param tx_rate [bytes/s] Transmit rate
  69. * @param rx_rate [bytes/s] Receive rate
  70. * @param rx_parse_err [bytes] Number of bytes that could not be parsed correctly.
  71. * @param tx_overflows [bytes] Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX
  72. * @param rx_overflows [bytes] Receive buffer overflows. This number wraps around as it reaches UINT16_MAX
  73. * @param messages_sent Messages sent
  74. * @param messages_received Messages received (estimated from counting seq)
  75. * @param messages_lost Messages lost (estimated from counting seq)
  76. * @return length of the message in bytes (excluding serial stream start sign)
  77. */
  78. MAVLINK_WIP
  79. static inline uint16_t mavlink_msg_link_node_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  80. uint64_t timestamp, uint8_t tx_buf, uint8_t rx_buf, uint32_t tx_rate, uint32_t rx_rate, uint16_t rx_parse_err, uint16_t tx_overflows, uint16_t rx_overflows, uint32_t messages_sent, uint32_t messages_received, uint32_t messages_lost)
  81. {
  82. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  83. char buf[MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN];
  84. _mav_put_uint64_t(buf, 0, timestamp);
  85. _mav_put_uint32_t(buf, 8, tx_rate);
  86. _mav_put_uint32_t(buf, 12, rx_rate);
  87. _mav_put_uint32_t(buf, 16, messages_sent);
  88. _mav_put_uint32_t(buf, 20, messages_received);
  89. _mav_put_uint32_t(buf, 24, messages_lost);
  90. _mav_put_uint16_t(buf, 28, rx_parse_err);
  91. _mav_put_uint16_t(buf, 30, tx_overflows);
  92. _mav_put_uint16_t(buf, 32, rx_overflows);
  93. _mav_put_uint8_t(buf, 34, tx_buf);
  94. _mav_put_uint8_t(buf, 35, rx_buf);
  95. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN);
  96. #else
  97. mavlink_link_node_status_t packet;
  98. packet.timestamp = timestamp;
  99. packet.tx_rate = tx_rate;
  100. packet.rx_rate = rx_rate;
  101. packet.messages_sent = messages_sent;
  102. packet.messages_received = messages_received;
  103. packet.messages_lost = messages_lost;
  104. packet.rx_parse_err = rx_parse_err;
  105. packet.tx_overflows = tx_overflows;
  106. packet.rx_overflows = rx_overflows;
  107. packet.tx_buf = tx_buf;
  108. packet.rx_buf = rx_buf;
  109. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN);
  110. #endif
  111. msg->msgid = MAVLINK_MSG_ID_LINK_NODE_STATUS;
  112. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC);
  113. }
  114. /**
  115. * @brief Pack a link_node_status message
  116. * @param system_id ID of this system
  117. * @param component_id ID of this component (e.g. 200 for IMU)
  118. * @param status MAVLink status structure
  119. * @param msg The MAVLink message to compress the data into
  120. *
  121. * @param timestamp [ms] Timestamp (time since system boot).
  122. * @param tx_buf [%] Remaining free transmit buffer space
  123. * @param rx_buf [%] Remaining free receive buffer space
  124. * @param tx_rate [bytes/s] Transmit rate
  125. * @param rx_rate [bytes/s] Receive rate
  126. * @param rx_parse_err [bytes] Number of bytes that could not be parsed correctly.
  127. * @param tx_overflows [bytes] Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX
  128. * @param rx_overflows [bytes] Receive buffer overflows. This number wraps around as it reaches UINT16_MAX
  129. * @param messages_sent Messages sent
  130. * @param messages_received Messages received (estimated from counting seq)
  131. * @param messages_lost Messages lost (estimated from counting seq)
  132. * @return length of the message in bytes (excluding serial stream start sign)
  133. */
  134. static inline uint16_t mavlink_msg_link_node_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
  135. uint64_t timestamp, uint8_t tx_buf, uint8_t rx_buf, uint32_t tx_rate, uint32_t rx_rate, uint16_t rx_parse_err, uint16_t tx_overflows, uint16_t rx_overflows, uint32_t messages_sent, uint32_t messages_received, uint32_t messages_lost)
  136. {
  137. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  138. char buf[MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN];
  139. _mav_put_uint64_t(buf, 0, timestamp);
  140. _mav_put_uint32_t(buf, 8, tx_rate);
  141. _mav_put_uint32_t(buf, 12, rx_rate);
  142. _mav_put_uint32_t(buf, 16, messages_sent);
  143. _mav_put_uint32_t(buf, 20, messages_received);
  144. _mav_put_uint32_t(buf, 24, messages_lost);
  145. _mav_put_uint16_t(buf, 28, rx_parse_err);
  146. _mav_put_uint16_t(buf, 30, tx_overflows);
  147. _mav_put_uint16_t(buf, 32, rx_overflows);
  148. _mav_put_uint8_t(buf, 34, tx_buf);
  149. _mav_put_uint8_t(buf, 35, rx_buf);
  150. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN);
  151. #else
  152. mavlink_link_node_status_t packet;
  153. packet.timestamp = timestamp;
  154. packet.tx_rate = tx_rate;
  155. packet.rx_rate = rx_rate;
  156. packet.messages_sent = messages_sent;
  157. packet.messages_received = messages_received;
  158. packet.messages_lost = messages_lost;
  159. packet.rx_parse_err = rx_parse_err;
  160. packet.tx_overflows = tx_overflows;
  161. packet.rx_overflows = rx_overflows;
  162. packet.tx_buf = tx_buf;
  163. packet.rx_buf = rx_buf;
  164. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN);
  165. #endif
  166. msg->msgid = MAVLINK_MSG_ID_LINK_NODE_STATUS;
  167. #if MAVLINK_CRC_EXTRA
  168. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC);
  169. #else
  170. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN);
  171. #endif
  172. }
  173. /**
  174. * @brief Pack a link_node_status message on a channel
  175. * @param system_id ID of this system
  176. * @param component_id ID of this component (e.g. 200 for IMU)
  177. * @param chan The MAVLink channel this message will be sent over
  178. * @param msg The MAVLink message to compress the data into
  179. * @param timestamp [ms] Timestamp (time since system boot).
  180. * @param tx_buf [%] Remaining free transmit buffer space
  181. * @param rx_buf [%] Remaining free receive buffer space
  182. * @param tx_rate [bytes/s] Transmit rate
  183. * @param rx_rate [bytes/s] Receive rate
  184. * @param rx_parse_err [bytes] Number of bytes that could not be parsed correctly.
  185. * @param tx_overflows [bytes] Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX
  186. * @param rx_overflows [bytes] Receive buffer overflows. This number wraps around as it reaches UINT16_MAX
  187. * @param messages_sent Messages sent
  188. * @param messages_received Messages received (estimated from counting seq)
  189. * @param messages_lost Messages lost (estimated from counting seq)
  190. * @return length of the message in bytes (excluding serial stream start sign)
  191. */
  192. MAVLINK_WIP
  193. static inline uint16_t mavlink_msg_link_node_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  194. mavlink_message_t* msg,
  195. uint64_t timestamp,uint8_t tx_buf,uint8_t rx_buf,uint32_t tx_rate,uint32_t rx_rate,uint16_t rx_parse_err,uint16_t tx_overflows,uint16_t rx_overflows,uint32_t messages_sent,uint32_t messages_received,uint32_t messages_lost)
  196. {
  197. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  198. char buf[MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN];
  199. _mav_put_uint64_t(buf, 0, timestamp);
  200. _mav_put_uint32_t(buf, 8, tx_rate);
  201. _mav_put_uint32_t(buf, 12, rx_rate);
  202. _mav_put_uint32_t(buf, 16, messages_sent);
  203. _mav_put_uint32_t(buf, 20, messages_received);
  204. _mav_put_uint32_t(buf, 24, messages_lost);
  205. _mav_put_uint16_t(buf, 28, rx_parse_err);
  206. _mav_put_uint16_t(buf, 30, tx_overflows);
  207. _mav_put_uint16_t(buf, 32, rx_overflows);
  208. _mav_put_uint8_t(buf, 34, tx_buf);
  209. _mav_put_uint8_t(buf, 35, rx_buf);
  210. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN);
  211. #else
  212. mavlink_link_node_status_t packet;
  213. packet.timestamp = timestamp;
  214. packet.tx_rate = tx_rate;
  215. packet.rx_rate = rx_rate;
  216. packet.messages_sent = messages_sent;
  217. packet.messages_received = messages_received;
  218. packet.messages_lost = messages_lost;
  219. packet.rx_parse_err = rx_parse_err;
  220. packet.tx_overflows = tx_overflows;
  221. packet.rx_overflows = rx_overflows;
  222. packet.tx_buf = tx_buf;
  223. packet.rx_buf = rx_buf;
  224. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN);
  225. #endif
  226. msg->msgid = MAVLINK_MSG_ID_LINK_NODE_STATUS;
  227. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC);
  228. }
  229. /**
  230. * @brief Encode a link_node_status 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 link_node_status C-struct to read the message contents from
  236. */
  237. MAVLINK_WIP
  238. static inline uint16_t mavlink_msg_link_node_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_link_node_status_t* link_node_status)
  239. {
  240. return mavlink_msg_link_node_status_pack(system_id, component_id, msg, link_node_status->timestamp, link_node_status->tx_buf, link_node_status->rx_buf, link_node_status->tx_rate, link_node_status->rx_rate, link_node_status->rx_parse_err, link_node_status->tx_overflows, link_node_status->rx_overflows, link_node_status->messages_sent, link_node_status->messages_received, link_node_status->messages_lost);
  241. }
  242. /**
  243. * @brief Encode a link_node_status struct on a channel
  244. *
  245. * @param system_id ID of this system
  246. * @param component_id ID of this component (e.g. 200 for IMU)
  247. * @param chan The MAVLink channel this message will be sent over
  248. * @param msg The MAVLink message to compress the data into
  249. * @param link_node_status C-struct to read the message contents from
  250. */
  251. MAVLINK_WIP
  252. static inline uint16_t mavlink_msg_link_node_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_link_node_status_t* link_node_status)
  253. {
  254. return mavlink_msg_link_node_status_pack_chan(system_id, component_id, chan, msg, link_node_status->timestamp, link_node_status->tx_buf, link_node_status->rx_buf, link_node_status->tx_rate, link_node_status->rx_rate, link_node_status->rx_parse_err, link_node_status->tx_overflows, link_node_status->rx_overflows, link_node_status->messages_sent, link_node_status->messages_received, link_node_status->messages_lost);
  255. }
  256. /**
  257. * @brief Encode a link_node_status struct with provided status structure
  258. *
  259. * @param system_id ID of this system
  260. * @param component_id ID of this component (e.g. 200 for IMU)
  261. * @param status MAVLink status structure
  262. * @param msg The MAVLink message to compress the data into
  263. * @param link_node_status C-struct to read the message contents from
  264. */
  265. static inline uint16_t mavlink_msg_link_node_status_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_link_node_status_t* link_node_status)
  266. {
  267. return mavlink_msg_link_node_status_pack_status(system_id, component_id, _status, msg, link_node_status->timestamp, link_node_status->tx_buf, link_node_status->rx_buf, link_node_status->tx_rate, link_node_status->rx_rate, link_node_status->rx_parse_err, link_node_status->tx_overflows, link_node_status->rx_overflows, link_node_status->messages_sent, link_node_status->messages_received, link_node_status->messages_lost);
  268. }
  269. /**
  270. * @brief Send a link_node_status message
  271. * @param chan MAVLink channel to send the message
  272. *
  273. * @param timestamp [ms] Timestamp (time since system boot).
  274. * @param tx_buf [%] Remaining free transmit buffer space
  275. * @param rx_buf [%] Remaining free receive buffer space
  276. * @param tx_rate [bytes/s] Transmit rate
  277. * @param rx_rate [bytes/s] Receive rate
  278. * @param rx_parse_err [bytes] Number of bytes that could not be parsed correctly.
  279. * @param tx_overflows [bytes] Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX
  280. * @param rx_overflows [bytes] Receive buffer overflows. This number wraps around as it reaches UINT16_MAX
  281. * @param messages_sent Messages sent
  282. * @param messages_received Messages received (estimated from counting seq)
  283. * @param messages_lost Messages lost (estimated from counting seq)
  284. */
  285. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  286. MAVLINK_WIP
  287. static inline void mavlink_msg_link_node_status_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t tx_buf, uint8_t rx_buf, uint32_t tx_rate, uint32_t rx_rate, uint16_t rx_parse_err, uint16_t tx_overflows, uint16_t rx_overflows, uint32_t messages_sent, uint32_t messages_received, uint32_t messages_lost)
  288. {
  289. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  290. char buf[MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN];
  291. _mav_put_uint64_t(buf, 0, timestamp);
  292. _mav_put_uint32_t(buf, 8, tx_rate);
  293. _mav_put_uint32_t(buf, 12, rx_rate);
  294. _mav_put_uint32_t(buf, 16, messages_sent);
  295. _mav_put_uint32_t(buf, 20, messages_received);
  296. _mav_put_uint32_t(buf, 24, messages_lost);
  297. _mav_put_uint16_t(buf, 28, rx_parse_err);
  298. _mav_put_uint16_t(buf, 30, tx_overflows);
  299. _mav_put_uint16_t(buf, 32, rx_overflows);
  300. _mav_put_uint8_t(buf, 34, tx_buf);
  301. _mav_put_uint8_t(buf, 35, rx_buf);
  302. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LINK_NODE_STATUS, buf, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC);
  303. #else
  304. mavlink_link_node_status_t packet;
  305. packet.timestamp = timestamp;
  306. packet.tx_rate = tx_rate;
  307. packet.rx_rate = rx_rate;
  308. packet.messages_sent = messages_sent;
  309. packet.messages_received = messages_received;
  310. packet.messages_lost = messages_lost;
  311. packet.rx_parse_err = rx_parse_err;
  312. packet.tx_overflows = tx_overflows;
  313. packet.rx_overflows = rx_overflows;
  314. packet.tx_buf = tx_buf;
  315. packet.rx_buf = rx_buf;
  316. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LINK_NODE_STATUS, (const char *)&packet, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC);
  317. #endif
  318. }
  319. /**
  320. * @brief Send a link_node_status message
  321. * @param chan MAVLink channel to send the message
  322. * @param struct The MAVLink struct to serialize
  323. */
  324. MAVLINK_WIP
  325. static inline void mavlink_msg_link_node_status_send_struct(mavlink_channel_t chan, const mavlink_link_node_status_t* link_node_status)
  326. {
  327. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  328. mavlink_msg_link_node_status_send(chan, link_node_status->timestamp, link_node_status->tx_buf, link_node_status->rx_buf, link_node_status->tx_rate, link_node_status->rx_rate, link_node_status->rx_parse_err, link_node_status->tx_overflows, link_node_status->rx_overflows, link_node_status->messages_sent, link_node_status->messages_received, link_node_status->messages_lost);
  329. #else
  330. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LINK_NODE_STATUS, (const char *)link_node_status, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC);
  331. #endif
  332. }
  333. #if MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  334. /*
  335. This variant of _send() can be used to save stack space by reusing
  336. memory from the receive buffer. The caller provides a
  337. mavlink_message_t which is the size of a full mavlink message. This
  338. is usually the receive buffer for the channel, and allows a reply to an
  339. incoming message with minimum stack space usage.
  340. */
  341. MAVLINK_WIP
  342. static inline void mavlink_msg_link_node_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t tx_buf, uint8_t rx_buf, uint32_t tx_rate, uint32_t rx_rate, uint16_t rx_parse_err, uint16_t tx_overflows, uint16_t rx_overflows, uint32_t messages_sent, uint32_t messages_received, uint32_t messages_lost)
  343. {
  344. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  345. char *buf = (char *)msgbuf;
  346. _mav_put_uint64_t(buf, 0, timestamp);
  347. _mav_put_uint32_t(buf, 8, tx_rate);
  348. _mav_put_uint32_t(buf, 12, rx_rate);
  349. _mav_put_uint32_t(buf, 16, messages_sent);
  350. _mav_put_uint32_t(buf, 20, messages_received);
  351. _mav_put_uint32_t(buf, 24, messages_lost);
  352. _mav_put_uint16_t(buf, 28, rx_parse_err);
  353. _mav_put_uint16_t(buf, 30, tx_overflows);
  354. _mav_put_uint16_t(buf, 32, rx_overflows);
  355. _mav_put_uint8_t(buf, 34, tx_buf);
  356. _mav_put_uint8_t(buf, 35, rx_buf);
  357. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LINK_NODE_STATUS, buf, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC);
  358. #else
  359. mavlink_link_node_status_t *packet = (mavlink_link_node_status_t *)msgbuf;
  360. packet->timestamp = timestamp;
  361. packet->tx_rate = tx_rate;
  362. packet->rx_rate = rx_rate;
  363. packet->messages_sent = messages_sent;
  364. packet->messages_received = messages_received;
  365. packet->messages_lost = messages_lost;
  366. packet->rx_parse_err = rx_parse_err;
  367. packet->tx_overflows = tx_overflows;
  368. packet->rx_overflows = rx_overflows;
  369. packet->tx_buf = tx_buf;
  370. packet->rx_buf = rx_buf;
  371. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LINK_NODE_STATUS, (const char *)packet, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC);
  372. #endif
  373. }
  374. #endif
  375. #endif
  376. // MESSAGE LINK_NODE_STATUS UNPACKING
  377. /**
  378. * @brief Get field timestamp from link_node_status message
  379. *
  380. * @return [ms] Timestamp (time since system boot).
  381. */
  382. MAVLINK_WIP
  383. static inline uint64_t mavlink_msg_link_node_status_get_timestamp(const mavlink_message_t* msg)
  384. {
  385. return _MAV_RETURN_uint64_t(msg, 0);
  386. }
  387. /**
  388. * @brief Get field tx_buf from link_node_status message
  389. *
  390. * @return [%] Remaining free transmit buffer space
  391. */
  392. MAVLINK_WIP
  393. static inline uint8_t mavlink_msg_link_node_status_get_tx_buf(const mavlink_message_t* msg)
  394. {
  395. return _MAV_RETURN_uint8_t(msg, 34);
  396. }
  397. /**
  398. * @brief Get field rx_buf from link_node_status message
  399. *
  400. * @return [%] Remaining free receive buffer space
  401. */
  402. MAVLINK_WIP
  403. static inline uint8_t mavlink_msg_link_node_status_get_rx_buf(const mavlink_message_t* msg)
  404. {
  405. return _MAV_RETURN_uint8_t(msg, 35);
  406. }
  407. /**
  408. * @brief Get field tx_rate from link_node_status message
  409. *
  410. * @return [bytes/s] Transmit rate
  411. */
  412. MAVLINK_WIP
  413. static inline uint32_t mavlink_msg_link_node_status_get_tx_rate(const mavlink_message_t* msg)
  414. {
  415. return _MAV_RETURN_uint32_t(msg, 8);
  416. }
  417. /**
  418. * @brief Get field rx_rate from link_node_status message
  419. *
  420. * @return [bytes/s] Receive rate
  421. */
  422. MAVLINK_WIP
  423. static inline uint32_t mavlink_msg_link_node_status_get_rx_rate(const mavlink_message_t* msg)
  424. {
  425. return _MAV_RETURN_uint32_t(msg, 12);
  426. }
  427. /**
  428. * @brief Get field rx_parse_err from link_node_status message
  429. *
  430. * @return [bytes] Number of bytes that could not be parsed correctly.
  431. */
  432. MAVLINK_WIP
  433. static inline uint16_t mavlink_msg_link_node_status_get_rx_parse_err(const mavlink_message_t* msg)
  434. {
  435. return _MAV_RETURN_uint16_t(msg, 28);
  436. }
  437. /**
  438. * @brief Get field tx_overflows from link_node_status message
  439. *
  440. * @return [bytes] Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX
  441. */
  442. MAVLINK_WIP
  443. static inline uint16_t mavlink_msg_link_node_status_get_tx_overflows(const mavlink_message_t* msg)
  444. {
  445. return _MAV_RETURN_uint16_t(msg, 30);
  446. }
  447. /**
  448. * @brief Get field rx_overflows from link_node_status message
  449. *
  450. * @return [bytes] Receive buffer overflows. This number wraps around as it reaches UINT16_MAX
  451. */
  452. MAVLINK_WIP
  453. static inline uint16_t mavlink_msg_link_node_status_get_rx_overflows(const mavlink_message_t* msg)
  454. {
  455. return _MAV_RETURN_uint16_t(msg, 32);
  456. }
  457. /**
  458. * @brief Get field messages_sent from link_node_status message
  459. *
  460. * @return Messages sent
  461. */
  462. MAVLINK_WIP
  463. static inline uint32_t mavlink_msg_link_node_status_get_messages_sent(const mavlink_message_t* msg)
  464. {
  465. return _MAV_RETURN_uint32_t(msg, 16);
  466. }
  467. /**
  468. * @brief Get field messages_received from link_node_status message
  469. *
  470. * @return Messages received (estimated from counting seq)
  471. */
  472. MAVLINK_WIP
  473. static inline uint32_t mavlink_msg_link_node_status_get_messages_received(const mavlink_message_t* msg)
  474. {
  475. return _MAV_RETURN_uint32_t(msg, 20);
  476. }
  477. /**
  478. * @brief Get field messages_lost from link_node_status message
  479. *
  480. * @return Messages lost (estimated from counting seq)
  481. */
  482. MAVLINK_WIP
  483. static inline uint32_t mavlink_msg_link_node_status_get_messages_lost(const mavlink_message_t* msg)
  484. {
  485. return _MAV_RETURN_uint32_t(msg, 24);
  486. }
  487. /**
  488. * @brief Decode a link_node_status message into a struct
  489. *
  490. * @param msg The message to decode
  491. * @param link_node_status C-struct to decode the message contents into
  492. */
  493. MAVLINK_WIP
  494. static inline void mavlink_msg_link_node_status_decode(const mavlink_message_t* msg, mavlink_link_node_status_t* link_node_status)
  495. {
  496. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  497. link_node_status->timestamp = mavlink_msg_link_node_status_get_timestamp(msg);
  498. link_node_status->tx_rate = mavlink_msg_link_node_status_get_tx_rate(msg);
  499. link_node_status->rx_rate = mavlink_msg_link_node_status_get_rx_rate(msg);
  500. link_node_status->messages_sent = mavlink_msg_link_node_status_get_messages_sent(msg);
  501. link_node_status->messages_received = mavlink_msg_link_node_status_get_messages_received(msg);
  502. link_node_status->messages_lost = mavlink_msg_link_node_status_get_messages_lost(msg);
  503. link_node_status->rx_parse_err = mavlink_msg_link_node_status_get_rx_parse_err(msg);
  504. link_node_status->tx_overflows = mavlink_msg_link_node_status_get_tx_overflows(msg);
  505. link_node_status->rx_overflows = mavlink_msg_link_node_status_get_rx_overflows(msg);
  506. link_node_status->tx_buf = mavlink_msg_link_node_status_get_tx_buf(msg);
  507. link_node_status->rx_buf = mavlink_msg_link_node_status_get_rx_buf(msg);
  508. #else
  509. uint8_t len = msg->len < MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN? msg->len : MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN;
  510. memset(link_node_status, 0, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN);
  511. memcpy(link_node_status, _MAV_PAYLOAD(msg), len);
  512. #endif
  513. }