DroneCAN.cpp 16 KB

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