DroneCAN.cpp 15 KB

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