mavlink_helpers.h 37 KB

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