mavlink_msg_rc_channels.h 32 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713
  1. #pragma once
  2. // MESSAGE RC_CHANNELS PACKING
  3. #define MAVLINK_MSG_ID_RC_CHANNELS 65
  4. typedef struct __mavlink_rc_channels_t {
  5. uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
  6. uint16_t chan1_raw; /*< [us] RC channel 1 value.*/
  7. uint16_t chan2_raw; /*< [us] RC channel 2 value.*/
  8. uint16_t chan3_raw; /*< [us] RC channel 3 value.*/
  9. uint16_t chan4_raw; /*< [us] RC channel 4 value.*/
  10. uint16_t chan5_raw; /*< [us] RC channel 5 value.*/
  11. uint16_t chan6_raw; /*< [us] RC channel 6 value.*/
  12. uint16_t chan7_raw; /*< [us] RC channel 7 value.*/
  13. uint16_t chan8_raw; /*< [us] RC channel 8 value.*/
  14. uint16_t chan9_raw; /*< [us] RC channel 9 value.*/
  15. uint16_t chan10_raw; /*< [us] RC channel 10 value.*/
  16. uint16_t chan11_raw; /*< [us] RC channel 11 value.*/
  17. uint16_t chan12_raw; /*< [us] RC channel 12 value.*/
  18. uint16_t chan13_raw; /*< [us] RC channel 13 value.*/
  19. uint16_t chan14_raw; /*< [us] RC channel 14 value.*/
  20. uint16_t chan15_raw; /*< [us] RC channel 15 value.*/
  21. uint16_t chan16_raw; /*< [us] RC channel 16 value.*/
  22. uint16_t chan17_raw; /*< [us] RC channel 17 value.*/
  23. uint16_t chan18_raw; /*< [us] RC channel 18 value.*/
  24. uint8_t chancount; /*< Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.*/
  25. uint8_t rssi; /*< Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown.*/
  26. } mavlink_rc_channels_t;
  27. #define MAVLINK_MSG_ID_RC_CHANNELS_LEN 42
  28. #define MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN 42
  29. #define MAVLINK_MSG_ID_65_LEN 42
  30. #define MAVLINK_MSG_ID_65_MIN_LEN 42
  31. #define MAVLINK_MSG_ID_RC_CHANNELS_CRC 118
  32. #define MAVLINK_MSG_ID_65_CRC 118
  33. #if MAVLINK_COMMAND_24BIT
  34. #define MAVLINK_MESSAGE_INFO_RC_CHANNELS { \
  35. 65, \
  36. "RC_CHANNELS", \
  37. 21, \
  38. { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_t, time_boot_ms) }, \
  39. { "chancount", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_rc_channels_t, chancount) }, \
  40. { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_t, chan1_raw) }, \
  41. { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_t, chan2_raw) }, \
  42. { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_t, chan3_raw) }, \
  43. { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_t, chan4_raw) }, \
  44. { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_t, chan5_raw) }, \
  45. { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_t, chan6_raw) }, \
  46. { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_t, chan7_raw) }, \
  47. { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_t, chan8_raw) }, \
  48. { "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_rc_channels_t, chan9_raw) }, \
  49. { "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_rc_channels_t, chan10_raw) }, \
  50. { "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_rc_channels_t, chan11_raw) }, \
  51. { "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_rc_channels_t, chan12_raw) }, \
  52. { "chan13_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_rc_channels_t, chan13_raw) }, \
  53. { "chan14_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_rc_channels_t, chan14_raw) }, \
  54. { "chan15_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_rc_channels_t, chan15_raw) }, \
  55. { "chan16_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_rc_channels_t, chan16_raw) }, \
  56. { "chan17_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_rc_channels_t, chan17_raw) }, \
  57. { "chan18_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 38, offsetof(mavlink_rc_channels_t, chan18_raw) }, \
  58. { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_rc_channels_t, rssi) }, \
  59. } \
  60. }
  61. #else
  62. #define MAVLINK_MESSAGE_INFO_RC_CHANNELS { \
  63. "RC_CHANNELS", \
  64. 21, \
  65. { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_t, time_boot_ms) }, \
  66. { "chancount", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_rc_channels_t, chancount) }, \
  67. { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_t, chan1_raw) }, \
  68. { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_t, chan2_raw) }, \
  69. { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_t, chan3_raw) }, \
  70. { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_t, chan4_raw) }, \
  71. { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_t, chan5_raw) }, \
  72. { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_t, chan6_raw) }, \
  73. { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_t, chan7_raw) }, \
  74. { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_t, chan8_raw) }, \
  75. { "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_rc_channels_t, chan9_raw) }, \
  76. { "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_rc_channels_t, chan10_raw) }, \
  77. { "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_rc_channels_t, chan11_raw) }, \
  78. { "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_rc_channels_t, chan12_raw) }, \
  79. { "chan13_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_rc_channels_t, chan13_raw) }, \
  80. { "chan14_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_rc_channels_t, chan14_raw) }, \
  81. { "chan15_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_rc_channels_t, chan15_raw) }, \
  82. { "chan16_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_rc_channels_t, chan16_raw) }, \
  83. { "chan17_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_rc_channels_t, chan17_raw) }, \
  84. { "chan18_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 38, offsetof(mavlink_rc_channels_t, chan18_raw) }, \
  85. { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_rc_channels_t, rssi) }, \
  86. } \
  87. }
  88. #endif
  89. /**
  90. * @brief Pack a rc_channels message
  91. * @param system_id ID of this system
  92. * @param component_id ID of this component (e.g. 200 for IMU)
  93. * @param msg The MAVLink message to compress the data into
  94. *
  95. * @param time_boot_ms [ms] Timestamp (time since system boot).
  96. * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.
  97. * @param chan1_raw [us] RC channel 1 value.
  98. * @param chan2_raw [us] RC channel 2 value.
  99. * @param chan3_raw [us] RC channel 3 value.
  100. * @param chan4_raw [us] RC channel 4 value.
  101. * @param chan5_raw [us] RC channel 5 value.
  102. * @param chan6_raw [us] RC channel 6 value.
  103. * @param chan7_raw [us] RC channel 7 value.
  104. * @param chan8_raw [us] RC channel 8 value.
  105. * @param chan9_raw [us] RC channel 9 value.
  106. * @param chan10_raw [us] RC channel 10 value.
  107. * @param chan11_raw [us] RC channel 11 value.
  108. * @param chan12_raw [us] RC channel 12 value.
  109. * @param chan13_raw [us] RC channel 13 value.
  110. * @param chan14_raw [us] RC channel 14 value.
  111. * @param chan15_raw [us] RC channel 15 value.
  112. * @param chan16_raw [us] RC channel 16 value.
  113. * @param chan17_raw [us] RC channel 17 value.
  114. * @param chan18_raw [us] RC channel 18 value.
  115. * @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown.
  116. * @return length of the message in bytes (excluding serial stream start sign)
  117. */
  118. static inline uint16_t mavlink_msg_rc_channels_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  119. uint32_t time_boot_ms, uint8_t chancount, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi)
  120. {
  121. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  122. char buf[MAVLINK_MSG_ID_RC_CHANNELS_LEN];
  123. _mav_put_uint32_t(buf, 0, time_boot_ms);
  124. _mav_put_uint16_t(buf, 4, chan1_raw);
  125. _mav_put_uint16_t(buf, 6, chan2_raw);
  126. _mav_put_uint16_t(buf, 8, chan3_raw);
  127. _mav_put_uint16_t(buf, 10, chan4_raw);
  128. _mav_put_uint16_t(buf, 12, chan5_raw);
  129. _mav_put_uint16_t(buf, 14, chan6_raw);
  130. _mav_put_uint16_t(buf, 16, chan7_raw);
  131. _mav_put_uint16_t(buf, 18, chan8_raw);
  132. _mav_put_uint16_t(buf, 20, chan9_raw);
  133. _mav_put_uint16_t(buf, 22, chan10_raw);
  134. _mav_put_uint16_t(buf, 24, chan11_raw);
  135. _mav_put_uint16_t(buf, 26, chan12_raw);
  136. _mav_put_uint16_t(buf, 28, chan13_raw);
  137. _mav_put_uint16_t(buf, 30, chan14_raw);
  138. _mav_put_uint16_t(buf, 32, chan15_raw);
  139. _mav_put_uint16_t(buf, 34, chan16_raw);
  140. _mav_put_uint16_t(buf, 36, chan17_raw);
  141. _mav_put_uint16_t(buf, 38, chan18_raw);
  142. _mav_put_uint8_t(buf, 40, chancount);
  143. _mav_put_uint8_t(buf, 41, rssi);
  144. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
  145. #else
  146. mavlink_rc_channels_t packet;
  147. packet.time_boot_ms = time_boot_ms;
  148. packet.chan1_raw = chan1_raw;
  149. packet.chan2_raw = chan2_raw;
  150. packet.chan3_raw = chan3_raw;
  151. packet.chan4_raw = chan4_raw;
  152. packet.chan5_raw = chan5_raw;
  153. packet.chan6_raw = chan6_raw;
  154. packet.chan7_raw = chan7_raw;
  155. packet.chan8_raw = chan8_raw;
  156. packet.chan9_raw = chan9_raw;
  157. packet.chan10_raw = chan10_raw;
  158. packet.chan11_raw = chan11_raw;
  159. packet.chan12_raw = chan12_raw;
  160. packet.chan13_raw = chan13_raw;
  161. packet.chan14_raw = chan14_raw;
  162. packet.chan15_raw = chan15_raw;
  163. packet.chan16_raw = chan16_raw;
  164. packet.chan17_raw = chan17_raw;
  165. packet.chan18_raw = chan18_raw;
  166. packet.chancount = chancount;
  167. packet.rssi = rssi;
  168. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
  169. #endif
  170. msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS;
  171. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC);
  172. }
  173. /**
  174. * @brief Pack a rc_channels 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 time_boot_ms [ms] Timestamp (time since system boot).
  180. * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.
  181. * @param chan1_raw [us] RC channel 1 value.
  182. * @param chan2_raw [us] RC channel 2 value.
  183. * @param chan3_raw [us] RC channel 3 value.
  184. * @param chan4_raw [us] RC channel 4 value.
  185. * @param chan5_raw [us] RC channel 5 value.
  186. * @param chan6_raw [us] RC channel 6 value.
  187. * @param chan7_raw [us] RC channel 7 value.
  188. * @param chan8_raw [us] RC channel 8 value.
  189. * @param chan9_raw [us] RC channel 9 value.
  190. * @param chan10_raw [us] RC channel 10 value.
  191. * @param chan11_raw [us] RC channel 11 value.
  192. * @param chan12_raw [us] RC channel 12 value.
  193. * @param chan13_raw [us] RC channel 13 value.
  194. * @param chan14_raw [us] RC channel 14 value.
  195. * @param chan15_raw [us] RC channel 15 value.
  196. * @param chan16_raw [us] RC channel 16 value.
  197. * @param chan17_raw [us] RC channel 17 value.
  198. * @param chan18_raw [us] RC channel 18 value.
  199. * @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown.
  200. * @return length of the message in bytes (excluding serial stream start sign)
  201. */
  202. static inline uint16_t mavlink_msg_rc_channels_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  203. mavlink_message_t* msg,
  204. uint32_t time_boot_ms,uint8_t chancount,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw,uint16_t chan9_raw,uint16_t chan10_raw,uint16_t chan11_raw,uint16_t chan12_raw,uint16_t chan13_raw,uint16_t chan14_raw,uint16_t chan15_raw,uint16_t chan16_raw,uint16_t chan17_raw,uint16_t chan18_raw,uint8_t rssi)
  205. {
  206. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  207. char buf[MAVLINK_MSG_ID_RC_CHANNELS_LEN];
  208. _mav_put_uint32_t(buf, 0, time_boot_ms);
  209. _mav_put_uint16_t(buf, 4, chan1_raw);
  210. _mav_put_uint16_t(buf, 6, chan2_raw);
  211. _mav_put_uint16_t(buf, 8, chan3_raw);
  212. _mav_put_uint16_t(buf, 10, chan4_raw);
  213. _mav_put_uint16_t(buf, 12, chan5_raw);
  214. _mav_put_uint16_t(buf, 14, chan6_raw);
  215. _mav_put_uint16_t(buf, 16, chan7_raw);
  216. _mav_put_uint16_t(buf, 18, chan8_raw);
  217. _mav_put_uint16_t(buf, 20, chan9_raw);
  218. _mav_put_uint16_t(buf, 22, chan10_raw);
  219. _mav_put_uint16_t(buf, 24, chan11_raw);
  220. _mav_put_uint16_t(buf, 26, chan12_raw);
  221. _mav_put_uint16_t(buf, 28, chan13_raw);
  222. _mav_put_uint16_t(buf, 30, chan14_raw);
  223. _mav_put_uint16_t(buf, 32, chan15_raw);
  224. _mav_put_uint16_t(buf, 34, chan16_raw);
  225. _mav_put_uint16_t(buf, 36, chan17_raw);
  226. _mav_put_uint16_t(buf, 38, chan18_raw);
  227. _mav_put_uint8_t(buf, 40, chancount);
  228. _mav_put_uint8_t(buf, 41, rssi);
  229. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
  230. #else
  231. mavlink_rc_channels_t packet;
  232. packet.time_boot_ms = time_boot_ms;
  233. packet.chan1_raw = chan1_raw;
  234. packet.chan2_raw = chan2_raw;
  235. packet.chan3_raw = chan3_raw;
  236. packet.chan4_raw = chan4_raw;
  237. packet.chan5_raw = chan5_raw;
  238. packet.chan6_raw = chan6_raw;
  239. packet.chan7_raw = chan7_raw;
  240. packet.chan8_raw = chan8_raw;
  241. packet.chan9_raw = chan9_raw;
  242. packet.chan10_raw = chan10_raw;
  243. packet.chan11_raw = chan11_raw;
  244. packet.chan12_raw = chan12_raw;
  245. packet.chan13_raw = chan13_raw;
  246. packet.chan14_raw = chan14_raw;
  247. packet.chan15_raw = chan15_raw;
  248. packet.chan16_raw = chan16_raw;
  249. packet.chan17_raw = chan17_raw;
  250. packet.chan18_raw = chan18_raw;
  251. packet.chancount = chancount;
  252. packet.rssi = rssi;
  253. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
  254. #endif
  255. msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS;
  256. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC);
  257. }
  258. /**
  259. * @brief Encode a rc_channels struct
  260. *
  261. * @param system_id ID of this system
  262. * @param component_id ID of this component (e.g. 200 for IMU)
  263. * @param msg The MAVLink message to compress the data into
  264. * @param rc_channels C-struct to read the message contents from
  265. */
  266. static inline uint16_t mavlink_msg_rc_channels_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_t* rc_channels)
  267. {
  268. return mavlink_msg_rc_channels_pack(system_id, component_id, msg, rc_channels->time_boot_ms, rc_channels->chancount, rc_channels->chan1_raw, rc_channels->chan2_raw, rc_channels->chan3_raw, rc_channels->chan4_raw, rc_channels->chan5_raw, rc_channels->chan6_raw, rc_channels->chan7_raw, rc_channels->chan8_raw, rc_channels->chan9_raw, rc_channels->chan10_raw, rc_channels->chan11_raw, rc_channels->chan12_raw, rc_channels->chan13_raw, rc_channels->chan14_raw, rc_channels->chan15_raw, rc_channels->chan16_raw, rc_channels->chan17_raw, rc_channels->chan18_raw, rc_channels->rssi);
  269. }
  270. /**
  271. * @brief Encode a rc_channels struct on a channel
  272. *
  273. * @param system_id ID of this system
  274. * @param component_id ID of this component (e.g. 200 for IMU)
  275. * @param chan The MAVLink channel this message will be sent over
  276. * @param msg The MAVLink message to compress the data into
  277. * @param rc_channels C-struct to read the message contents from
  278. */
  279. static inline uint16_t mavlink_msg_rc_channels_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_t* rc_channels)
  280. {
  281. return mavlink_msg_rc_channels_pack_chan(system_id, component_id, chan, msg, rc_channels->time_boot_ms, rc_channels->chancount, rc_channels->chan1_raw, rc_channels->chan2_raw, rc_channels->chan3_raw, rc_channels->chan4_raw, rc_channels->chan5_raw, rc_channels->chan6_raw, rc_channels->chan7_raw, rc_channels->chan8_raw, rc_channels->chan9_raw, rc_channels->chan10_raw, rc_channels->chan11_raw, rc_channels->chan12_raw, rc_channels->chan13_raw, rc_channels->chan14_raw, rc_channels->chan15_raw, rc_channels->chan16_raw, rc_channels->chan17_raw, rc_channels->chan18_raw, rc_channels->rssi);
  282. }
  283. /**
  284. * @brief Send a rc_channels message
  285. * @param chan MAVLink channel to send the message
  286. *
  287. * @param time_boot_ms [ms] Timestamp (time since system boot).
  288. * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.
  289. * @param chan1_raw [us] RC channel 1 value.
  290. * @param chan2_raw [us] RC channel 2 value.
  291. * @param chan3_raw [us] RC channel 3 value.
  292. * @param chan4_raw [us] RC channel 4 value.
  293. * @param chan5_raw [us] RC channel 5 value.
  294. * @param chan6_raw [us] RC channel 6 value.
  295. * @param chan7_raw [us] RC channel 7 value.
  296. * @param chan8_raw [us] RC channel 8 value.
  297. * @param chan9_raw [us] RC channel 9 value.
  298. * @param chan10_raw [us] RC channel 10 value.
  299. * @param chan11_raw [us] RC channel 11 value.
  300. * @param chan12_raw [us] RC channel 12 value.
  301. * @param chan13_raw [us] RC channel 13 value.
  302. * @param chan14_raw [us] RC channel 14 value.
  303. * @param chan15_raw [us] RC channel 15 value.
  304. * @param chan16_raw [us] RC channel 16 value.
  305. * @param chan17_raw [us] RC channel 17 value.
  306. * @param chan18_raw [us] RC channel 18 value.
  307. * @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown.
  308. */
  309. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  310. static inline void mavlink_msg_rc_channels_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t chancount, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi)
  311. {
  312. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  313. char buf[MAVLINK_MSG_ID_RC_CHANNELS_LEN];
  314. _mav_put_uint32_t(buf, 0, time_boot_ms);
  315. _mav_put_uint16_t(buf, 4, chan1_raw);
  316. _mav_put_uint16_t(buf, 6, chan2_raw);
  317. _mav_put_uint16_t(buf, 8, chan3_raw);
  318. _mav_put_uint16_t(buf, 10, chan4_raw);
  319. _mav_put_uint16_t(buf, 12, chan5_raw);
  320. _mav_put_uint16_t(buf, 14, chan6_raw);
  321. _mav_put_uint16_t(buf, 16, chan7_raw);
  322. _mav_put_uint16_t(buf, 18, chan8_raw);
  323. _mav_put_uint16_t(buf, 20, chan9_raw);
  324. _mav_put_uint16_t(buf, 22, chan10_raw);
  325. _mav_put_uint16_t(buf, 24, chan11_raw);
  326. _mav_put_uint16_t(buf, 26, chan12_raw);
  327. _mav_put_uint16_t(buf, 28, chan13_raw);
  328. _mav_put_uint16_t(buf, 30, chan14_raw);
  329. _mav_put_uint16_t(buf, 32, chan15_raw);
  330. _mav_put_uint16_t(buf, 34, chan16_raw);
  331. _mav_put_uint16_t(buf, 36, chan17_raw);
  332. _mav_put_uint16_t(buf, 38, chan18_raw);
  333. _mav_put_uint8_t(buf, 40, chancount);
  334. _mav_put_uint8_t(buf, 41, rssi);
  335. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC);
  336. #else
  337. mavlink_rc_channels_t packet;
  338. packet.time_boot_ms = time_boot_ms;
  339. packet.chan1_raw = chan1_raw;
  340. packet.chan2_raw = chan2_raw;
  341. packet.chan3_raw = chan3_raw;
  342. packet.chan4_raw = chan4_raw;
  343. packet.chan5_raw = chan5_raw;
  344. packet.chan6_raw = chan6_raw;
  345. packet.chan7_raw = chan7_raw;
  346. packet.chan8_raw = chan8_raw;
  347. packet.chan9_raw = chan9_raw;
  348. packet.chan10_raw = chan10_raw;
  349. packet.chan11_raw = chan11_raw;
  350. packet.chan12_raw = chan12_raw;
  351. packet.chan13_raw = chan13_raw;
  352. packet.chan14_raw = chan14_raw;
  353. packet.chan15_raw = chan15_raw;
  354. packet.chan16_raw = chan16_raw;
  355. packet.chan17_raw = chan17_raw;
  356. packet.chan18_raw = chan18_raw;
  357. packet.chancount = chancount;
  358. packet.rssi = rssi;
  359. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC);
  360. #endif
  361. }
  362. /**
  363. * @brief Send a rc_channels message
  364. * @param chan MAVLink channel to send the message
  365. * @param struct The MAVLink struct to serialize
  366. */
  367. static inline void mavlink_msg_rc_channels_send_struct(mavlink_channel_t chan, const mavlink_rc_channels_t* rc_channels)
  368. {
  369. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  370. mavlink_msg_rc_channels_send(chan, rc_channels->time_boot_ms, rc_channels->chancount, rc_channels->chan1_raw, rc_channels->chan2_raw, rc_channels->chan3_raw, rc_channels->chan4_raw, rc_channels->chan5_raw, rc_channels->chan6_raw, rc_channels->chan7_raw, rc_channels->chan8_raw, rc_channels->chan9_raw, rc_channels->chan10_raw, rc_channels->chan11_raw, rc_channels->chan12_raw, rc_channels->chan13_raw, rc_channels->chan14_raw, rc_channels->chan15_raw, rc_channels->chan16_raw, rc_channels->chan17_raw, rc_channels->chan18_raw, rc_channels->rssi);
  371. #else
  372. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)rc_channels, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC);
  373. #endif
  374. }
  375. #if MAVLINK_MSG_ID_RC_CHANNELS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  376. /*
  377. This variant of _send() can be used to save stack space by re-using
  378. memory from the receive buffer. The caller provides a
  379. mavlink_message_t which is the size of a full mavlink message. This
  380. is usually the receive buffer for the channel, and allows a reply to an
  381. incoming message with minimum stack space usage.
  382. */
  383. static inline void mavlink_msg_rc_channels_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t chancount, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi)
  384. {
  385. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  386. char *buf = (char *)msgbuf;
  387. _mav_put_uint32_t(buf, 0, time_boot_ms);
  388. _mav_put_uint16_t(buf, 4, chan1_raw);
  389. _mav_put_uint16_t(buf, 6, chan2_raw);
  390. _mav_put_uint16_t(buf, 8, chan3_raw);
  391. _mav_put_uint16_t(buf, 10, chan4_raw);
  392. _mav_put_uint16_t(buf, 12, chan5_raw);
  393. _mav_put_uint16_t(buf, 14, chan6_raw);
  394. _mav_put_uint16_t(buf, 16, chan7_raw);
  395. _mav_put_uint16_t(buf, 18, chan8_raw);
  396. _mav_put_uint16_t(buf, 20, chan9_raw);
  397. _mav_put_uint16_t(buf, 22, chan10_raw);
  398. _mav_put_uint16_t(buf, 24, chan11_raw);
  399. _mav_put_uint16_t(buf, 26, chan12_raw);
  400. _mav_put_uint16_t(buf, 28, chan13_raw);
  401. _mav_put_uint16_t(buf, 30, chan14_raw);
  402. _mav_put_uint16_t(buf, 32, chan15_raw);
  403. _mav_put_uint16_t(buf, 34, chan16_raw);
  404. _mav_put_uint16_t(buf, 36, chan17_raw);
  405. _mav_put_uint16_t(buf, 38, chan18_raw);
  406. _mav_put_uint8_t(buf, 40, chancount);
  407. _mav_put_uint8_t(buf, 41, rssi);
  408. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC);
  409. #else
  410. mavlink_rc_channels_t *packet = (mavlink_rc_channels_t *)msgbuf;
  411. packet->time_boot_ms = time_boot_ms;
  412. packet->chan1_raw = chan1_raw;
  413. packet->chan2_raw = chan2_raw;
  414. packet->chan3_raw = chan3_raw;
  415. packet->chan4_raw = chan4_raw;
  416. packet->chan5_raw = chan5_raw;
  417. packet->chan6_raw = chan6_raw;
  418. packet->chan7_raw = chan7_raw;
  419. packet->chan8_raw = chan8_raw;
  420. packet->chan9_raw = chan9_raw;
  421. packet->chan10_raw = chan10_raw;
  422. packet->chan11_raw = chan11_raw;
  423. packet->chan12_raw = chan12_raw;
  424. packet->chan13_raw = chan13_raw;
  425. packet->chan14_raw = chan14_raw;
  426. packet->chan15_raw = chan15_raw;
  427. packet->chan16_raw = chan16_raw;
  428. packet->chan17_raw = chan17_raw;
  429. packet->chan18_raw = chan18_raw;
  430. packet->chancount = chancount;
  431. packet->rssi = rssi;
  432. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC);
  433. #endif
  434. }
  435. #endif
  436. #endif
  437. // MESSAGE RC_CHANNELS UNPACKING
  438. /**
  439. * @brief Get field time_boot_ms from rc_channels message
  440. *
  441. * @return [ms] Timestamp (time since system boot).
  442. */
  443. static inline uint32_t mavlink_msg_rc_channels_get_time_boot_ms(const mavlink_message_t* msg)
  444. {
  445. return _MAV_RETURN_uint32_t(msg, 0);
  446. }
  447. /**
  448. * @brief Get field chancount from rc_channels message
  449. *
  450. * @return Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.
  451. */
  452. static inline uint8_t mavlink_msg_rc_channels_get_chancount(const mavlink_message_t* msg)
  453. {
  454. return _MAV_RETURN_uint8_t(msg, 40);
  455. }
  456. /**
  457. * @brief Get field chan1_raw from rc_channels message
  458. *
  459. * @return [us] RC channel 1 value.
  460. */
  461. static inline uint16_t mavlink_msg_rc_channels_get_chan1_raw(const mavlink_message_t* msg)
  462. {
  463. return _MAV_RETURN_uint16_t(msg, 4);
  464. }
  465. /**
  466. * @brief Get field chan2_raw from rc_channels message
  467. *
  468. * @return [us] RC channel 2 value.
  469. */
  470. static inline uint16_t mavlink_msg_rc_channels_get_chan2_raw(const mavlink_message_t* msg)
  471. {
  472. return _MAV_RETURN_uint16_t(msg, 6);
  473. }
  474. /**
  475. * @brief Get field chan3_raw from rc_channels message
  476. *
  477. * @return [us] RC channel 3 value.
  478. */
  479. static inline uint16_t mavlink_msg_rc_channels_get_chan3_raw(const mavlink_message_t* msg)
  480. {
  481. return _MAV_RETURN_uint16_t(msg, 8);
  482. }
  483. /**
  484. * @brief Get field chan4_raw from rc_channels message
  485. *
  486. * @return [us] RC channel 4 value.
  487. */
  488. static inline uint16_t mavlink_msg_rc_channels_get_chan4_raw(const mavlink_message_t* msg)
  489. {
  490. return _MAV_RETURN_uint16_t(msg, 10);
  491. }
  492. /**
  493. * @brief Get field chan5_raw from rc_channels message
  494. *
  495. * @return [us] RC channel 5 value.
  496. */
  497. static inline uint16_t mavlink_msg_rc_channels_get_chan5_raw(const mavlink_message_t* msg)
  498. {
  499. return _MAV_RETURN_uint16_t(msg, 12);
  500. }
  501. /**
  502. * @brief Get field chan6_raw from rc_channels message
  503. *
  504. * @return [us] RC channel 6 value.
  505. */
  506. static inline uint16_t mavlink_msg_rc_channels_get_chan6_raw(const mavlink_message_t* msg)
  507. {
  508. return _MAV_RETURN_uint16_t(msg, 14);
  509. }
  510. /**
  511. * @brief Get field chan7_raw from rc_channels message
  512. *
  513. * @return [us] RC channel 7 value.
  514. */
  515. static inline uint16_t mavlink_msg_rc_channels_get_chan7_raw(const mavlink_message_t* msg)
  516. {
  517. return _MAV_RETURN_uint16_t(msg, 16);
  518. }
  519. /**
  520. * @brief Get field chan8_raw from rc_channels message
  521. *
  522. * @return [us] RC channel 8 value.
  523. */
  524. static inline uint16_t mavlink_msg_rc_channels_get_chan8_raw(const mavlink_message_t* msg)
  525. {
  526. return _MAV_RETURN_uint16_t(msg, 18);
  527. }
  528. /**
  529. * @brief Get field chan9_raw from rc_channels message
  530. *
  531. * @return [us] RC channel 9 value.
  532. */
  533. static inline uint16_t mavlink_msg_rc_channels_get_chan9_raw(const mavlink_message_t* msg)
  534. {
  535. return _MAV_RETURN_uint16_t(msg, 20);
  536. }
  537. /**
  538. * @brief Get field chan10_raw from rc_channels message
  539. *
  540. * @return [us] RC channel 10 value.
  541. */
  542. static inline uint16_t mavlink_msg_rc_channels_get_chan10_raw(const mavlink_message_t* msg)
  543. {
  544. return _MAV_RETURN_uint16_t(msg, 22);
  545. }
  546. /**
  547. * @brief Get field chan11_raw from rc_channels message
  548. *
  549. * @return [us] RC channel 11 value.
  550. */
  551. static inline uint16_t mavlink_msg_rc_channels_get_chan11_raw(const mavlink_message_t* msg)
  552. {
  553. return _MAV_RETURN_uint16_t(msg, 24);
  554. }
  555. /**
  556. * @brief Get field chan12_raw from rc_channels message
  557. *
  558. * @return [us] RC channel 12 value.
  559. */
  560. static inline uint16_t mavlink_msg_rc_channels_get_chan12_raw(const mavlink_message_t* msg)
  561. {
  562. return _MAV_RETURN_uint16_t(msg, 26);
  563. }
  564. /**
  565. * @brief Get field chan13_raw from rc_channels message
  566. *
  567. * @return [us] RC channel 13 value.
  568. */
  569. static inline uint16_t mavlink_msg_rc_channels_get_chan13_raw(const mavlink_message_t* msg)
  570. {
  571. return _MAV_RETURN_uint16_t(msg, 28);
  572. }
  573. /**
  574. * @brief Get field chan14_raw from rc_channels message
  575. *
  576. * @return [us] RC channel 14 value.
  577. */
  578. static inline uint16_t mavlink_msg_rc_channels_get_chan14_raw(const mavlink_message_t* msg)
  579. {
  580. return _MAV_RETURN_uint16_t(msg, 30);
  581. }
  582. /**
  583. * @brief Get field chan15_raw from rc_channels message
  584. *
  585. * @return [us] RC channel 15 value.
  586. */
  587. static inline uint16_t mavlink_msg_rc_channels_get_chan15_raw(const mavlink_message_t* msg)
  588. {
  589. return _MAV_RETURN_uint16_t(msg, 32);
  590. }
  591. /**
  592. * @brief Get field chan16_raw from rc_channels message
  593. *
  594. * @return [us] RC channel 16 value.
  595. */
  596. static inline uint16_t mavlink_msg_rc_channels_get_chan16_raw(const mavlink_message_t* msg)
  597. {
  598. return _MAV_RETURN_uint16_t(msg, 34);
  599. }
  600. /**
  601. * @brief Get field chan17_raw from rc_channels message
  602. *
  603. * @return [us] RC channel 17 value.
  604. */
  605. static inline uint16_t mavlink_msg_rc_channels_get_chan17_raw(const mavlink_message_t* msg)
  606. {
  607. return _MAV_RETURN_uint16_t(msg, 36);
  608. }
  609. /**
  610. * @brief Get field chan18_raw from rc_channels message
  611. *
  612. * @return [us] RC channel 18 value.
  613. */
  614. static inline uint16_t mavlink_msg_rc_channels_get_chan18_raw(const mavlink_message_t* msg)
  615. {
  616. return _MAV_RETURN_uint16_t(msg, 38);
  617. }
  618. /**
  619. * @brief Get field rssi from rc_channels message
  620. *
  621. * @return Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown.
  622. */
  623. static inline uint8_t mavlink_msg_rc_channels_get_rssi(const mavlink_message_t* msg)
  624. {
  625. return _MAV_RETURN_uint8_t(msg, 41);
  626. }
  627. /**
  628. * @brief Decode a rc_channels message into a struct
  629. *
  630. * @param msg The message to decode
  631. * @param rc_channels C-struct to decode the message contents into
  632. */
  633. static inline void mavlink_msg_rc_channels_decode(const mavlink_message_t* msg, mavlink_rc_channels_t* rc_channels)
  634. {
  635. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  636. rc_channels->time_boot_ms = mavlink_msg_rc_channels_get_time_boot_ms(msg);
  637. rc_channels->chan1_raw = mavlink_msg_rc_channels_get_chan1_raw(msg);
  638. rc_channels->chan2_raw = mavlink_msg_rc_channels_get_chan2_raw(msg);
  639. rc_channels->chan3_raw = mavlink_msg_rc_channels_get_chan3_raw(msg);
  640. rc_channels->chan4_raw = mavlink_msg_rc_channels_get_chan4_raw(msg);
  641. rc_channels->chan5_raw = mavlink_msg_rc_channels_get_chan5_raw(msg);
  642. rc_channels->chan6_raw = mavlink_msg_rc_channels_get_chan6_raw(msg);
  643. rc_channels->chan7_raw = mavlink_msg_rc_channels_get_chan7_raw(msg);
  644. rc_channels->chan8_raw = mavlink_msg_rc_channels_get_chan8_raw(msg);
  645. rc_channels->chan9_raw = mavlink_msg_rc_channels_get_chan9_raw(msg);
  646. rc_channels->chan10_raw = mavlink_msg_rc_channels_get_chan10_raw(msg);
  647. rc_channels->chan11_raw = mavlink_msg_rc_channels_get_chan11_raw(msg);
  648. rc_channels->chan12_raw = mavlink_msg_rc_channels_get_chan12_raw(msg);
  649. rc_channels->chan13_raw = mavlink_msg_rc_channels_get_chan13_raw(msg);
  650. rc_channels->chan14_raw = mavlink_msg_rc_channels_get_chan14_raw(msg);
  651. rc_channels->chan15_raw = mavlink_msg_rc_channels_get_chan15_raw(msg);
  652. rc_channels->chan16_raw = mavlink_msg_rc_channels_get_chan16_raw(msg);
  653. rc_channels->chan17_raw = mavlink_msg_rc_channels_get_chan17_raw(msg);
  654. rc_channels->chan18_raw = mavlink_msg_rc_channels_get_chan18_raw(msg);
  655. rc_channels->chancount = mavlink_msg_rc_channels_get_chancount(msg);
  656. rc_channels->rssi = mavlink_msg_rc_channels_get_rssi(msg);
  657. #else
  658. uint8_t len = msg->len < MAVLINK_MSG_ID_RC_CHANNELS_LEN? msg->len : MAVLINK_MSG_ID_RC_CHANNELS_LEN;
  659. memset(rc_channels, 0, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
  660. memcpy(rc_channels, _MAV_PAYLOAD(msg), len);
  661. #endif
  662. }