DroneCAN.cpp 17 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506
  1. /*
  2. DroneCAN class for handling OpenDroneID messages
  3. */
  4. #include <Arduino.h>
  5. #include <time.h>
  6. #include "DroneCAN.h"
  7. #include <canard.h>
  8. #include <uavcan.protocol.NodeStatus.h>
  9. #include <uavcan.protocol.GetNodeInfo.h>
  10. #include <uavcan.protocol.RestartNode.h>
  11. #include <uavcan.protocol.dynamic_node_id.Allocation.h>
  12. #include <dronecan.remoteid.BasicID.h>
  13. #include <dronecan.remoteid.Location.h>
  14. #include <dronecan.remoteid.SelfID.h>
  15. #include <dronecan.remoteid.System.h>
  16. #include <dronecan.remoteid.OperatorID.h>
  17. #include <dronecan.remoteid.ArmStatus.h>
  18. #define FW_VERSION_MAJOR 1
  19. #define FW_VERSION_MINOR 0
  20. #define BOARD_ID 10001
  21. #define CAN_APP_NODE_NAME "ArduPilot RemoteIDModule"
  22. #define CAN_DEFAULT_NODE_ID 0 // use DNA
  23. // constructor
  24. DroneCAN::DroneCAN()
  25. {}
  26. static void onTransferReceived_trampoline(CanardInstance* ins, CanardRxTransfer* transfer);
  27. static bool shouldAcceptTransfer_trampoline(const CanardInstance* ins, uint64_t* out_data_type_signature, uint16_t data_type_id,
  28. CanardTransferType transfer_type,
  29. uint8_t source_node_id);
  30. // decoded messages
  31. void DroneCAN::init(void)
  32. {
  33. can_driver.init(1000000);
  34. canardInit(&canard, (uint8_t *)canard_memory_pool, sizeof(canard_memory_pool),
  35. onTransferReceived_trampoline, shouldAcceptTransfer_trampoline, NULL);
  36. #if CAN_DEFAULT_NODE_ID
  37. canardSetLocalNodeID(&canard, CAN_DEFAULT_NODE_ID);
  38. #endif
  39. canard.user_reference = (void*)this;
  40. }
  41. void DroneCAN::update(void)
  42. {
  43. if (do_DNA()) {
  44. const uint32_t now_ms = millis();
  45. if (now_ms - last_node_status_ms >= 1000) {
  46. last_node_status_ms = now_ms;
  47. node_status_send();
  48. arm_status_send();
  49. }
  50. }
  51. processTx();
  52. processRx();
  53. }
  54. void DroneCAN::node_status_send(void)
  55. {
  56. uint8_t buffer[UAVCAN_PROTOCOL_NODESTATUS_MAX_SIZE];
  57. node_status.uptime_sec = millis() / 1000U;
  58. node_status.vendor_specific_status_code = 0;
  59. const uint16_t len = uavcan_protocol_NodeStatus_encode(&node_status, buffer);
  60. static uint8_t tx_id;
  61. Serial.printf("sending NodeStatus len=%u\n", unsigned(len));
  62. canardBroadcast(&canard,
  63. UAVCAN_PROTOCOL_NODESTATUS_SIGNATURE,
  64. UAVCAN_PROTOCOL_NODESTATUS_ID,
  65. &tx_id,
  66. CANARD_TRANSFER_PRIORITY_LOW,
  67. (void*)buffer,
  68. len);
  69. }
  70. void DroneCAN::arm_status_send(void)
  71. {
  72. uint8_t buffer[DRONECAN_REMOTEID_ARMSTATUS_MAX_SIZE];
  73. dronecan_remoteid_ArmStatus arm_status {};
  74. const uint32_t max_age_location_ms = 3000;
  75. const uint32_t max_age_other_ms = 22000;
  76. const uint32_t now_ms = millis();
  77. const char *reason = "";
  78. arm_status.status = DRONECAN_REMOTEID_ARMSTATUS_ODID_ARM_STATUS_FAIL_GENERIC;
  79. if (last_location_ms == 0 || now_ms - last_location_ms > max_age_location_ms) {
  80. reason = "missing location message";
  81. } else if (last_basic_id_ms == 0 || now_ms - last_basic_id_ms > max_age_other_ms) {
  82. reason = "missing basic_id message";
  83. } else if (last_self_id_ms == 0 || now_ms - last_self_id_ms > max_age_other_ms) {
  84. reason = "missing self_id message";
  85. } else if (last_operator_id_ms == 0 || now_ms - last_operator_id_ms > max_age_other_ms) {
  86. reason = "missing operator_id message";
  87. } else if (last_system_ms == 0 || now_ms - last_system_ms > max_age_other_ms) {
  88. reason = "missing system message";
  89. } else if (msg_Location.latitude == 0 && msg_Location.longitude == 0) {
  90. reason = "Bad location";
  91. } else if (msg_System.operator_latitude == 0 && msg_System.operator_longitude == 0) {
  92. reason = "Bad operator location";
  93. } else {
  94. arm_status.status = DRONECAN_REMOTEID_ARMSTATUS_ODID_ARM_STATUS_GOOD_TO_ARM;
  95. }
  96. arm_status.error.len = strlen(reason);
  97. strncpy((char*)arm_status.error.data, reason, sizeof(arm_status.error.data));
  98. const uint16_t len = dronecan_remoteid_ArmStatus_encode(&arm_status, buffer);
  99. static uint8_t tx_id;
  100. canardBroadcast(&canard,
  101. DRONECAN_REMOTEID_ARMSTATUS_SIGNATURE,
  102. DRONECAN_REMOTEID_ARMSTATUS_ID,
  103. &tx_id,
  104. CANARD_TRANSFER_PRIORITY_LOW,
  105. (void*)buffer,
  106. len);
  107. }
  108. void DroneCAN::onTransferReceived(CanardInstance* ins,
  109. CanardRxTransfer* transfer)
  110. {
  111. if (canardGetLocalNodeID(ins) == CANARD_BROADCAST_NODE_ID) {
  112. if (transfer->transfer_type == CanardTransferTypeBroadcast &&
  113. transfer->data_type_id == UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID) {
  114. handle_allocation_response(ins, transfer);
  115. }
  116. return;
  117. }
  118. const uint32_t now_ms = millis();
  119. switch (transfer->data_type_id) {
  120. case UAVCAN_PROTOCOL_GETNODEINFO_ID:
  121. handle_get_node_info(ins, transfer);
  122. break;
  123. case UAVCAN_PROTOCOL_RESTARTNODE_ID:
  124. Serial.printf("RestartNode\n");
  125. delay(20);
  126. esp_restart();
  127. break;
  128. case DRONECAN_REMOTEID_BASICID_ID:
  129. Serial.printf("Got BasicID\n");
  130. dronecan_remoteid_BasicID_decode(transfer, &msg_BasicID);
  131. last_basic_id_ms = now_ms;
  132. break;
  133. case DRONECAN_REMOTEID_LOCATION_ID:
  134. Serial.printf("Got Location\n");
  135. dronecan_remoteid_Location_decode(transfer, &msg_Location);
  136. last_location_ms = now_ms;
  137. break;
  138. case DRONECAN_REMOTEID_SELFID_ID:
  139. Serial.printf("Got SelfID\n");
  140. dronecan_remoteid_SelfID_decode(transfer, &msg_SelfID);
  141. last_self_id_ms = now_ms;
  142. break;
  143. case DRONECAN_REMOTEID_SYSTEM_ID:
  144. Serial.printf("Got System\n");
  145. dronecan_remoteid_System_decode(transfer, &msg_System);
  146. last_system_ms = now_ms;
  147. break;
  148. case DRONECAN_REMOTEID_OPERATORID_ID:
  149. Serial.printf("Got OperatorID\n");
  150. dronecan_remoteid_OperatorID_decode(transfer, &msg_OperatorID);
  151. last_operator_id_ms = now_ms;
  152. break;
  153. default:
  154. //Serial.printf("reject %u\n", transfer->data_type_id);
  155. break;
  156. }
  157. }
  158. bool DroneCAN::shouldAcceptTransfer(const CanardInstance* ins,
  159. uint64_t* out_data_type_signature,
  160. uint16_t data_type_id,
  161. CanardTransferType transfer_type,
  162. uint8_t source_node_id)
  163. {
  164. if (canardGetLocalNodeID(ins) == CANARD_BROADCAST_NODE_ID &&
  165. data_type_id == UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID) {
  166. *out_data_type_signature = UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_SIGNATURE;
  167. return true;
  168. }
  169. #define ACCEPT_ID(name) case name ## _ID: *out_data_type_signature = name ## _SIGNATURE; return true
  170. switch (data_type_id) {
  171. ACCEPT_ID(UAVCAN_PROTOCOL_GETNODEINFO);
  172. ACCEPT_ID(UAVCAN_PROTOCOL_RESTARTNODE);
  173. ACCEPT_ID(DRONECAN_REMOTEID_BASICID);
  174. ACCEPT_ID(DRONECAN_REMOTEID_LOCATION);
  175. ACCEPT_ID(DRONECAN_REMOTEID_SELFID);
  176. ACCEPT_ID(DRONECAN_REMOTEID_OPERATORID);
  177. ACCEPT_ID(DRONECAN_REMOTEID_SYSTEM);
  178. return true;
  179. }
  180. //Serial.printf("%u: reject ID 0x%x\n", millis(), data_type_id);
  181. return false;
  182. }
  183. static void onTransferReceived_trampoline(CanardInstance* ins,
  184. CanardRxTransfer* transfer)
  185. {
  186. DroneCAN *dc = (DroneCAN *)ins->user_reference;
  187. dc->onTransferReceived(ins, transfer);
  188. }
  189. /*
  190. see if we want to process this packet
  191. */
  192. static bool shouldAcceptTransfer_trampoline(const CanardInstance* ins,
  193. uint64_t* out_data_type_signature,
  194. uint16_t data_type_id,
  195. CanardTransferType transfer_type,
  196. uint8_t source_node_id)
  197. {
  198. DroneCAN *dc = (DroneCAN *)ins->user_reference;
  199. return dc->shouldAcceptTransfer(ins, out_data_type_signature,
  200. data_type_id,
  201. transfer_type,
  202. source_node_id);
  203. }
  204. void DroneCAN::processTx(void)
  205. {
  206. for (const CanardCANFrame* txf = NULL; (txf = canardPeekTxQueue(&canard)) != NULL;) {
  207. CANFrame txmsg {};
  208. txmsg.dlc = CANFrame::dataLengthToDlc(txf->data_len);
  209. memcpy(txmsg.data, txf->data, txf->data_len);
  210. txmsg.id = (txf->id | CANFrame::FlagEFF);
  211. // push message with 1s timeout
  212. if (can_driver.send(txmsg)) {
  213. canardPopTxQueue(&canard);
  214. tx_fail_count = 0;
  215. } else {
  216. if (tx_fail_count < 8) {
  217. tx_fail_count++;
  218. } else {
  219. canardPopTxQueue(&canard);
  220. }
  221. break;
  222. }
  223. }
  224. }
  225. void DroneCAN::processRx(void)
  226. {
  227. CANFrame rxmsg;
  228. while (can_driver.receive(rxmsg)) {
  229. CanardCANFrame rx_frame {};
  230. uint64_t timestamp = micros64();
  231. rx_frame.data_len = CANFrame::dlcToDataLength(rxmsg.dlc);
  232. memcpy(rx_frame.data, rxmsg.data, rx_frame.data_len);
  233. rx_frame.id = rxmsg.id;
  234. int err = canardHandleRxFrame(&canard, &rx_frame, timestamp);
  235. #if 0
  236. Serial.printf("%u: FX %08x %02x %02x %02x %02x %02x %02x %02x %02x (%u) -> %d\n",
  237. millis(),
  238. rx_frame.id,
  239. rxmsg.data[0], rxmsg.data[1], rxmsg.data[2], rxmsg.data[3],
  240. rxmsg.data[4], rxmsg.data[5], rxmsg.data[6], rxmsg.data[7],
  241. rx_frame.data_len,
  242. err);
  243. #endif
  244. }
  245. }
  246. CANFrame::CANFrame(uint32_t can_id, const uint8_t* can_data, uint8_t data_len, bool canfd_frame) :
  247. id(can_id)
  248. {
  249. if ((can_data == nullptr) || (data_len == 0) || (data_len > MaxDataLen)) {
  250. return;
  251. }
  252. memcpy(this->data, can_data, data_len);
  253. if (data_len <= 8) {
  254. dlc = data_len;
  255. } else {
  256. dlc = 8;
  257. }
  258. }
  259. uint8_t CANFrame::dataLengthToDlc(uint8_t data_length)
  260. {
  261. if (data_length <= 8) {
  262. return data_length;
  263. } else if (data_length <= 12) {
  264. return 9;
  265. } else if (data_length <= 16) {
  266. return 10;
  267. } else if (data_length <= 20) {
  268. return 11;
  269. } else if (data_length <= 24) {
  270. return 12;
  271. } else if (data_length <= 32) {
  272. return 13;
  273. } else if (data_length <= 48) {
  274. return 14;
  275. }
  276. return 15;
  277. }
  278. uint8_t CANFrame::dlcToDataLength(uint8_t dlc)
  279. {
  280. /*
  281. Data Length Code 9 10 11 12 13 14 15
  282. Number of data bytes 12 16 20 24 32 48 64
  283. */
  284. if (dlc <= 8) {
  285. return dlc;
  286. } else if (dlc == 9) {
  287. return 12;
  288. } else if (dlc == 10) {
  289. return 16;
  290. } else if (dlc == 11) {
  291. return 20;
  292. } else if (dlc == 12) {
  293. return 24;
  294. } else if (dlc == 13) {
  295. return 32;
  296. } else if (dlc == 14) {
  297. return 48;
  298. }
  299. return 64;
  300. }
  301. uint64_t DroneCAN::micros64(void)
  302. {
  303. uint32_t us = micros();
  304. if (us < last_micros32) {
  305. base_micros64 += 0x100000000ULL;
  306. }
  307. last_micros32 = us;
  308. return us + base_micros64;
  309. }
  310. /*
  311. handle a GET_NODE_INFO request
  312. */
  313. void DroneCAN::handle_get_node_info(CanardInstance* ins, CanardRxTransfer* transfer)
  314. {
  315. uint8_t buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE] {};
  316. uavcan_protocol_GetNodeInfoResponse pkt {};
  317. node_status.uptime_sec = millis() / 1000U;
  318. pkt.status = node_status;
  319. pkt.software_version.major = FW_VERSION_MAJOR;
  320. pkt.software_version.minor = FW_VERSION_MINOR;
  321. pkt.software_version.optional_field_flags = UAVCAN_PROTOCOL_SOFTWAREVERSION_OPTIONAL_FIELD_FLAG_VCS_COMMIT | UAVCAN_PROTOCOL_SOFTWAREVERSION_OPTIONAL_FIELD_FLAG_IMAGE_CRC;
  322. pkt.software_version.vcs_commit = 0;
  323. readUniqueID(pkt.hardware_version.unique_id);
  324. pkt.hardware_version.major = BOARD_ID >> 8;
  325. pkt.hardware_version.minor = BOARD_ID & 0xFF;
  326. snprintf((char*)pkt.name.data, sizeof(pkt.name.data), "%s", CAN_APP_NODE_NAME);
  327. pkt.name.len = strnlen((char*)pkt.name.data, sizeof(pkt.name.data));
  328. uint16_t total_size = uavcan_protocol_GetNodeInfoResponse_encode(&pkt, buffer);
  329. canardRequestOrRespond(ins,
  330. transfer->source_node_id,
  331. UAVCAN_PROTOCOL_GETNODEINFO_SIGNATURE,
  332. UAVCAN_PROTOCOL_GETNODEINFO_ID,
  333. &transfer->transfer_id,
  334. transfer->priority,
  335. CanardResponse,
  336. &buffer[0],
  337. total_size);
  338. }
  339. void DroneCAN::handle_allocation_response(CanardInstance* ins, CanardRxTransfer* transfer)
  340. {
  341. // Rule C - updating the randomized time interval
  342. send_next_node_id_allocation_request_at_ms =
  343. millis() + UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS +
  344. random(1, UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_FOLLOWUP_DELAY_MS);
  345. if (transfer->source_node_id == CANARD_BROADCAST_NODE_ID) {
  346. node_id_allocation_unique_id_offset = 0;
  347. return;
  348. }
  349. // Copying the unique ID from the message
  350. uavcan_protocol_dynamic_node_id_Allocation msg;
  351. uavcan_protocol_dynamic_node_id_Allocation_decode(transfer, &msg);
  352. // Obtaining the local unique ID
  353. uint8_t my_unique_id[sizeof(msg.unique_id.data)] {};
  354. readUniqueID(my_unique_id);
  355. // Matching the received UID against the local one
  356. if (memcmp(msg.unique_id.data, my_unique_id, msg.unique_id.len) != 0) {
  357. node_id_allocation_unique_id_offset = 0;
  358. return;
  359. }
  360. if (msg.unique_id.len < sizeof(msg.unique_id.data)) {
  361. // The allocator has confirmed part of unique ID, switching to the next stage and updating the timeout.
  362. node_id_allocation_unique_id_offset = msg.unique_id.len;
  363. send_next_node_id_allocation_request_at_ms -= UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS;
  364. } else {
  365. // Allocation complete - copying the allocated node ID from the message
  366. canardSetLocalNodeID(ins, msg.node_id);
  367. Serial.printf("Node ID allocated: %u\n", unsigned(msg.node_id));
  368. }
  369. }
  370. bool DroneCAN::do_DNA(void)
  371. {
  372. if (canardGetLocalNodeID(&canard) != CANARD_BROADCAST_NODE_ID) {
  373. return true;
  374. }
  375. const uint32_t now = millis();
  376. if (now - last_DNA_start_ms < 1000 && node_id_allocation_unique_id_offset == 0) {
  377. return false;
  378. }
  379. last_DNA_start_ms = now;
  380. uint8_t node_id_allocation_transfer_id = 0;
  381. send_next_node_id_allocation_request_at_ms =
  382. now + UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS +
  383. random(1, UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_FOLLOWUP_DELAY_MS);
  384. uint8_t allocation_request[CANARD_CAN_FRAME_MAX_DATA_LEN - 1] {};
  385. allocation_request[0] = 0;
  386. if (node_id_allocation_unique_id_offset == 0) {
  387. allocation_request[0] |= 1;
  388. }
  389. uint8_t my_unique_id[sizeof(uavcan_protocol_dynamic_node_id_Allocation::unique_id.data)] {};
  390. readUniqueID(my_unique_id);
  391. static const uint8_t MaxLenOfUniqueIDInRequest = 6;
  392. uint8_t uid_size = (uint8_t)(sizeof(uavcan_protocol_dynamic_node_id_Allocation::unique_id.data) - node_id_allocation_unique_id_offset);
  393. if (uid_size > MaxLenOfUniqueIDInRequest) {
  394. uid_size = MaxLenOfUniqueIDInRequest;
  395. }
  396. memmove(&allocation_request[1], &my_unique_id[node_id_allocation_unique_id_offset], uid_size);
  397. // Broadcasting the request
  398. static uint8_t tx_id;
  399. canardBroadcast(&canard,
  400. UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_SIGNATURE,
  401. UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID,
  402. &tx_id,
  403. CANARD_TRANSFER_PRIORITY_LOW,
  404. &allocation_request[0],
  405. (uint16_t) (uid_size + 1));
  406. node_id_allocation_unique_id_offset = 0;
  407. return false;
  408. }
  409. void DroneCAN::readUniqueID(uint8_t id[6])
  410. {
  411. esp_efuse_mac_get_default(id);
  412. }
  413. bool DroneCAN::system_valid(void)
  414. {
  415. uint32_t now_ms = millis();
  416. uint32_t max_ms = 15000;
  417. if (last_system_ms == 0 ||
  418. last_self_id_ms == 0 ||
  419. last_basic_id_ms == 0 ||
  420. last_system_ms == 0 ||
  421. last_operator_id_ms == 0) {
  422. return false;
  423. }
  424. return (now_ms - last_system_ms < max_ms &&
  425. now_ms - last_self_id_ms < max_ms &&
  426. now_ms - last_basic_id_ms < max_ms &&
  427. now_ms - last_operator_id_ms < max_ms);
  428. }
  429. bool DroneCAN::location_valid(void)
  430. {
  431. uint32_t now_ms = millis();
  432. uint32_t max_ms = 2000;
  433. return last_location_ms != 0 && now_ms - last_location_ms < max_ms;
  434. }
  435. #if 0
  436. // xprintf is useful when debugging in C code such as libcanard
  437. extern "C" {
  438. void xprintf(const char *fmt, ...);
  439. }
  440. void xprintf(const char *fmt, ...)
  441. {
  442. char buffer[200] {};
  443. va_list ap;
  444. va_start(ap, fmt);
  445. uint32_t n = vsnprintf(buffer, sizeof(buffer), fmt, ap);
  446. va_end(ap);
  447. Serial.printf("%s", buffer);
  448. }
  449. #endif