mavlink_helpers.h 37 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069107010711072107310741075107610771078107910801081108210831084108510861087108810891090109110921093109410951096109710981099110011011102110311041105110611071108110911101111111211131114111511161117111811191120112111221123112411251126112711281129113011311132113311341135113611371138113911401141114211431144114511461147114811491150115111521153115411551156115711581159116011611162116311641165116611671168
  1. #pragma once
  2. #include "string.h"
  3. #include "checksum.h"
  4. #include "mavlink_types.h"
  5. #include "mavlink_conversions.h"
  6. #include <stdio.h>
  7. #ifndef MAVLINK_HELPER
  8. #define MAVLINK_HELPER
  9. #endif
  10. #include "mavlink_sha256.h"
  11. #ifndef MAVLINK_SIGNING_TIMESTAMP_LIMIT
  12. #define MAVLINK_SIGNING_TIMESTAMP_LIMIT 60
  13. #endif
  14. #ifdef MAVLINK_USE_CXX_NAMESPACE
  15. namespace mavlink {
  16. #endif
  17. /*
  18. * Internal function to give access to the channel status for each channel
  19. */
  20. #ifndef MAVLINK_GET_CHANNEL_STATUS
  21. MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan)
  22. {
  23. #ifdef MAVLINK_EXTERNAL_RX_STATUS
  24. // No m_mavlink_status array defined in function,
  25. // has to be defined externally
  26. #else
  27. static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS];
  28. #endif
  29. return &m_mavlink_status[chan];
  30. }
  31. #endif
  32. /*
  33. * Internal function to give access to the channel buffer for each channel
  34. */
  35. #ifndef MAVLINK_GET_CHANNEL_BUFFER
  36. MAVLINK_HELPER mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan)
  37. {
  38. #ifdef MAVLINK_EXTERNAL_RX_BUFFER
  39. // No m_mavlink_buffer array defined in function,
  40. // has to be defined externally
  41. #else
  42. static mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];
  43. #endif
  44. return &m_mavlink_buffer[chan];
  45. }
  46. #endif // MAVLINK_GET_CHANNEL_BUFFER
  47. /* Enable this option to check the length of each message.
  48. This allows invalid messages to be caught much sooner. Use if the transmission
  49. medium is prone to missing (or extra) characters (e.g. a radio that fades in
  50. and out). Only use if the channel will only contain messages types listed in
  51. the headers.
  52. */
  53. //#define MAVLINK_CHECK_MESSAGE_LENGTH
  54. /**
  55. * @brief Reset the status of a channel.
  56. */
  57. MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan)
  58. {
  59. mavlink_status_t *status = mavlink_get_channel_status(chan);
  60. status->parse_state = MAVLINK_PARSE_STATE_IDLE;
  61. }
  62. #ifndef MAVLINK_NO_SIGN_PACKET
  63. /**
  64. * @brief create a signature block for a packet
  65. */
  66. MAVLINK_HELPER uint8_t mavlink_sign_packet(mavlink_signing_t *signing,
  67. uint8_t signature[MAVLINK_SIGNATURE_BLOCK_LEN],
  68. const uint8_t *header, uint8_t header_len,
  69. const uint8_t *packet, uint8_t packet_len,
  70. const uint8_t crc[2])
  71. {
  72. mavlink_sha256_ctx ctx;
  73. union {
  74. uint64_t t64;
  75. uint8_t t8[8];
  76. } tstamp;
  77. if (signing == NULL || !(signing->flags & MAVLINK_SIGNING_FLAG_SIGN_OUTGOING)) {
  78. return 0;
  79. }
  80. signature[0] = signing->link_id;
  81. tstamp.t64 = signing->timestamp;
  82. memcpy(&signature[1], tstamp.t8, 6);
  83. signing->timestamp++;
  84. mavlink_sha256_init(&ctx);
  85. mavlink_sha256_update(&ctx, signing->secret_key, sizeof(signing->secret_key));
  86. mavlink_sha256_update(&ctx, header, header_len);
  87. mavlink_sha256_update(&ctx, packet, packet_len);
  88. mavlink_sha256_update(&ctx, crc, 2);
  89. mavlink_sha256_update(&ctx, signature, 7);
  90. mavlink_sha256_final_48(&ctx, &signature[7]);
  91. return MAVLINK_SIGNATURE_BLOCK_LEN;
  92. }
  93. #endif
  94. /**
  95. * @brief Trim payload of any trailing zero-populated bytes (MAVLink 2 only).
  96. *
  97. * @param payload Serialised payload buffer.
  98. * @param length Length of full-width payload buffer.
  99. * @return Length of payload after zero-filled bytes are trimmed.
  100. */
  101. MAVLINK_HELPER uint8_t _mav_trim_payload(const char *payload, uint8_t length)
  102. {
  103. while (length > 1 && payload[length-1] == 0) {
  104. length--;
  105. }
  106. return length;
  107. }
  108. #ifndef MAVLINK_NO_SIGNATURE_CHECK
  109. /**
  110. * @brief check a signature block for a packet
  111. */
  112. MAVLINK_HELPER bool mavlink_signature_check(mavlink_signing_t *signing,
  113. mavlink_signing_streams_t *signing_streams,
  114. const mavlink_message_t *msg)
  115. {
  116. if (signing == NULL) {
  117. return true;
  118. }
  119. const uint8_t *p = (const uint8_t *)&msg->magic;
  120. const uint8_t *psig = msg->signature;
  121. const uint8_t *incoming_signature = psig+7;
  122. mavlink_sha256_ctx ctx;
  123. uint8_t signature[6];
  124. uint16_t i;
  125. mavlink_sha256_init(&ctx);
  126. mavlink_sha256_update(&ctx, signing->secret_key, sizeof(signing->secret_key));
  127. mavlink_sha256_update(&ctx, p, MAVLINK_NUM_HEADER_BYTES);
  128. mavlink_sha256_update(&ctx, _MAV_PAYLOAD(msg), msg->len);
  129. mavlink_sha256_update(&ctx, msg->ck, 2);
  130. mavlink_sha256_update(&ctx, psig, 1+6);
  131. mavlink_sha256_final_48(&ctx, signature);
  132. if (memcmp(signature, incoming_signature, 6) != 0) {
  133. signing->last_status = MAVLINK_SIGNING_STATUS_BAD_SIGNATURE;
  134. return false;
  135. }
  136. // now check timestamp
  137. union tstamp {
  138. uint64_t t64;
  139. uint8_t t8[8];
  140. } tstamp;
  141. uint8_t link_id = psig[0];
  142. tstamp.t64 = 0;
  143. memcpy(tstamp.t8, psig+1, 6);
  144. if (signing_streams == NULL) {
  145. signing->last_status = MAVLINK_SIGNING_STATUS_NO_STREAMS;
  146. return false;
  147. }
  148. // find stream
  149. for (i=0; i<signing_streams->num_signing_streams; i++) {
  150. if (msg->sysid == signing_streams->stream[i].sysid &&
  151. msg->compid == signing_streams->stream[i].compid &&
  152. link_id == signing_streams->stream[i].link_id) {
  153. break;
  154. }
  155. }
  156. if (i == signing_streams->num_signing_streams) {
  157. if (signing_streams->num_signing_streams >= MAVLINK_MAX_SIGNING_STREAMS) {
  158. // over max number of streams
  159. signing->last_status = MAVLINK_SIGNING_STATUS_TOO_MANY_STREAMS;
  160. return false;
  161. }
  162. // new stream. Only accept if timestamp is not more than 1 minute old by default
  163. if (tstamp.t64 + MAVLINK_SIGNING_TIMESTAMP_LIMIT*100000UL < signing->timestamp) {
  164. signing->last_status = MAVLINK_SIGNING_STATUS_OLD_TIMESTAMP;
  165. return false;
  166. }
  167. // add new stream
  168. signing_streams->stream[i].sysid = msg->sysid;
  169. signing_streams->stream[i].compid = msg->compid;
  170. signing_streams->stream[i].link_id = link_id;
  171. signing_streams->num_signing_streams++;
  172. } else {
  173. union tstamp last_tstamp;
  174. last_tstamp.t64 = 0;
  175. memcpy(last_tstamp.t8, signing_streams->stream[i].timestamp_bytes, 6);
  176. if (tstamp.t64 <= last_tstamp.t64) {
  177. // repeating old timestamp
  178. signing->last_status = MAVLINK_SIGNING_STATUS_REPLAY;
  179. return false;
  180. }
  181. }
  182. // remember last timestamp
  183. memcpy(signing_streams->stream[i].timestamp_bytes, psig+1, 6);
  184. // our next timestamp must be at least this timestamp
  185. if (tstamp.t64 > signing->timestamp) {
  186. signing->timestamp = tstamp.t64;
  187. }
  188. signing->last_status = MAVLINK_SIGNING_STATUS_OK;
  189. return true;
  190. }
  191. #endif
  192. /**
  193. * @brief Finalize a MAVLink message with channel assignment
  194. *
  195. * This function calculates the checksum and sets length and aircraft id correctly.
  196. * It assumes that the message id and the payload are already correctly set. This function
  197. * can also be used if the message header has already been written before (as in mavlink_msg_xxx_pack
  198. * instead of mavlink_msg_xxx_pack_headerless), it just introduces little extra overhead.
  199. *
  200. * @param msg Message to finalize
  201. * @param system_id Id of the sending (this) system, 1-127
  202. * @param length Message length
  203. */
  204. MAVLINK_HELPER uint16_t mavlink_finalize_message_buffer(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
  205. mavlink_status_t* status, uint8_t min_length, uint8_t length, uint8_t crc_extra)
  206. {
  207. bool mavlink1 = (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) != 0;
  208. #ifndef MAVLINK_NO_SIGN_PACKET
  209. bool signing = (!mavlink1) && status->signing && (status->signing->flags & MAVLINK_SIGNING_FLAG_SIGN_OUTGOING);
  210. #else
  211. bool signing = false;
  212. #endif
  213. uint8_t signature_len = signing? MAVLINK_SIGNATURE_BLOCK_LEN : 0;
  214. uint8_t header_len = MAVLINK_CORE_HEADER_LEN+1;
  215. uint8_t buf[MAVLINK_CORE_HEADER_LEN+1];
  216. if (mavlink1) {
  217. msg->magic = MAVLINK_STX_MAVLINK1;
  218. header_len = MAVLINK_CORE_HEADER_MAVLINK1_LEN+1;
  219. } else {
  220. msg->magic = MAVLINK_STX;
  221. }
  222. msg->len = mavlink1?min_length:_mav_trim_payload(_MAV_PAYLOAD(msg), length);
  223. msg->sysid = system_id;
  224. msg->compid = component_id;
  225. msg->incompat_flags = 0;
  226. if (signing) {
  227. msg->incompat_flags |= MAVLINK_IFLAG_SIGNED;
  228. }
  229. msg->compat_flags = 0;
  230. msg->seq = status->current_tx_seq;
  231. status->current_tx_seq = status->current_tx_seq + 1;
  232. // form the header as a byte array for the crc
  233. buf[0] = msg->magic;
  234. buf[1] = msg->len;
  235. if (mavlink1) {
  236. buf[2] = msg->seq;
  237. buf[3] = msg->sysid;
  238. buf[4] = msg->compid;
  239. buf[5] = msg->msgid & 0xFF;
  240. } else {
  241. buf[2] = msg->incompat_flags;
  242. buf[3] = msg->compat_flags;
  243. buf[4] = msg->seq;
  244. buf[5] = msg->sysid;
  245. buf[6] = msg->compid;
  246. buf[7] = msg->msgid & 0xFF;
  247. buf[8] = (msg->msgid >> 8) & 0xFF;
  248. buf[9] = (msg->msgid >> 16) & 0xFF;
  249. }
  250. uint16_t checksum = crc_calculate(&buf[1], header_len-1);
  251. crc_accumulate_buffer(&checksum, _MAV_PAYLOAD(msg), msg->len);
  252. crc_accumulate(crc_extra, &checksum);
  253. mavlink_ck_a(msg) = (uint8_t)(checksum & 0xFF);
  254. mavlink_ck_b(msg) = (uint8_t)(checksum >> 8);
  255. msg->checksum = checksum;
  256. #ifndef MAVLINK_NO_SIGN_PACKET
  257. if (signing) {
  258. mavlink_sign_packet(status->signing,
  259. msg->signature,
  260. (const uint8_t *)buf, header_len,
  261. (const uint8_t *)_MAV_PAYLOAD(msg), msg->len,
  262. (const uint8_t *)_MAV_PAYLOAD(msg)+(uint16_t)msg->len);
  263. }
  264. #endif
  265. return msg->len + header_len + 2 + signature_len;
  266. }
  267. MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
  268. uint8_t chan, uint8_t min_length, uint8_t length, uint8_t crc_extra)
  269. {
  270. mavlink_status_t *status = mavlink_get_channel_status(chan);
  271. return mavlink_finalize_message_buffer(msg, system_id, component_id, status, min_length, length, crc_extra);
  272. }
  273. /**
  274. * @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel
  275. */
  276. MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
  277. uint8_t min_length, uint8_t length, uint8_t crc_extra)
  278. {
  279. return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, min_length, length, crc_extra);
  280. }
  281. static inline void _mav_parse_error(mavlink_status_t *status)
  282. {
  283. status->parse_error++;
  284. }
  285. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  286. MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len);
  287. /**
  288. * @brief Finalize a MAVLink message with channel assignment and send
  289. */
  290. MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint32_t msgid,
  291. const char *packet,
  292. uint8_t min_length, uint8_t length, uint8_t crc_extra)
  293. {
  294. uint16_t checksum;
  295. uint8_t buf[MAVLINK_NUM_HEADER_BYTES];
  296. uint8_t ck[2];
  297. mavlink_status_t *status = mavlink_get_channel_status(chan);
  298. uint8_t header_len = MAVLINK_CORE_HEADER_LEN;
  299. uint8_t signature_len = 0;
  300. uint8_t signature[MAVLINK_SIGNATURE_BLOCK_LEN];
  301. bool mavlink1 = (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) != 0;
  302. bool signing = (!mavlink1) && status->signing && (status->signing->flags & MAVLINK_SIGNING_FLAG_SIGN_OUTGOING);
  303. if (mavlink1) {
  304. length = min_length;
  305. if (msgid > 255) {
  306. // can't send 16 bit messages
  307. _mav_parse_error(status);
  308. return;
  309. }
  310. header_len = MAVLINK_CORE_HEADER_MAVLINK1_LEN;
  311. buf[0] = MAVLINK_STX_MAVLINK1;
  312. buf[1] = length;
  313. buf[2] = status->current_tx_seq;
  314. buf[3] = mavlink_system.sysid;
  315. buf[4] = mavlink_system.compid;
  316. buf[5] = msgid & 0xFF;
  317. } else {
  318. uint8_t incompat_flags = 0;
  319. if (signing) {
  320. incompat_flags |= MAVLINK_IFLAG_SIGNED;
  321. }
  322. length = _mav_trim_payload(packet, length);
  323. buf[0] = MAVLINK_STX;
  324. buf[1] = length;
  325. buf[2] = incompat_flags;
  326. buf[3] = 0; // compat_flags
  327. buf[4] = status->current_tx_seq;
  328. buf[5] = mavlink_system.sysid;
  329. buf[6] = mavlink_system.compid;
  330. buf[7] = msgid & 0xFF;
  331. buf[8] = (msgid >> 8) & 0xFF;
  332. buf[9] = (msgid >> 16) & 0xFF;
  333. }
  334. status->current_tx_seq++;
  335. checksum = crc_calculate((const uint8_t*)&buf[1], header_len);
  336. crc_accumulate_buffer(&checksum, packet, length);
  337. crc_accumulate(crc_extra, &checksum);
  338. ck[0] = (uint8_t)(checksum & 0xFF);
  339. ck[1] = (uint8_t)(checksum >> 8);
  340. #ifndef MAVLINK_NO_SIGN_PACKET
  341. if (signing) {
  342. // possibly add a signature
  343. signature_len = mavlink_sign_packet(status->signing, signature, buf, header_len+1,
  344. (const uint8_t *)packet, length, ck);
  345. }
  346. #endif
  347. MAVLINK_START_UART_SEND(chan, header_len + 3 + (uint16_t)length + (uint16_t)signature_len);
  348. _mavlink_send_uart(chan, (const char *)buf, header_len+1);
  349. _mavlink_send_uart(chan, packet, length);
  350. _mavlink_send_uart(chan, (const char *)ck, 2);
  351. if (signature_len != 0) {
  352. _mavlink_send_uart(chan, (const char *)signature, signature_len);
  353. }
  354. MAVLINK_END_UART_SEND(chan, header_len + 3 + (uint16_t)length + (uint16_t)signature_len);
  355. }
  356. /**
  357. * @brief re-send a message over a uart channel
  358. * this is more stack efficient than re-marshalling the message
  359. * If the message is signed then the original signature is also sent
  360. */
  361. MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg)
  362. {
  363. uint8_t ck[2];
  364. ck[0] = (uint8_t)(msg->checksum & 0xFF);
  365. ck[1] = (uint8_t)(msg->checksum >> 8);
  366. // XXX use the right sequence here
  367. uint8_t header_len;
  368. uint8_t signature_len;
  369. if (msg->magic == MAVLINK_STX_MAVLINK1) {
  370. header_len = MAVLINK_CORE_HEADER_MAVLINK1_LEN + 1;
  371. signature_len = 0;
  372. MAVLINK_START_UART_SEND(chan, header_len + msg->len + 2 + signature_len);
  373. // we can't send the structure directly as it has extra mavlink2 elements in it
  374. uint8_t buf[MAVLINK_CORE_HEADER_MAVLINK1_LEN + 1];
  375. buf[0] = msg->magic;
  376. buf[1] = msg->len;
  377. buf[2] = msg->seq;
  378. buf[3] = msg->sysid;
  379. buf[4] = msg->compid;
  380. buf[5] = msg->msgid & 0xFF;
  381. _mavlink_send_uart(chan, (const char*)buf, header_len);
  382. } else {
  383. header_len = MAVLINK_CORE_HEADER_LEN + 1;
  384. signature_len = (msg->incompat_flags & MAVLINK_IFLAG_SIGNED)?MAVLINK_SIGNATURE_BLOCK_LEN:0;
  385. MAVLINK_START_UART_SEND(chan, header_len + msg->len + 2 + signature_len);
  386. uint8_t buf[MAVLINK_CORE_HEADER_LEN + 1];
  387. buf[0] = msg->magic;
  388. buf[1] = msg->len;
  389. buf[2] = msg->incompat_flags;
  390. buf[3] = msg->compat_flags;
  391. buf[4] = msg->seq;
  392. buf[5] = msg->sysid;
  393. buf[6] = msg->compid;
  394. buf[7] = msg->msgid & 0xFF;
  395. buf[8] = (msg->msgid >> 8) & 0xFF;
  396. buf[9] = (msg->msgid >> 16) & 0xFF;
  397. _mavlink_send_uart(chan, (const char *)buf, header_len);
  398. }
  399. _mavlink_send_uart(chan, _MAV_PAYLOAD(msg), msg->len);
  400. _mavlink_send_uart(chan, (const char *)ck, 2);
  401. if (signature_len != 0) {
  402. _mavlink_send_uart(chan, (const char *)msg->signature, MAVLINK_SIGNATURE_BLOCK_LEN);
  403. }
  404. MAVLINK_END_UART_SEND(chan, header_len + msg->len + 2 + signature_len);
  405. }
  406. #endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
  407. /**
  408. * @brief Pack a message to send it over a serial byte stream
  409. */
  410. MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buf, const mavlink_message_t *msg)
  411. {
  412. uint8_t signature_len, header_len;
  413. uint8_t *ck;
  414. uint8_t length = msg->len;
  415. if (msg->magic == MAVLINK_STX_MAVLINK1) {
  416. signature_len = 0;
  417. header_len = MAVLINK_CORE_HEADER_MAVLINK1_LEN;
  418. buf[0] = msg->magic;
  419. buf[1] = length;
  420. buf[2] = msg->seq;
  421. buf[3] = msg->sysid;
  422. buf[4] = msg->compid;
  423. buf[5] = msg->msgid & 0xFF;
  424. memcpy(&buf[6], _MAV_PAYLOAD(msg), msg->len);
  425. ck = buf + header_len + 1 + (uint16_t)msg->len;
  426. } else {
  427. length = _mav_trim_payload(_MAV_PAYLOAD(msg), length);
  428. header_len = MAVLINK_CORE_HEADER_LEN;
  429. buf[0] = msg->magic;
  430. buf[1] = length;
  431. buf[2] = msg->incompat_flags;
  432. buf[3] = msg->compat_flags;
  433. buf[4] = msg->seq;
  434. buf[5] = msg->sysid;
  435. buf[6] = msg->compid;
  436. buf[7] = msg->msgid & 0xFF;
  437. buf[8] = (msg->msgid >> 8) & 0xFF;
  438. buf[9] = (msg->msgid >> 16) & 0xFF;
  439. memcpy(&buf[10], _MAV_PAYLOAD(msg), length);
  440. ck = buf + header_len + 1 + (uint16_t)length;
  441. signature_len = (msg->incompat_flags & MAVLINK_IFLAG_SIGNED)?MAVLINK_SIGNATURE_BLOCK_LEN:0;
  442. }
  443. ck[0] = (uint8_t)(msg->checksum & 0xFF);
  444. ck[1] = (uint8_t)(msg->checksum >> 8);
  445. if (signature_len > 0) {
  446. memcpy(&ck[2], msg->signature, signature_len);
  447. }
  448. return header_len + 1 + 2 + (uint16_t)length + (uint16_t)signature_len;
  449. }
  450. union __mavlink_bitfield {
  451. uint8_t uint8;
  452. int8_t int8;
  453. uint16_t uint16;
  454. int16_t int16;
  455. uint32_t uint32;
  456. int32_t int32;
  457. };
  458. MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg)
  459. {
  460. uint16_t crcTmp = 0;
  461. crc_init(&crcTmp);
  462. msg->checksum = crcTmp;
  463. }
  464. MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c)
  465. {
  466. uint16_t checksum = msg->checksum;
  467. crc_accumulate(c, &checksum);
  468. msg->checksum = checksum;
  469. }
  470. /*
  471. return the crc_entry value for a msgid
  472. */
  473. #ifndef MAVLINK_GET_MSG_ENTRY
  474. MAVLINK_HELPER const mavlink_msg_entry_t *mavlink_get_msg_entry(uint32_t msgid)
  475. {
  476. static const mavlink_msg_entry_t mavlink_message_crcs[] = MAVLINK_MESSAGE_CRCS;
  477. /*
  478. use a bisection search to find the right entry. A perfect hash may be better
  479. Note that this assumes the table is sorted by msgid
  480. */
  481. uint32_t low=0, high=sizeof(mavlink_message_crcs)/sizeof(mavlink_message_crcs[0]) - 1;
  482. while (low < high) {
  483. uint32_t mid = (low+1+high)/2;
  484. if (msgid < mavlink_message_crcs[mid].msgid) {
  485. high = mid-1;
  486. continue;
  487. }
  488. if (msgid > mavlink_message_crcs[mid].msgid) {
  489. low = mid;
  490. continue;
  491. }
  492. low = mid;
  493. break;
  494. }
  495. if (mavlink_message_crcs[low].msgid != msgid) {
  496. // msgid is not in the table
  497. return NULL;
  498. }
  499. return &mavlink_message_crcs[low];
  500. }
  501. #endif // MAVLINK_GET_MSG_ENTRY
  502. /*
  503. return the crc_extra value for a message
  504. */
  505. MAVLINK_HELPER uint8_t mavlink_get_crc_extra(const mavlink_message_t *msg)
  506. {
  507. const mavlink_msg_entry_t *e = mavlink_get_msg_entry(msg->msgid);
  508. return e?e->crc_extra:0;
  509. }
  510. /*
  511. return the min message length
  512. */
  513. #define MAVLINK_HAVE_MIN_MESSAGE_LENGTH
  514. MAVLINK_HELPER uint8_t mavlink_min_message_length(const mavlink_message_t *msg)
  515. {
  516. const mavlink_msg_entry_t *e = mavlink_get_msg_entry(msg->msgid);
  517. return e?e->min_msg_len:0;
  518. }
  519. /*
  520. return the max message length (including extensions)
  521. */
  522. #define MAVLINK_HAVE_MAX_MESSAGE_LENGTH
  523. MAVLINK_HELPER uint8_t mavlink_max_message_length(const mavlink_message_t *msg)
  524. {
  525. const mavlink_msg_entry_t *e = mavlink_get_msg_entry(msg->msgid);
  526. return e?e->max_msg_len:0;
  527. }
  528. /**
  529. * This is a variant of mavlink_frame_char() but with caller supplied
  530. * parsing buffers. It is useful when you want to create a MAVLink
  531. * parser in a library that doesn't use any global variables
  532. *
  533. * @param rxmsg parsing message buffer
  534. * @param status parsing status buffer
  535. * @param c The char to parse
  536. *
  537. * @param r_message NULL if no message could be decoded, otherwise the message data
  538. * @param r_mavlink_status if a message was decoded, this is filled with the channel's stats
  539. * @return 0 if no message could be decoded, 1 on good message and CRC, 2 on bad CRC
  540. *
  541. */
  542. MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg,
  543. mavlink_status_t* status,
  544. uint8_t c,
  545. mavlink_message_t* r_message,
  546. mavlink_status_t* r_mavlink_status)
  547. {
  548. status->msg_received = MAVLINK_FRAMING_INCOMPLETE;
  549. switch (status->parse_state)
  550. {
  551. case MAVLINK_PARSE_STATE_UNINIT:
  552. case MAVLINK_PARSE_STATE_IDLE:
  553. if (c == MAVLINK_STX)
  554. {
  555. status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
  556. rxmsg->len = 0;
  557. rxmsg->magic = c;
  558. status->flags &= ~MAVLINK_STATUS_FLAG_IN_MAVLINK1;
  559. mavlink_start_checksum(rxmsg);
  560. } else if (c == MAVLINK_STX_MAVLINK1)
  561. {
  562. status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
  563. rxmsg->len = 0;
  564. rxmsg->magic = c;
  565. status->flags |= MAVLINK_STATUS_FLAG_IN_MAVLINK1;
  566. mavlink_start_checksum(rxmsg);
  567. }
  568. break;
  569. case MAVLINK_PARSE_STATE_GOT_STX:
  570. if (status->msg_received
  571. /* Support shorter buffers than the
  572. default maximum packet size */
  573. #if (MAVLINK_MAX_PAYLOAD_LEN < 255)
  574. || c > MAVLINK_MAX_PAYLOAD_LEN
  575. #endif
  576. )
  577. {
  578. status->buffer_overrun++;
  579. _mav_parse_error(status);
  580. status->msg_received = MAVLINK_FRAMING_INCOMPLETE;
  581. status->parse_state = MAVLINK_PARSE_STATE_IDLE;
  582. }
  583. else
  584. {
  585. // NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2
  586. rxmsg->len = c;
  587. status->packet_idx = 0;
  588. mavlink_update_checksum(rxmsg, c);
  589. if (status->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) {
  590. rxmsg->incompat_flags = 0;
  591. rxmsg->compat_flags = 0;
  592. status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPAT_FLAGS;
  593. } else {
  594. status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH;
  595. }
  596. }
  597. break;
  598. case MAVLINK_PARSE_STATE_GOT_LENGTH:
  599. rxmsg->incompat_flags = c;
  600. if ((rxmsg->incompat_flags & ~MAVLINK_IFLAG_MASK) != 0) {
  601. // message includes an incompatible feature flag
  602. _mav_parse_error(status);
  603. status->msg_received = MAVLINK_FRAMING_INCOMPLETE;
  604. status->parse_state = MAVLINK_PARSE_STATE_IDLE;
  605. break;
  606. }
  607. mavlink_update_checksum(rxmsg, c);
  608. status->parse_state = MAVLINK_PARSE_STATE_GOT_INCOMPAT_FLAGS;
  609. break;
  610. case MAVLINK_PARSE_STATE_GOT_INCOMPAT_FLAGS:
  611. rxmsg->compat_flags = c;
  612. mavlink_update_checksum(rxmsg, c);
  613. status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPAT_FLAGS;
  614. break;
  615. case MAVLINK_PARSE_STATE_GOT_COMPAT_FLAGS:
  616. rxmsg->seq = c;
  617. mavlink_update_checksum(rxmsg, c);
  618. status->parse_state = MAVLINK_PARSE_STATE_GOT_SEQ;
  619. break;
  620. case MAVLINK_PARSE_STATE_GOT_SEQ:
  621. rxmsg->sysid = c;
  622. mavlink_update_checksum(rxmsg, c);
  623. status->parse_state = MAVLINK_PARSE_STATE_GOT_SYSID;
  624. break;
  625. case MAVLINK_PARSE_STATE_GOT_SYSID:
  626. rxmsg->compid = c;
  627. mavlink_update_checksum(rxmsg, c);
  628. status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPID;
  629. break;
  630. case MAVLINK_PARSE_STATE_GOT_COMPID:
  631. rxmsg->msgid = c;
  632. mavlink_update_checksum(rxmsg, c);
  633. if (status->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) {
  634. if(rxmsg->len > 0) {
  635. status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID3;
  636. } else {
  637. status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD;
  638. }
  639. #ifdef MAVLINK_CHECK_MESSAGE_LENGTH
  640. if (rxmsg->len < mavlink_min_message_length(rxmsg) ||
  641. rxmsg->len > mavlink_max_message_length(rxmsg)) {
  642. _mav_parse_error(status);
  643. status->parse_state = MAVLINK_PARSE_STATE_IDLE;
  644. break;
  645. }
  646. #endif
  647. } else {
  648. status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID1;
  649. }
  650. break;
  651. case MAVLINK_PARSE_STATE_GOT_MSGID1:
  652. rxmsg->msgid |= ((uint32_t)c)<<8;
  653. mavlink_update_checksum(rxmsg, c);
  654. status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID2;
  655. break;
  656. case MAVLINK_PARSE_STATE_GOT_MSGID2:
  657. rxmsg->msgid |= ((uint32_t)c)<<16;
  658. mavlink_update_checksum(rxmsg, c);
  659. if(rxmsg->len > 0){
  660. status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID3;
  661. } else {
  662. status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD;
  663. }
  664. #ifdef MAVLINK_CHECK_MESSAGE_LENGTH
  665. if (rxmsg->len < mavlink_min_message_length(rxmsg) ||
  666. rxmsg->len > mavlink_max_message_length(rxmsg))
  667. {
  668. _mav_parse_error(status);
  669. status->parse_state = MAVLINK_PARSE_STATE_IDLE;
  670. break;
  671. }
  672. #endif
  673. break;
  674. case MAVLINK_PARSE_STATE_GOT_MSGID3:
  675. _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx++] = (char)c;
  676. mavlink_update_checksum(rxmsg, c);
  677. if (status->packet_idx == rxmsg->len)
  678. {
  679. status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD;
  680. }
  681. break;
  682. case MAVLINK_PARSE_STATE_GOT_PAYLOAD: {
  683. const mavlink_msg_entry_t *e = mavlink_get_msg_entry(rxmsg->msgid);
  684. if (e == NULL) {
  685. // Message not found in CRC_EXTRA table.
  686. status->parse_state = MAVLINK_PARSE_STATE_GOT_BAD_CRC1;
  687. rxmsg->ck[0] = c;
  688. } else {
  689. uint8_t crc_extra = e->crc_extra;
  690. mavlink_update_checksum(rxmsg, crc_extra);
  691. if (c != (rxmsg->checksum & 0xFF)) {
  692. status->parse_state = MAVLINK_PARSE_STATE_GOT_BAD_CRC1;
  693. } else {
  694. status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1;
  695. }
  696. rxmsg->ck[0] = c;
  697. // zero-fill the packet to cope with short incoming packets
  698. if (e && status->packet_idx < e->max_msg_len) {
  699. memset(&_MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx], 0, e->max_msg_len - status->packet_idx);
  700. }
  701. }
  702. break;
  703. }
  704. case MAVLINK_PARSE_STATE_GOT_CRC1:
  705. case MAVLINK_PARSE_STATE_GOT_BAD_CRC1:
  706. if (status->parse_state == MAVLINK_PARSE_STATE_GOT_BAD_CRC1 || c != (rxmsg->checksum >> 8)) {
  707. // got a bad CRC message
  708. status->msg_received = MAVLINK_FRAMING_BAD_CRC;
  709. } else {
  710. // Successfully got message
  711. status->msg_received = MAVLINK_FRAMING_OK;
  712. }
  713. rxmsg->ck[1] = c;
  714. if (rxmsg->incompat_flags & MAVLINK_IFLAG_SIGNED) {
  715. if (status->msg_received == MAVLINK_FRAMING_BAD_CRC) {
  716. // If the CRC is already wrong, don't overwrite msg_received,
  717. // otherwise we can end up with garbage flagged as valid.
  718. status->parse_state = MAVLINK_PARSE_STATE_SIGNATURE_WAIT_BAD_CRC;
  719. } else {
  720. status->parse_state = MAVLINK_PARSE_STATE_SIGNATURE_WAIT;
  721. status->msg_received = MAVLINK_FRAMING_INCOMPLETE;
  722. }
  723. status->signature_wait = MAVLINK_SIGNATURE_BLOCK_LEN;
  724. } else {
  725. if (status->signing &&
  726. (status->signing->accept_unsigned_callback == NULL ||
  727. !status->signing->accept_unsigned_callback(status, rxmsg->msgid))) {
  728. // If the CRC is already wrong, don't overwrite msg_received.
  729. if (status->msg_received != MAVLINK_FRAMING_BAD_CRC) {
  730. status->msg_received = MAVLINK_FRAMING_BAD_SIGNATURE;
  731. }
  732. }
  733. status->parse_state = MAVLINK_PARSE_STATE_IDLE;
  734. if (r_message != NULL) {
  735. memcpy(r_message, rxmsg, sizeof(mavlink_message_t));
  736. }
  737. }
  738. break;
  739. case MAVLINK_PARSE_STATE_SIGNATURE_WAIT:
  740. case MAVLINK_PARSE_STATE_SIGNATURE_WAIT_BAD_CRC:
  741. rxmsg->signature[MAVLINK_SIGNATURE_BLOCK_LEN-status->signature_wait] = c;
  742. status->signature_wait--;
  743. if (status->signature_wait == 0) {
  744. // we have the whole signature, check it is OK
  745. #ifndef MAVLINK_NO_SIGNATURE_CHECK
  746. bool sig_ok = mavlink_signature_check(status->signing, status->signing_streams, rxmsg);
  747. #else
  748. bool sig_ok = true;
  749. #endif
  750. if (!sig_ok &&
  751. (status->signing->accept_unsigned_callback &&
  752. status->signing->accept_unsigned_callback(status, rxmsg->msgid))) {
  753. // accepted via application level override
  754. sig_ok = true;
  755. }
  756. if (status->parse_state == MAVLINK_PARSE_STATE_SIGNATURE_WAIT_BAD_CRC) {
  757. status->msg_received = MAVLINK_FRAMING_BAD_CRC;
  758. } else if (sig_ok) {
  759. status->msg_received = MAVLINK_FRAMING_OK;
  760. } else {
  761. status->msg_received = MAVLINK_FRAMING_BAD_SIGNATURE;
  762. }
  763. status->parse_state = MAVLINK_PARSE_STATE_IDLE;
  764. if (r_message !=NULL) {
  765. memcpy(r_message, rxmsg, sizeof(mavlink_message_t));
  766. }
  767. }
  768. break;
  769. }
  770. // If a message has been successfully decoded, check index
  771. if (status->msg_received == MAVLINK_FRAMING_OK)
  772. {
  773. //while(status->current_seq != rxmsg->seq)
  774. //{
  775. // status->packet_rx_drop_count++;
  776. // status->current_seq++;
  777. //}
  778. status->current_rx_seq = rxmsg->seq;
  779. // Initial condition: If no packet has been received so far, drop count is undefined
  780. if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0;
  781. // Count this packet as received
  782. status->packet_rx_success_count++;
  783. }
  784. if (r_message != NULL) {
  785. r_message->len = rxmsg->len; // Provide visibility on how far we are into current msg
  786. }
  787. if (r_mavlink_status != NULL) {
  788. r_mavlink_status->parse_state = status->parse_state;
  789. r_mavlink_status->packet_idx = status->packet_idx;
  790. r_mavlink_status->current_rx_seq = status->current_rx_seq+1;
  791. r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count;
  792. r_mavlink_status->packet_rx_drop_count = status->parse_error;
  793. r_mavlink_status->flags = status->flags;
  794. }
  795. status->parse_error = 0;
  796. if (status->msg_received == MAVLINK_FRAMING_BAD_CRC) {
  797. /*
  798. the CRC came out wrong. We now need to overwrite the
  799. msg CRC with the one on the wire so that if the
  800. caller decides to forward the message anyway that
  801. mavlink_msg_to_send_buffer() won't overwrite the
  802. checksum
  803. */
  804. if (r_message != NULL) {
  805. r_message->checksum = rxmsg->ck[0] | (rxmsg->ck[1]<<8);
  806. }
  807. }
  808. return status->msg_received;
  809. }
  810. /**
  811. * This is a convenience function which handles the complete MAVLink parsing.
  812. * the function will parse one byte at a time and return the complete packet once
  813. * it could be successfully decoded. This function will return 0, 1 or
  814. * 2 (MAVLINK_FRAMING_INCOMPLETE, MAVLINK_FRAMING_OK or MAVLINK_FRAMING_BAD_CRC)
  815. *
  816. * Messages are parsed into an internal buffer (one for each channel). When a complete
  817. * message is received it is copies into *r_message and the channel's status is
  818. * copied into *r_mavlink_status.
  819. *
  820. * @param chan ID of the channel to be parsed.
  821. * A channel is not a physical message channel like a serial port, but a logical partition of
  822. * the communication streams. COMM_NB is the limit for the number of channels
  823. * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows
  824. * @param c The char to parse
  825. *
  826. * @param r_message NULL if no message could be decoded, otherwise the message data
  827. * @param r_mavlink_status if a message was decoded, this is filled with the channel's stats
  828. * @return 0 if no message could be decoded, 1 on good message and CRC, 2 on bad CRC
  829. *
  830. * A typical use scenario of this function call is:
  831. *
  832. * @code
  833. * #include <mavlink.h>
  834. *
  835. * mavlink_status_t status;
  836. * mavlink_message_t msg;
  837. * int chan = 0;
  838. *
  839. *
  840. * while(serial.bytesAvailable > 0)
  841. * {
  842. * uint8_t byte = serial.getNextByte();
  843. * if (mavlink_frame_char(chan, byte, &msg, &status) != MAVLINK_FRAMING_INCOMPLETE)
  844. * {
  845. * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid);
  846. * }
  847. * }
  848. *
  849. *
  850. * @endcode
  851. */
  852. MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status)
  853. {
  854. return mavlink_frame_char_buffer(mavlink_get_channel_buffer(chan),
  855. mavlink_get_channel_status(chan),
  856. c,
  857. r_message,
  858. r_mavlink_status);
  859. }
  860. /**
  861. * Set the protocol version
  862. */
  863. MAVLINK_HELPER void mavlink_set_proto_version(uint8_t chan, unsigned int version)
  864. {
  865. mavlink_status_t *status = mavlink_get_channel_status(chan);
  866. if (version > 1) {
  867. status->flags &= ~(MAVLINK_STATUS_FLAG_OUT_MAVLINK1);
  868. } else {
  869. status->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
  870. }
  871. }
  872. /**
  873. * Get the protocol version
  874. *
  875. * @return 1 for v1, 2 for v2
  876. */
  877. MAVLINK_HELPER unsigned int mavlink_get_proto_version(uint8_t chan)
  878. {
  879. mavlink_status_t *status = mavlink_get_channel_status(chan);
  880. if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) > 0) {
  881. return 1;
  882. } else {
  883. return 2;
  884. }
  885. }
  886. /**
  887. * This is a convenience function which handles the complete MAVLink parsing.
  888. * the function will parse one byte at a time and return the complete packet once
  889. * it could be successfully decoded. This function will return 0 or 1.
  890. *
  891. * Messages are parsed into an internal buffer (one for each channel). When a complete
  892. * message is received it is copies into *r_message and the channel's status is
  893. * copied into *r_mavlink_status.
  894. *
  895. * @param chan ID of the channel to be parsed.
  896. * A channel is not a physical message channel like a serial port, but a logical partition of
  897. * the communication streams. COMM_NB is the limit for the number of channels
  898. * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows
  899. * @param c The char to parse
  900. *
  901. * @param r_message NULL if no message could be decoded, otherwise the message data
  902. * @param r_mavlink_status if a message was decoded, this is filled with the channel's stats
  903. * @return 0 if no message could be decoded or bad CRC, 1 on good message and CRC
  904. *
  905. * A typical use scenario of this function call is:
  906. *
  907. * @code
  908. * #include <mavlink.h>
  909. *
  910. * mavlink_status_t status;
  911. * mavlink_message_t msg;
  912. * int chan = 0;
  913. *
  914. *
  915. * while(serial.bytesAvailable > 0)
  916. * {
  917. * uint8_t byte = serial.getNextByte();
  918. * if (mavlink_parse_char(chan, byte, &msg, &status))
  919. * {
  920. * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid);
  921. * }
  922. * }
  923. *
  924. *
  925. * @endcode
  926. */
  927. MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status)
  928. {
  929. uint8_t msg_received = mavlink_frame_char(chan, c, r_message, r_mavlink_status);
  930. if (msg_received == MAVLINK_FRAMING_BAD_CRC ||
  931. msg_received == MAVLINK_FRAMING_BAD_SIGNATURE) {
  932. // we got a bad CRC. Treat as a parse failure
  933. mavlink_message_t* rxmsg = mavlink_get_channel_buffer(chan);
  934. mavlink_status_t* status = mavlink_get_channel_status(chan);
  935. _mav_parse_error(status);
  936. status->msg_received = MAVLINK_FRAMING_INCOMPLETE;
  937. status->parse_state = MAVLINK_PARSE_STATE_IDLE;
  938. if (c == MAVLINK_STX)
  939. {
  940. status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
  941. rxmsg->len = 0;
  942. mavlink_start_checksum(rxmsg);
  943. }
  944. return 0;
  945. }
  946. return msg_received;
  947. }
  948. /**
  949. * @brief Put a bitfield of length 1-32 bit into the buffer
  950. *
  951. * @param b the value to add, will be encoded in the bitfield
  952. * @param bits number of bits to use to encode b, e.g. 1 for boolean, 2, 3, etc.
  953. * @param packet_index the position in the packet (the index of the first byte to use)
  954. * @param bit_index the position in the byte (the index of the first bit to use)
  955. * @param buffer packet buffer to write into
  956. * @return new position of the last used byte in the buffer
  957. */
  958. MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, uint8_t* r_bit_index, uint8_t* buffer)
  959. {
  960. uint16_t bits_remain = bits;
  961. // Transform number into network order
  962. int32_t v;
  963. uint8_t i_bit_index, i_byte_index, curr_bits_n;
  964. #if MAVLINK_NEED_BYTE_SWAP
  965. union {
  966. int32_t i;
  967. uint8_t b[4];
  968. } bin, bout;
  969. bin.i = b;
  970. bout.b[0] = bin.b[3];
  971. bout.b[1] = bin.b[2];
  972. bout.b[2] = bin.b[1];
  973. bout.b[3] = bin.b[0];
  974. v = bout.i;
  975. #else
  976. v = b;
  977. #endif
  978. // buffer in
  979. // 01100000 01000000 00000000 11110001
  980. // buffer out
  981. // 11110001 00000000 01000000 01100000
  982. // Existing partly filled byte (four free slots)
  983. // 0111xxxx
  984. // Mask n free bits
  985. // 00001111 = 2^0 + 2^1 + 2^2 + 2^3 = 2^n - 1
  986. // = ((uint32_t)(1 << n)) - 1; // = 2^n - 1
  987. // Shift n bits into the right position
  988. // out = in >> n;
  989. // Mask and shift bytes
  990. i_bit_index = bit_index;
  991. i_byte_index = packet_index;
  992. if (bit_index > 0)
  993. {
  994. // If bits were available at start, they were available
  995. // in the byte before the current index
  996. i_byte_index--;
  997. }
  998. // While bits have not been packed yet
  999. while (bits_remain > 0)
  1000. {
  1001. // Bits still have to be packed
  1002. // there can be more than 8 bits, so
  1003. // we might have to pack them into more than one byte
  1004. // First pack everything we can into the current 'open' byte
  1005. //curr_bits_n = bits_remain << 3; // Equals bits_remain mod 8
  1006. //FIXME
  1007. if (bits_remain <= (uint8_t)(8 - i_bit_index))
  1008. {
  1009. // Enough space
  1010. curr_bits_n = (uint8_t)bits_remain;
  1011. }
  1012. else
  1013. {
  1014. curr_bits_n = (8 - i_bit_index);
  1015. }
  1016. // Pack these n bits into the current byte
  1017. // Mask out whatever was at that position with ones (xxx11111)
  1018. buffer[i_byte_index] &= (0xFF >> (8 - curr_bits_n));
  1019. // Put content to this position, by masking out the non-used part
  1020. buffer[i_byte_index] |= ((0x00 << curr_bits_n) & v);
  1021. // Increment the bit index
  1022. i_bit_index += curr_bits_n;
  1023. // Now proceed to the next byte, if necessary
  1024. bits_remain -= curr_bits_n;
  1025. if (bits_remain > 0)
  1026. {
  1027. // Offer another 8 bits / one byte
  1028. i_byte_index++;
  1029. i_bit_index = 0;
  1030. }
  1031. }
  1032. *r_bit_index = i_bit_index;
  1033. // If a partly filled byte is present, mark this as consumed
  1034. if (i_bit_index != 7) i_byte_index++;
  1035. return i_byte_index - packet_index;
  1036. }
  1037. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  1038. // To make MAVLink work on your MCU, define comm_send_ch() if you wish
  1039. // to send 1 byte at a time, or MAVLINK_SEND_UART_BYTES() to send a
  1040. // whole packet at a time
  1041. /*
  1042. #include "mavlink_types.h"
  1043. void comm_send_ch(mavlink_channel_t chan, uint8_t ch)
  1044. {
  1045. if (chan == MAVLINK_COMM_0)
  1046. {
  1047. uart0_transmit(ch);
  1048. }
  1049. if (chan == MAVLINK_COMM_1)
  1050. {
  1051. uart1_transmit(ch);
  1052. }
  1053. }
  1054. */
  1055. MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len)
  1056. {
  1057. #ifdef MAVLINK_SEND_UART_BYTES
  1058. /* this is the more efficient approach, if the platform
  1059. defines it */
  1060. MAVLINK_SEND_UART_BYTES(chan, (const uint8_t *)buf, len);
  1061. #else
  1062. /* fallback to one byte at a time */
  1063. uint16_t i;
  1064. for (i = 0; i < len; i++) {
  1065. comm_send_ch(chan, (uint8_t)buf[i]);
  1066. }
  1067. #endif
  1068. }
  1069. #endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
  1070. #ifdef MAVLINK_USE_CXX_NAMESPACE
  1071. } // namespace mavlink
  1072. #endif