DroneCAN.cpp 17 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503
  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 = 2200;
  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. last_basic_id_ms == 0 || now_ms - last_basic_id_ms > max_age_other_ms ||
  81. last_self_id_ms == 0 || now_ms - last_self_id_ms > max_age_other_ms ||
  82. last_operator_id_ms == 0 || now_ms - last_operator_id_ms > max_age_other_ms ||
  83. last_system_ms == 0 || now_ms - last_system_ms > max_age_other_ms) {
  84. reason = "missing ODID messages";
  85. } else if (msg_Location.latitude == 0 && msg_Location.longitude == 0) {
  86. reason = "Bad location";
  87. } else if (msg_System.operator_latitude == 0 && msg_System.operator_longitude == 0) {
  88. reason = "Bad operator location";
  89. } else {
  90. arm_status.status = DRONECAN_REMOTEID_ARMSTATUS_ODID_ARM_STATUS_GOOD_TO_ARM;
  91. }
  92. arm_status.error.len = strlen(reason);
  93. strncpy((char*)arm_status.error.data, reason, sizeof(arm_status.error.data));
  94. const uint16_t len = dronecan_remoteid_ArmStatus_encode(&arm_status, buffer);
  95. static uint8_t tx_id;
  96. canardBroadcast(&canard,
  97. DRONECAN_REMOTEID_ARMSTATUS_SIGNATURE,
  98. DRONECAN_REMOTEID_ARMSTATUS_ID,
  99. &tx_id,
  100. CANARD_TRANSFER_PRIORITY_LOW,
  101. (void*)buffer,
  102. len);
  103. }
  104. void DroneCAN::onTransferReceived(CanardInstance* ins,
  105. CanardRxTransfer* transfer)
  106. {
  107. if (canardGetLocalNodeID(ins) == CANARD_BROADCAST_NODE_ID) {
  108. if (transfer->transfer_type == CanardTransferTypeBroadcast &&
  109. transfer->data_type_id == UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID) {
  110. handle_allocation_response(ins, transfer);
  111. }
  112. return;
  113. }
  114. const uint32_t now_ms = millis();
  115. switch (transfer->data_type_id) {
  116. case UAVCAN_PROTOCOL_GETNODEINFO_ID:
  117. handle_get_node_info(ins, transfer);
  118. break;
  119. case UAVCAN_PROTOCOL_RESTARTNODE_ID:
  120. Serial.printf("RestartNode\n");
  121. delay(20);
  122. esp_restart();
  123. break;
  124. case DRONECAN_REMOTEID_BASICID_ID:
  125. Serial.printf("Got BasicID\n");
  126. dronecan_remoteid_BasicID_decode(transfer, &msg_BasicID);
  127. last_basic_id_ms = now_ms;
  128. break;
  129. case DRONECAN_REMOTEID_LOCATION_ID:
  130. Serial.printf("Got Location\n");
  131. dronecan_remoteid_Location_decode(transfer, &msg_Location);
  132. last_location_ms = now_ms;
  133. break;
  134. case DRONECAN_REMOTEID_SELFID_ID:
  135. Serial.printf("Got SelfID\n");
  136. dronecan_remoteid_SelfID_decode(transfer, &msg_SelfID);
  137. last_self_id_ms = now_ms;
  138. break;
  139. case DRONECAN_REMOTEID_SYSTEM_ID:
  140. Serial.printf("Got System\n");
  141. dronecan_remoteid_System_decode(transfer, &msg_System);
  142. last_system_ms = now_ms;
  143. break;
  144. case DRONECAN_REMOTEID_OPERATORID_ID:
  145. Serial.printf("Got OperatorID\n");
  146. dronecan_remoteid_OperatorID_decode(transfer, &msg_OperatorID);
  147. last_operator_id_ms = now_ms;
  148. break;
  149. default:
  150. //Serial.printf("reject %u\n", transfer->data_type_id);
  151. break;
  152. }
  153. }
  154. bool DroneCAN::shouldAcceptTransfer(const CanardInstance* ins,
  155. uint64_t* out_data_type_signature,
  156. uint16_t data_type_id,
  157. CanardTransferType transfer_type,
  158. uint8_t source_node_id)
  159. {
  160. if (canardGetLocalNodeID(ins) == CANARD_BROADCAST_NODE_ID &&
  161. data_type_id == UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID) {
  162. *out_data_type_signature = UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_SIGNATURE;
  163. return true;
  164. }
  165. #define ACCEPT_ID(name) case name ## _ID: *out_data_type_signature = name ## _SIGNATURE; return true
  166. switch (data_type_id) {
  167. ACCEPT_ID(UAVCAN_PROTOCOL_GETNODEINFO);
  168. ACCEPT_ID(UAVCAN_PROTOCOL_RESTARTNODE);
  169. ACCEPT_ID(DRONECAN_REMOTEID_BASICID);
  170. ACCEPT_ID(DRONECAN_REMOTEID_LOCATION);
  171. ACCEPT_ID(DRONECAN_REMOTEID_SELFID);
  172. ACCEPT_ID(DRONECAN_REMOTEID_OPERATORID);
  173. ACCEPT_ID(DRONECAN_REMOTEID_SYSTEM);
  174. return true;
  175. }
  176. //Serial.printf("%u: reject ID 0x%x\n", millis(), data_type_id);
  177. return false;
  178. }
  179. static void onTransferReceived_trampoline(CanardInstance* ins,
  180. CanardRxTransfer* transfer)
  181. {
  182. DroneCAN *dc = (DroneCAN *)ins->user_reference;
  183. dc->onTransferReceived(ins, transfer);
  184. }
  185. /*
  186. see if we want to process this packet
  187. */
  188. static bool shouldAcceptTransfer_trampoline(const CanardInstance* ins,
  189. uint64_t* out_data_type_signature,
  190. uint16_t data_type_id,
  191. CanardTransferType transfer_type,
  192. uint8_t source_node_id)
  193. {
  194. DroneCAN *dc = (DroneCAN *)ins->user_reference;
  195. return dc->shouldAcceptTransfer(ins, out_data_type_signature,
  196. data_type_id,
  197. transfer_type,
  198. source_node_id);
  199. }
  200. void DroneCAN::processTx(void)
  201. {
  202. for (const CanardCANFrame* txf = NULL; (txf = canardPeekTxQueue(&canard)) != NULL;) {
  203. CANFrame txmsg {};
  204. txmsg.dlc = CANFrame::dataLengthToDlc(txf->data_len);
  205. memcpy(txmsg.data, txf->data, txf->data_len);
  206. txmsg.id = (txf->id | CANFrame::FlagEFF);
  207. // push message with 1s timeout
  208. if (can_driver.send(txmsg)) {
  209. canardPopTxQueue(&canard);
  210. tx_fail_count = 0;
  211. } else {
  212. Serial.printf("can send fail\n");
  213. if (tx_fail_count < 8) {
  214. tx_fail_count++;
  215. } else {
  216. canardPopTxQueue(&canard);
  217. }
  218. break;
  219. }
  220. }
  221. }
  222. void DroneCAN::processRx(void)
  223. {
  224. CANFrame rxmsg;
  225. while (can_driver.receive(rxmsg)) {
  226. CanardCANFrame rx_frame {};
  227. uint64_t timestamp = micros64();
  228. rx_frame.data_len = CANFrame::dlcToDataLength(rxmsg.dlc);
  229. memcpy(rx_frame.data, rxmsg.data, rx_frame.data_len);
  230. rx_frame.id = rxmsg.id;
  231. int err = canardHandleRxFrame(&canard, &rx_frame, timestamp);
  232. #if 0
  233. Serial.printf("%u: FX %08x %02x %02x %02x %02x %02x %02x %02x %02x (%u) -> %d\n",
  234. millis(),
  235. rx_frame.id,
  236. rxmsg.data[0], rxmsg.data[1], rxmsg.data[2], rxmsg.data[3],
  237. rxmsg.data[4], rxmsg.data[5], rxmsg.data[6], rxmsg.data[7],
  238. rx_frame.data_len,
  239. 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 = 0;
  320. readUniqueID(pkt.hardware_version.unique_id);
  321. pkt.hardware_version.major = BOARD_ID >> 8;
  322. pkt.hardware_version.minor = 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. send_next_node_id_allocation_request_at_ms =
  379. now + UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS +
  380. random(1, UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_FOLLOWUP_DELAY_MS);
  381. uint8_t allocation_request[CANARD_CAN_FRAME_MAX_DATA_LEN - 1] {};
  382. allocation_request[0] = 0;
  383. if (node_id_allocation_unique_id_offset == 0) {
  384. allocation_request[0] |= 1;
  385. }
  386. uint8_t my_unique_id[sizeof(uavcan_protocol_dynamic_node_id_Allocation::unique_id.data)] {};
  387. readUniqueID(my_unique_id);
  388. static const uint8_t MaxLenOfUniqueIDInRequest = 6;
  389. uint8_t uid_size = (uint8_t)(sizeof(uavcan_protocol_dynamic_node_id_Allocation::unique_id.data) - node_id_allocation_unique_id_offset);
  390. if (uid_size > MaxLenOfUniqueIDInRequest) {
  391. uid_size = MaxLenOfUniqueIDInRequest;
  392. }
  393. memmove(&allocation_request[1], &my_unique_id[node_id_allocation_unique_id_offset], uid_size);
  394. // Broadcasting the request
  395. static uint8_t tx_id;
  396. canardBroadcast(&canard,
  397. UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_SIGNATURE,
  398. UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID,
  399. &tx_id,
  400. CANARD_TRANSFER_PRIORITY_LOW,
  401. &allocation_request[0],
  402. (uint16_t) (uid_size + 1));
  403. node_id_allocation_unique_id_offset = 0;
  404. return false;
  405. }
  406. void DroneCAN::readUniqueID(uint8_t id[6])
  407. {
  408. esp_efuse_mac_get_default(id);
  409. }
  410. bool DroneCAN::system_valid(void)
  411. {
  412. uint32_t now_ms = millis();
  413. uint32_t max_ms = 15000;
  414. if (last_system_ms == 0 ||
  415. last_self_id_ms == 0 ||
  416. last_basic_id_ms == 0 ||
  417. last_system_ms == 0 ||
  418. last_operator_id_ms == 0) {
  419. return false;
  420. }
  421. return (now_ms - last_system_ms < max_ms &&
  422. now_ms - last_self_id_ms < max_ms &&
  423. now_ms - last_basic_id_ms < max_ms &&
  424. now_ms - last_operator_id_ms < max_ms);
  425. }
  426. bool DroneCAN::location_valid(void)
  427. {
  428. uint32_t now_ms = millis();
  429. uint32_t max_ms = 2000;
  430. return last_location_ms != 0 && now_ms - last_location_ms < max_ms;
  431. }
  432. #if 0
  433. // xprintf is useful when debugging in C code such as libcanard
  434. extern "C" {
  435. void xprintf(const char *fmt, ...);
  436. }
  437. void xprintf(const char *fmt, ...)
  438. {
  439. char buffer[200] {};
  440. va_list ap;
  441. va_start(ap, fmt);
  442. uint32_t n = vsnprintf(buffer, sizeof(buffer), fmt, ap);
  443. va_end(ap);
  444. Serial.printf("%s", buffer);
  445. }
  446. #endif