DroneCAN.cpp 13 KB

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