DroneCAN.cpp 28 KB

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