DroneCAN.cpp 28 KB

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