DroneCAN.cpp 17 KB

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