DroneCAN.cpp 21 KB

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