DroneCAN.cpp 24 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730
  1. /*
  2. DroneCAN class for handling OpenDroneID messages
  3. with thanks to David Buzz for ArduPilot ESP32 HAL
  4. */
  5. #include <Arduino.h>
  6. #include "board_config.h"
  7. #include "version.h"
  8. #include <time.h>
  9. #include "DroneCAN.h"
  10. #include "parameters.h"
  11. #include <stdarg.h>
  12. #include <canard.h>
  13. #include <uavcan.protocol.NodeStatus.h>
  14. #include <uavcan.protocol.GetNodeInfo.h>
  15. #include <uavcan.protocol.RestartNode.h>
  16. #include <uavcan.protocol.dynamic_node_id.Allocation.h>
  17. #include <uavcan.protocol.param.GetSet.h>
  18. #include <uavcan.protocol.debug.LogMessage.h>
  19. #include <dronecan.remoteid.BasicID.h>
  20. #include <dronecan.remoteid.Location.h>
  21. #include <dronecan.remoteid.SelfID.h>
  22. #include <dronecan.remoteid.System.h>
  23. #include <dronecan.remoteid.OperatorID.h>
  24. #include <dronecan.remoteid.ArmStatus.h>
  25. #ifndef CAN_BOARD_ID
  26. #define CAN_BOARD_ID 10001
  27. #endif
  28. #ifndef CAN_APP_NODE_NAME
  29. #define CAN_APP_NODE_NAME "ArduPilot RemoteIDModule"
  30. #endif
  31. #define UNUSED(x) (void)(x)
  32. static void onTransferReceived_trampoline(CanardInstance* ins, CanardRxTransfer* transfer);
  33. static bool shouldAcceptTransfer_trampoline(const CanardInstance* ins, uint64_t* out_data_type_signature, uint16_t data_type_id,
  34. CanardTransferType transfer_type,
  35. uint8_t source_node_id);
  36. // decoded messages
  37. void DroneCAN::init(void)
  38. {
  39. can_driver.init(1000000);
  40. canardInit(&canard, (uint8_t *)canard_memory_pool, sizeof(canard_memory_pool),
  41. onTransferReceived_trampoline, shouldAcceptTransfer_trampoline, NULL);
  42. if (g.can_node > 0 && g.can_node < 128) {
  43. canardSetLocalNodeID(&canard, g.can_node);
  44. }
  45. canard.user_reference = (void*)this;
  46. }
  47. void DroneCAN::update(void)
  48. {
  49. if (do_DNA()) {
  50. const uint32_t now_ms = millis();
  51. if (now_ms - last_node_status_ms >= 1000) {
  52. last_node_status_ms = now_ms;
  53. node_status_send();
  54. arm_status_send();
  55. }
  56. }
  57. processTx();
  58. processRx();
  59. }
  60. void DroneCAN::node_status_send(void)
  61. {
  62. uint8_t buffer[UAVCAN_PROTOCOL_NODESTATUS_MAX_SIZE];
  63. node_status.uptime_sec = millis() / 1000U;
  64. node_status.vendor_specific_status_code = 0;
  65. const uint16_t len = uavcan_protocol_NodeStatus_encode(&node_status, buffer);
  66. static uint8_t tx_id;
  67. canardBroadcast(&canard,
  68. UAVCAN_PROTOCOL_NODESTATUS_SIGNATURE,
  69. UAVCAN_PROTOCOL_NODESTATUS_ID,
  70. &tx_id,
  71. CANARD_TRANSFER_PRIORITY_LOW,
  72. (void*)buffer,
  73. len);
  74. }
  75. void DroneCAN::arm_status_send(void)
  76. {
  77. uint8_t buffer[DRONECAN_REMOTEID_ARMSTATUS_MAX_SIZE];
  78. dronecan_remoteid_ArmStatus arm_status {};
  79. const uint8_t status = parse_fail==nullptr?MAV_ODID_GOOD_TO_ARM:MAV_ODID_PRE_ARM_FAIL_GENERIC;
  80. const char *reason = parse_fail==nullptr?"":parse_fail;
  81. arm_status.status = status;
  82. arm_status.error.len = strlen(reason);
  83. strncpy((char*)arm_status.error.data, reason, sizeof(arm_status.error.data));
  84. const uint16_t len = dronecan_remoteid_ArmStatus_encode(&arm_status, buffer);
  85. static uint8_t tx_id;
  86. canardBroadcast(&canard,
  87. DRONECAN_REMOTEID_ARMSTATUS_SIGNATURE,
  88. DRONECAN_REMOTEID_ARMSTATUS_ID,
  89. &tx_id,
  90. CANARD_TRANSFER_PRIORITY_LOW,
  91. (void*)buffer,
  92. len);
  93. }
  94. void DroneCAN::onTransferReceived(CanardInstance* ins,
  95. CanardRxTransfer* transfer)
  96. {
  97. if (canardGetLocalNodeID(ins) == CANARD_BROADCAST_NODE_ID) {
  98. if (transfer->transfer_type == CanardTransferTypeBroadcast &&
  99. transfer->data_type_id == UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID) {
  100. handle_allocation_response(ins, transfer);
  101. }
  102. return;
  103. }
  104. const uint32_t now_ms = millis();
  105. switch (transfer->data_type_id) {
  106. case UAVCAN_PROTOCOL_GETNODEINFO_ID:
  107. handle_get_node_info(ins, transfer);
  108. break;
  109. case UAVCAN_PROTOCOL_RESTARTNODE_ID:
  110. Serial.printf("RestartNode\n");
  111. delay(20);
  112. esp_restart();
  113. break;
  114. case DRONECAN_REMOTEID_BASICID_ID:
  115. Serial.printf("Got BasicID\n");
  116. handle_BasicID(transfer);
  117. break;
  118. case DRONECAN_REMOTEID_LOCATION_ID:
  119. Serial.printf("Got Location\n");
  120. handle_Location(transfer);
  121. break;
  122. case DRONECAN_REMOTEID_SELFID_ID:
  123. Serial.printf("Got SelfID\n");
  124. handle_SelfID(transfer);
  125. break;
  126. case DRONECAN_REMOTEID_SYSTEM_ID:
  127. Serial.printf("Got System\n");
  128. handle_System(transfer);
  129. break;
  130. case DRONECAN_REMOTEID_OPERATORID_ID:
  131. Serial.printf("Got OperatorID\n");
  132. handle_OperatorID(transfer);
  133. break;
  134. case UAVCAN_PROTOCOL_PARAM_GETSET_ID:
  135. handle_param_getset(ins, transfer);
  136. break;
  137. default:
  138. //Serial.printf("reject %u\n", transfer->data_type_id);
  139. break;
  140. }
  141. }
  142. bool DroneCAN::shouldAcceptTransfer(const CanardInstance* ins,
  143. uint64_t* out_data_type_signature,
  144. uint16_t data_type_id,
  145. CanardTransferType transfer_type,
  146. uint8_t source_node_id)
  147. {
  148. if (canardGetLocalNodeID(ins) == CANARD_BROADCAST_NODE_ID &&
  149. data_type_id == UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID) {
  150. *out_data_type_signature = UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_SIGNATURE;
  151. return true;
  152. }
  153. #define ACCEPT_ID(name) case name ## _ID: *out_data_type_signature = name ## _SIGNATURE; return true
  154. switch (data_type_id) {
  155. ACCEPT_ID(UAVCAN_PROTOCOL_GETNODEINFO);
  156. ACCEPT_ID(UAVCAN_PROTOCOL_RESTARTNODE);
  157. ACCEPT_ID(DRONECAN_REMOTEID_BASICID);
  158. ACCEPT_ID(DRONECAN_REMOTEID_LOCATION);
  159. ACCEPT_ID(DRONECAN_REMOTEID_SELFID);
  160. ACCEPT_ID(DRONECAN_REMOTEID_OPERATORID);
  161. ACCEPT_ID(DRONECAN_REMOTEID_SYSTEM);
  162. ACCEPT_ID(UAVCAN_PROTOCOL_PARAM_GETSET);
  163. return true;
  164. }
  165. //Serial.printf("%u: reject ID 0x%x\n", millis(), data_type_id);
  166. return false;
  167. }
  168. static void onTransferReceived_trampoline(CanardInstance* ins,
  169. CanardRxTransfer* transfer)
  170. {
  171. DroneCAN *dc = (DroneCAN *)ins->user_reference;
  172. dc->onTransferReceived(ins, transfer);
  173. }
  174. /*
  175. see if we want to process this packet
  176. */
  177. static bool shouldAcceptTransfer_trampoline(const CanardInstance* ins,
  178. uint64_t* out_data_type_signature,
  179. uint16_t data_type_id,
  180. CanardTransferType transfer_type,
  181. uint8_t source_node_id)
  182. {
  183. DroneCAN *dc = (DroneCAN *)ins->user_reference;
  184. return dc->shouldAcceptTransfer(ins, out_data_type_signature,
  185. data_type_id,
  186. transfer_type,
  187. source_node_id);
  188. }
  189. void DroneCAN::processTx(void)
  190. {
  191. for (const CanardCANFrame* txf = NULL; (txf = canardPeekTxQueue(&canard)) != NULL;) {
  192. CANFrame txmsg {};
  193. txmsg.dlc = CANFrame::dataLengthToDlc(txf->data_len);
  194. memcpy(txmsg.data, txf->data, txf->data_len);
  195. txmsg.id = (txf->id | CANFrame::FlagEFF);
  196. // push message with 1s timeout
  197. if (can_driver.send(txmsg)) {
  198. canardPopTxQueue(&canard);
  199. tx_fail_count = 0;
  200. } else {
  201. if (tx_fail_count < 8) {
  202. tx_fail_count++;
  203. } else {
  204. canardPopTxQueue(&canard);
  205. }
  206. break;
  207. }
  208. }
  209. }
  210. void DroneCAN::processRx(void)
  211. {
  212. CANFrame rxmsg;
  213. while (can_driver.receive(rxmsg)) {
  214. CanardCANFrame rx_frame {};
  215. uint64_t timestamp = micros64();
  216. rx_frame.data_len = CANFrame::dlcToDataLength(rxmsg.dlc);
  217. memcpy(rx_frame.data, rxmsg.data, rx_frame.data_len);
  218. rx_frame.id = rxmsg.id;
  219. int err = canardHandleRxFrame(&canard, &rx_frame, timestamp);
  220. #if 0
  221. Serial.printf("%u: FX %08x %02x %02x %02x %02x %02x %02x %02x %02x (%u) -> %d\n",
  222. millis(),
  223. rx_frame.id,
  224. rxmsg.data[0], rxmsg.data[1], rxmsg.data[2], rxmsg.data[3],
  225. rxmsg.data[4], rxmsg.data[5], rxmsg.data[6], rxmsg.data[7],
  226. rx_frame.data_len,
  227. err);
  228. #else
  229. UNUSED(err);
  230. #endif
  231. }
  232. }
  233. CANFrame::CANFrame(uint32_t can_id, const uint8_t* can_data, uint8_t data_len, bool canfd_frame) :
  234. id(can_id)
  235. {
  236. if ((can_data == nullptr) || (data_len == 0) || (data_len > MaxDataLen)) {
  237. return;
  238. }
  239. memcpy(this->data, can_data, data_len);
  240. if (data_len <= 8) {
  241. dlc = data_len;
  242. } else {
  243. dlc = 8;
  244. }
  245. }
  246. uint8_t CANFrame::dataLengthToDlc(uint8_t data_length)
  247. {
  248. if (data_length <= 8) {
  249. return data_length;
  250. } else if (data_length <= 12) {
  251. return 9;
  252. } else if (data_length <= 16) {
  253. return 10;
  254. } else if (data_length <= 20) {
  255. return 11;
  256. } else if (data_length <= 24) {
  257. return 12;
  258. } else if (data_length <= 32) {
  259. return 13;
  260. } else if (data_length <= 48) {
  261. return 14;
  262. }
  263. return 15;
  264. }
  265. uint8_t CANFrame::dlcToDataLength(uint8_t dlc)
  266. {
  267. /*
  268. Data Length Code 9 10 11 12 13 14 15
  269. Number of data bytes 12 16 20 24 32 48 64
  270. */
  271. if (dlc <= 8) {
  272. return dlc;
  273. } else if (dlc == 9) {
  274. return 12;
  275. } else if (dlc == 10) {
  276. return 16;
  277. } else if (dlc == 11) {
  278. return 20;
  279. } else if (dlc == 12) {
  280. return 24;
  281. } else if (dlc == 13) {
  282. return 32;
  283. } else if (dlc == 14) {
  284. return 48;
  285. }
  286. return 64;
  287. }
  288. uint64_t DroneCAN::micros64(void)
  289. {
  290. uint32_t us = micros();
  291. if (us < last_micros32) {
  292. base_micros64 += 0x100000000ULL;
  293. }
  294. last_micros32 = us;
  295. return us + base_micros64;
  296. }
  297. /*
  298. handle a GET_NODE_INFO request
  299. */
  300. void DroneCAN::handle_get_node_info(CanardInstance* ins, CanardRxTransfer* transfer)
  301. {
  302. uint8_t buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE] {};
  303. uavcan_protocol_GetNodeInfoResponse pkt {};
  304. node_status.uptime_sec = millis() / 1000U;
  305. pkt.status = node_status;
  306. pkt.software_version.major = FW_VERSION_MAJOR;
  307. pkt.software_version.minor = FW_VERSION_MINOR;
  308. pkt.software_version.optional_field_flags = UAVCAN_PROTOCOL_SOFTWAREVERSION_OPTIONAL_FIELD_FLAG_VCS_COMMIT | UAVCAN_PROTOCOL_SOFTWAREVERSION_OPTIONAL_FIELD_FLAG_IMAGE_CRC;
  309. pkt.software_version.vcs_commit = GIT_VERSION;
  310. readUniqueID(pkt.hardware_version.unique_id);
  311. pkt.hardware_version.major = CAN_BOARD_ID >> 8;
  312. pkt.hardware_version.minor = CAN_BOARD_ID & 0xFF;
  313. snprintf((char*)pkt.name.data, sizeof(pkt.name.data), "%s", CAN_APP_NODE_NAME);
  314. pkt.name.len = strnlen((char*)pkt.name.data, sizeof(pkt.name.data));
  315. uint16_t total_size = uavcan_protocol_GetNodeInfoResponse_encode(&pkt, buffer);
  316. canardRequestOrRespond(ins,
  317. transfer->source_node_id,
  318. UAVCAN_PROTOCOL_GETNODEINFO_SIGNATURE,
  319. UAVCAN_PROTOCOL_GETNODEINFO_ID,
  320. &transfer->transfer_id,
  321. transfer->priority,
  322. CanardResponse,
  323. &buffer[0],
  324. total_size);
  325. }
  326. void DroneCAN::handle_allocation_response(CanardInstance* ins, CanardRxTransfer* transfer)
  327. {
  328. // Rule C - updating the randomized time interval
  329. send_next_node_id_allocation_request_at_ms =
  330. millis() + UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS +
  331. random(1, UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_FOLLOWUP_DELAY_MS);
  332. if (transfer->source_node_id == CANARD_BROADCAST_NODE_ID) {
  333. node_id_allocation_unique_id_offset = 0;
  334. return;
  335. }
  336. // Copying the unique ID from the message
  337. uavcan_protocol_dynamic_node_id_Allocation msg;
  338. uavcan_protocol_dynamic_node_id_Allocation_decode(transfer, &msg);
  339. // Obtaining the local unique ID
  340. uint8_t my_unique_id[sizeof(msg.unique_id.data)] {};
  341. readUniqueID(my_unique_id);
  342. // Matching the received UID against the local one
  343. if (memcmp(msg.unique_id.data, my_unique_id, msg.unique_id.len) != 0) {
  344. node_id_allocation_unique_id_offset = 0;
  345. return;
  346. }
  347. if (msg.unique_id.len < sizeof(msg.unique_id.data)) {
  348. // The allocator has confirmed part of unique ID, switching to the next stage and updating the timeout.
  349. node_id_allocation_unique_id_offset = msg.unique_id.len;
  350. send_next_node_id_allocation_request_at_ms -= UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS;
  351. } else {
  352. // Allocation complete - copying the allocated node ID from the message
  353. canardSetLocalNodeID(ins, msg.node_id);
  354. Serial.printf("Node ID allocated: %u\n", unsigned(msg.node_id));
  355. }
  356. }
  357. bool DroneCAN::do_DNA(void)
  358. {
  359. if (canardGetLocalNodeID(&canard) != CANARD_BROADCAST_NODE_ID) {
  360. return true;
  361. }
  362. const uint32_t now = millis();
  363. if (now - last_DNA_start_ms < 1000 && node_id_allocation_unique_id_offset == 0) {
  364. return false;
  365. }
  366. last_DNA_start_ms = now;
  367. uint8_t node_id_allocation_transfer_id = 0;
  368. UNUSED(node_id_allocation_transfer_id);
  369. send_next_node_id_allocation_request_at_ms =
  370. now + UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS +
  371. random(1, UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_FOLLOWUP_DELAY_MS);
  372. uint8_t allocation_request[CANARD_CAN_FRAME_MAX_DATA_LEN - 1] {};
  373. allocation_request[0] = 0;
  374. if (node_id_allocation_unique_id_offset == 0) {
  375. allocation_request[0] |= 1;
  376. }
  377. uint8_t my_unique_id[sizeof(uavcan_protocol_dynamic_node_id_Allocation::unique_id.data)] {};
  378. readUniqueID(my_unique_id);
  379. static const uint8_t MaxLenOfUniqueIDInRequest = 6;
  380. uint8_t uid_size = (uint8_t)(sizeof(uavcan_protocol_dynamic_node_id_Allocation::unique_id.data) - node_id_allocation_unique_id_offset);
  381. if (uid_size > MaxLenOfUniqueIDInRequest) {
  382. uid_size = MaxLenOfUniqueIDInRequest;
  383. }
  384. memmove(&allocation_request[1], &my_unique_id[node_id_allocation_unique_id_offset], uid_size);
  385. // Broadcasting the request
  386. static uint8_t tx_id;
  387. canardBroadcast(&canard,
  388. UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_SIGNATURE,
  389. UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID,
  390. &tx_id,
  391. CANARD_TRANSFER_PRIORITY_LOW,
  392. &allocation_request[0],
  393. (uint16_t) (uid_size + 1));
  394. node_id_allocation_unique_id_offset = 0;
  395. return false;
  396. }
  397. void DroneCAN::readUniqueID(uint8_t id[6])
  398. {
  399. esp_efuse_mac_get_default(id);
  400. }
  401. #define IMIN(a,b) ((a)<(b)?(a):(b))
  402. #define COPY_FIELD(fname) mpkt.fname = pkt.fname
  403. #define COPY_STR(fname) memcpy(mpkt.fname, pkt.fname.data, IMIN(pkt.fname.len, sizeof(mpkt.fname)))
  404. void DroneCAN::handle_BasicID(CanardRxTransfer* transfer)
  405. {
  406. dronecan_remoteid_BasicID pkt {};
  407. auto &mpkt = basic_id;
  408. dronecan_remoteid_BasicID_decode(transfer, &pkt);
  409. last_basic_id_ms = millis();
  410. memset(&mpkt, 0, sizeof(mpkt));
  411. COPY_STR(id_or_mac);
  412. COPY_FIELD(id_type);
  413. COPY_FIELD(ua_type);
  414. COPY_STR(uas_id);
  415. }
  416. void DroneCAN::handle_SelfID(CanardRxTransfer* transfer)
  417. {
  418. dronecan_remoteid_SelfID pkt {};
  419. auto &mpkt = self_id;
  420. dronecan_remoteid_SelfID_decode(transfer, &pkt);
  421. last_self_id_ms = millis();
  422. memset(&mpkt, 0, sizeof(mpkt));
  423. COPY_STR(id_or_mac);
  424. COPY_FIELD(description_type);
  425. COPY_STR(description);
  426. }
  427. void DroneCAN::handle_System(CanardRxTransfer* transfer)
  428. {
  429. dronecan_remoteid_System pkt {};
  430. auto &mpkt = system;
  431. dronecan_remoteid_System_decode(transfer, &pkt);
  432. last_system_ms = millis();
  433. memset(&mpkt, 0, sizeof(mpkt));
  434. COPY_STR(id_or_mac);
  435. COPY_FIELD(operator_location_type);
  436. COPY_FIELD(classification_type);
  437. COPY_FIELD(operator_latitude);
  438. COPY_FIELD(operator_longitude);
  439. COPY_FIELD(area_count);
  440. COPY_FIELD(area_radius);
  441. COPY_FIELD(area_ceiling);
  442. COPY_FIELD(area_floor);
  443. COPY_FIELD(category_eu);
  444. COPY_FIELD(class_eu);
  445. COPY_FIELD(operator_altitude_geo);
  446. COPY_FIELD(timestamp);
  447. }
  448. void DroneCAN::handle_OperatorID(CanardRxTransfer* transfer)
  449. {
  450. dronecan_remoteid_OperatorID pkt {};
  451. auto &mpkt = operator_id;
  452. dronecan_remoteid_OperatorID_decode(transfer, &pkt);
  453. last_operator_id_ms = millis();
  454. memset(&mpkt, 0, sizeof(mpkt));
  455. COPY_STR(id_or_mac);
  456. COPY_FIELD(operator_id_type);
  457. COPY_STR(operator_id);
  458. }
  459. void DroneCAN::handle_Location(CanardRxTransfer* transfer)
  460. {
  461. dronecan_remoteid_Location pkt {};
  462. auto &mpkt = location;
  463. dronecan_remoteid_Location_decode(transfer, &pkt);
  464. last_location_ms = millis();
  465. memset(&mpkt, 0, sizeof(mpkt));
  466. COPY_STR(id_or_mac);
  467. COPY_FIELD(status);
  468. COPY_FIELD(direction);
  469. COPY_FIELD(speed_horizontal);
  470. COPY_FIELD(speed_vertical);
  471. COPY_FIELD(latitude);
  472. COPY_FIELD(longitude);
  473. COPY_FIELD(altitude_barometric);
  474. COPY_FIELD(altitude_geodetic);
  475. COPY_FIELD(height_reference);
  476. COPY_FIELD(height);
  477. COPY_FIELD(horizontal_accuracy);
  478. COPY_FIELD(vertical_accuracy);
  479. COPY_FIELD(barometer_accuracy);
  480. COPY_FIELD(speed_accuracy);
  481. COPY_FIELD(timestamp);
  482. COPY_FIELD(timestamp_accuracy);
  483. }
  484. /*
  485. handle parameter GetSet request
  486. */
  487. void DroneCAN::handle_param_getset(CanardInstance* ins, CanardRxTransfer* transfer)
  488. {
  489. uavcan_protocol_param_GetSetRequest req;
  490. if (uavcan_protocol_param_GetSetRequest_decode(transfer, &req)) {
  491. return;
  492. }
  493. uavcan_protocol_param_GetSetResponse pkt {};
  494. const Parameters::Param *vp = nullptr;
  495. if (req.name.len != 0 && req.name.len > PARAM_NAME_MAX_LEN) {
  496. vp = nullptr;
  497. } else if (req.name.len != 0 && req.name.len <= PARAM_NAME_MAX_LEN) {
  498. memcpy((char *)pkt.name.data, (char *)req.name.data, req.name.len);
  499. vp = Parameters::find((char *)pkt.name.data);
  500. } else {
  501. vp = Parameters::find_by_index(req.index);
  502. }
  503. if (vp != nullptr && req.name.len != 0 && req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_EMPTY) {
  504. // param set
  505. switch (vp->ptype) {
  506. case Parameters::ParamType::UINT8:
  507. if (req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE) {
  508. return;
  509. }
  510. vp->set_uint8(uint8_t(req.value.integer_value));
  511. break;
  512. case Parameters::ParamType::UINT32:
  513. if (req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE) {
  514. return;
  515. }
  516. vp->set_uint32(uint32_t(req.value.integer_value));
  517. break;
  518. case Parameters::ParamType::FLOAT:
  519. if (req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE) {
  520. return;
  521. }
  522. vp->set_float(req.value.real_value);
  523. break;
  524. case Parameters::ParamType::CHAR20: {
  525. if (req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_STRING_VALUE) {
  526. return;
  527. }
  528. char v[21] {};
  529. strncpy(v, (const char *)&req.value.string_value.data[0], req.value.string_value.len);
  530. if (vp->min_len > 0 && strlen(v) < vp->min_len) {
  531. can_printf("%s too short - min %u", vp->name, vp->min_len);
  532. } else {
  533. vp->set_char20(v);
  534. }
  535. break;
  536. }
  537. case Parameters::ParamType::CHAR64: {
  538. if (req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_STRING_VALUE) {
  539. return;
  540. }
  541. char v[65] {};
  542. strncpy(v, (const char *)&req.value.string_value.data[0], req.value.string_value.len);
  543. vp->set_char64(v);
  544. break;
  545. }
  546. default:
  547. return;
  548. }
  549. }
  550. if (vp != nullptr) {
  551. switch (vp->ptype) {
  552. case Parameters::ParamType::UINT8:
  553. pkt.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE;
  554. pkt.value.integer_value = vp->get_uint8();
  555. pkt.default_value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE;
  556. pkt.default_value.integer_value = uint8_t(vp->default_value);
  557. pkt.min_value.union_tag = UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_INTEGER_VALUE;
  558. pkt.min_value.integer_value = uint8_t(vp->min_value);
  559. pkt.max_value.union_tag = UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_INTEGER_VALUE;
  560. pkt.max_value.integer_value = uint8_t(vp->max_value);
  561. break;
  562. case Parameters::ParamType::UINT32:
  563. pkt.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE;
  564. pkt.value.integer_value = vp->get_uint32();
  565. pkt.default_value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE;
  566. pkt.default_value.integer_value = uint32_t(vp->default_value);
  567. pkt.min_value.union_tag = UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_INTEGER_VALUE;
  568. pkt.min_value.integer_value = uint32_t(vp->min_value);
  569. pkt.max_value.union_tag = UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_INTEGER_VALUE;
  570. pkt.max_value.integer_value = uint32_t(vp->max_value);
  571. break;
  572. case Parameters::ParamType::FLOAT:
  573. pkt.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE;
  574. pkt.value.real_value = vp->get_float();
  575. pkt.default_value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE;
  576. pkt.default_value.real_value = vp->default_value;
  577. pkt.min_value.union_tag = UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_REAL_VALUE;
  578. pkt.min_value.real_value = vp->min_value;
  579. pkt.max_value.union_tag = UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_REAL_VALUE;
  580. pkt.max_value.real_value = vp->max_value;
  581. break;
  582. case Parameters::ParamType::CHAR20: {
  583. pkt.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_STRING_VALUE;
  584. const char *s = vp->get_char20();
  585. if (vp->flags & PARAM_FLAG_HIDDEN) {
  586. s = "********";
  587. }
  588. strncpy((char*)pkt.value.string_value.data, s, sizeof(pkt.value.string_value.data));
  589. pkt.value.string_value.len = strlen(s);
  590. break;
  591. }
  592. case Parameters::ParamType::CHAR64: {
  593. pkt.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_STRING_VALUE;
  594. const char *s = vp->get_char64();
  595. strncpy((char*)pkt.value.string_value.data, s, sizeof(pkt.value.string_value.data));
  596. pkt.value.string_value.len = strlen(s);
  597. break;
  598. }
  599. default:
  600. return;
  601. }
  602. pkt.name.len = strlen(vp->name);
  603. strncpy((char *)pkt.name.data, vp->name, sizeof(pkt.name.data));
  604. }
  605. uint8_t buffer[UAVCAN_PROTOCOL_PARAM_GETSET_RESPONSE_MAX_SIZE] {};
  606. uint16_t total_size = uavcan_protocol_param_GetSetResponse_encode(&pkt, buffer);
  607. canardRequestOrRespond(ins,
  608. transfer->source_node_id,
  609. UAVCAN_PROTOCOL_PARAM_GETSET_SIGNATURE,
  610. UAVCAN_PROTOCOL_PARAM_GETSET_ID,
  611. &transfer->transfer_id,
  612. transfer->priority,
  613. CanardResponse,
  614. &buffer[0],
  615. total_size);
  616. }
  617. // printf to CAN LogMessage for debugging
  618. void DroneCAN::can_printf(const char *fmt, ...)
  619. {
  620. uavcan_protocol_debug_LogMessage pkt {};
  621. uint8_t buffer[UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_MAX_SIZE] {};
  622. va_list ap;
  623. va_start(ap, fmt);
  624. uint32_t n = vsnprintf((char*)pkt.text.data, sizeof(pkt.text.data), fmt, ap);
  625. va_end(ap);
  626. pkt.text.len = n;
  627. if (sizeof(pkt.text.data) < n) {
  628. pkt.text.len = sizeof(pkt.text.data);
  629. }
  630. uint32_t len = uavcan_protocol_debug_LogMessage_encode(&pkt, buffer);
  631. static uint8_t tx_id;
  632. canardBroadcast(&canard,
  633. UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_SIGNATURE,
  634. UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_ID,
  635. &tx_id,
  636. CANARD_TRANSFER_PRIORITY_LOW,
  637. buffer,
  638. len);
  639. }
  640. #if 0
  641. // xprintf is useful when debugging in C code such as libcanard
  642. extern "C" {
  643. void xprintf(const char *fmt, ...);
  644. }
  645. void xprintf(const char *fmt, ...)
  646. {
  647. char buffer[200] {};
  648. va_list ap;
  649. va_start(ap, fmt);
  650. uint32_t n = vsnprintf(buffer, sizeof(buffer), fmt, ap);
  651. va_end(ap);
  652. Serial.printf("%s", buffer);
  653. }
  654. #endif