DroneCAN.cpp 22 KB

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