demo.c 19 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531
  1. /*
  2. * This demo application is distributed under the terms of CC0 (public domain dedication).
  3. * More info: https://creativecommons.org/publicdomain/zero/1.0/
  4. */
  5. // This is needed to enable necessary declarations in sys/
  6. #ifndef _GNU_SOURCE
  7. # define _GNU_SOURCE
  8. #endif
  9. #include <canard.h>
  10. #include <socketcan.h> // CAN backend driver for SocketCAN, distributed with Libcanard
  11. #include <stdio.h>
  12. #include <stdlib.h>
  13. #include <time.h>
  14. #include <string.h>
  15. #include <assert.h>
  16. #include <errno.h>
  17. /*
  18. * Application constants
  19. */
  20. #define APP_VERSION_MAJOR 1
  21. #define APP_VERSION_MINOR 0
  22. #define APP_NODE_NAME "org.uavcan.libcanard.demo"
  23. /*
  24. * Some useful constants defined by the UAVCAN specification.
  25. * Data type signature values can be easily obtained with the script show_data_type_info.py
  26. */
  27. #define UAVCAN_NODE_ID_ALLOCATION_DATA_TYPE_ID 1
  28. #define UAVCAN_NODE_ID_ALLOCATION_DATA_TYPE_SIGNATURE 0x0b2a812620a11d40
  29. #define UAVCAN_NODE_ID_ALLOCATION_RANDOM_TIMEOUT_RANGE_USEC 400000UL
  30. #define UAVCAN_NODE_ID_ALLOCATION_REQUEST_DELAY_OFFSET_USEC 600000UL
  31. #define UAVCAN_NODE_STATUS_MESSAGE_SIZE 7
  32. #define UAVCAN_NODE_STATUS_DATA_TYPE_ID 341
  33. #define UAVCAN_NODE_STATUS_DATA_TYPE_SIGNATURE 0x0f0868d0c1a7c6f1
  34. #define UAVCAN_NODE_HEALTH_OK 0
  35. #define UAVCAN_NODE_HEALTH_WARNING 1
  36. #define UAVCAN_NODE_HEALTH_ERROR 2
  37. #define UAVCAN_NODE_HEALTH_CRITICAL 3
  38. #define UAVCAN_NODE_MODE_OPERATIONAL 0
  39. #define UAVCAN_NODE_MODE_INITIALIZATION 1
  40. #define UAVCAN_GET_NODE_INFO_RESPONSE_MAX_SIZE ((3015 + 7) / 8)
  41. #define UAVCAN_GET_NODE_INFO_DATA_TYPE_SIGNATURE 0xee468a8121c46a9e
  42. #define UAVCAN_GET_NODE_INFO_DATA_TYPE_ID 1
  43. #define UNIQUE_ID_LENGTH_BYTES 16
  44. /*
  45. * Library instance.
  46. * In simple applications it makes sense to make it static, but it is not necessary.
  47. */
  48. static CanardInstance g_canard; ///< The library instance
  49. static uint8_t g_canard_memory_pool[1024]; ///< Arena for memory allocation, used by the library
  50. /*
  51. * Variables used for dynamic node ID allocation.
  52. * RTFM at http://uavcan.org/Specification/6._Application_level_functions/#dynamic-node-id-allocation
  53. */
  54. static uint64_t g_send_next_node_id_allocation_request_at; ///< When the next node ID allocation request should be sent
  55. static uint8_t g_node_id_allocation_unique_id_offset; ///< Depends on the stage of the next request
  56. /*
  57. * Node status variables
  58. */
  59. static uint8_t g_node_health = UAVCAN_NODE_HEALTH_OK;
  60. static uint8_t g_node_mode = UAVCAN_NODE_MODE_INITIALIZATION;
  61. static uint64_t getMonotonicTimestampUSec(void)
  62. {
  63. struct timespec ts;
  64. memset(&ts, 0, sizeof(ts));
  65. if (clock_gettime(CLOCK_MONOTONIC, &ts) != 0)
  66. {
  67. abort();
  68. }
  69. return (uint64_t)(ts.tv_sec * 1000000LL + ts.tv_nsec / 1000LL);
  70. }
  71. /**
  72. * Returns a pseudo random float in the range [0, 1].
  73. */
  74. static float getRandomFloat(void)
  75. {
  76. static bool initialized = false;
  77. if (!initialized) // This is not thread safe, but a race condition here is not harmful.
  78. {
  79. initialized = true;
  80. srand((uint32_t) time(NULL));
  81. }
  82. // coverity[dont_call]
  83. return (float)rand() / (float)RAND_MAX;
  84. }
  85. /**
  86. * This function uses a mock unique ID, this is not allowed in real applications!
  87. */
  88. static void readUniqueID(uint8_t* out_uid)
  89. {
  90. for (uint8_t i = 0; i < UNIQUE_ID_LENGTH_BYTES; i++)
  91. {
  92. out_uid[i] = i;
  93. }
  94. }
  95. static void makeNodeStatusMessage(uint8_t buffer[UAVCAN_NODE_STATUS_MESSAGE_SIZE])
  96. {
  97. memset(buffer, 0, UAVCAN_NODE_STATUS_MESSAGE_SIZE);
  98. static uint32_t started_at_sec = 0;
  99. if (started_at_sec == 0)
  100. {
  101. started_at_sec = (uint32_t)(getMonotonicTimestampUSec() / 1000000U);
  102. }
  103. const uint32_t uptime_sec = (uint32_t)((getMonotonicTimestampUSec() / 1000000U) - started_at_sec);
  104. /*
  105. * Here we're using the helper for demonstrational purposes; in this simple case it could be preferred to
  106. * encode the values manually.
  107. */
  108. canardEncodeScalar(buffer, 0, 32, &uptime_sec);
  109. canardEncodeScalar(buffer, 32, 2, &g_node_health);
  110. canardEncodeScalar(buffer, 34, 3, &g_node_mode);
  111. }
  112. /**
  113. * This callback is invoked by the library when a new message or request or response is received.
  114. */
  115. static void onTransferReceived(CanardInstance* ins,
  116. CanardRxTransfer* transfer)
  117. {
  118. /*
  119. * Dynamic node ID allocation protocol.
  120. * Taking this branch only if we don't have a node ID, ignoring otherwise.
  121. */
  122. if ((canardGetLocalNodeID(ins) == CANARD_BROADCAST_NODE_ID) &&
  123. (transfer->transfer_type == CanardTransferTypeBroadcast) &&
  124. (transfer->data_type_id == UAVCAN_NODE_ID_ALLOCATION_DATA_TYPE_ID))
  125. {
  126. // Rule C - updating the randomized time interval
  127. g_send_next_node_id_allocation_request_at =
  128. getMonotonicTimestampUSec() + UAVCAN_NODE_ID_ALLOCATION_REQUEST_DELAY_OFFSET_USEC +
  129. (uint64_t)(getRandomFloat() * UAVCAN_NODE_ID_ALLOCATION_RANDOM_TIMEOUT_RANGE_USEC);
  130. if (transfer->source_node_id == CANARD_BROADCAST_NODE_ID)
  131. {
  132. puts("Allocation request from another allocatee");
  133. g_node_id_allocation_unique_id_offset = 0;
  134. return;
  135. }
  136. // Copying the unique ID from the message
  137. static const uint8_t UniqueIDBitOffset = 8;
  138. uint8_t received_unique_id[UNIQUE_ID_LENGTH_BYTES];
  139. uint8_t received_unique_id_len = 0;
  140. for (; received_unique_id_len < (transfer->payload_len - (UniqueIDBitOffset / 8U)); received_unique_id_len++)
  141. {
  142. assert(received_unique_id_len < UNIQUE_ID_LENGTH_BYTES);
  143. const uint8_t bit_offset = (uint8_t)(UniqueIDBitOffset + received_unique_id_len * 8U);
  144. (void) canardDecodeScalar(transfer, bit_offset, 8, false, &received_unique_id[received_unique_id_len]);
  145. }
  146. // Obtaining the local unique ID
  147. uint8_t my_unique_id[UNIQUE_ID_LENGTH_BYTES];
  148. readUniqueID(my_unique_id);
  149. // Matching the received UID against the local one
  150. if (memcmp(received_unique_id, my_unique_id, received_unique_id_len) != 0)
  151. {
  152. printf("Mismatching allocation response from %d:", transfer->source_node_id);
  153. for (uint8_t i = 0; i < received_unique_id_len; i++)
  154. {
  155. printf(" %02x/%02x", received_unique_id[i], my_unique_id[i]);
  156. }
  157. puts("");
  158. g_node_id_allocation_unique_id_offset = 0;
  159. return; // No match, return
  160. }
  161. if (received_unique_id_len < UNIQUE_ID_LENGTH_BYTES)
  162. {
  163. // The allocator has confirmed part of unique ID, switching to the next stage and updating the timeout.
  164. g_node_id_allocation_unique_id_offset = received_unique_id_len;
  165. g_send_next_node_id_allocation_request_at -= UAVCAN_NODE_ID_ALLOCATION_REQUEST_DELAY_OFFSET_USEC;
  166. printf("Matching allocation response from %d offset %d\n",
  167. transfer->source_node_id, g_node_id_allocation_unique_id_offset);
  168. }
  169. else
  170. {
  171. // Allocation complete - copying the allocated node ID from the message
  172. uint8_t allocated_node_id = 0;
  173. (void) canardDecodeScalar(transfer, 0, 7, false, &allocated_node_id);
  174. assert(allocated_node_id <= 127);
  175. canardSetLocalNodeID(ins, allocated_node_id);
  176. printf("Node ID %d allocated by %d\n", allocated_node_id, transfer->source_node_id);
  177. }
  178. }
  179. if ((transfer->transfer_type == CanardTransferTypeRequest) &&
  180. (transfer->data_type_id == UAVCAN_GET_NODE_INFO_DATA_TYPE_ID))
  181. {
  182. printf("GetNodeInfo request from %d\n", transfer->source_node_id);
  183. uint8_t buffer[UAVCAN_GET_NODE_INFO_RESPONSE_MAX_SIZE];
  184. memset(buffer, 0, UAVCAN_GET_NODE_INFO_RESPONSE_MAX_SIZE);
  185. // NodeStatus
  186. makeNodeStatusMessage(buffer);
  187. // SoftwareVersion
  188. buffer[7] = APP_VERSION_MAJOR;
  189. buffer[8] = APP_VERSION_MINOR;
  190. buffer[9] = 1; // Optional field flags, VCS commit is set
  191. uint32_t u32 = GIT_HASH;
  192. canardEncodeScalar(buffer, 80, 32, &u32);
  193. // Image CRC skipped
  194. // HardwareVersion
  195. // Major skipped
  196. // Minor skipped
  197. readUniqueID(&buffer[24]);
  198. // Certificate of authenticity skipped
  199. // Name
  200. const size_t name_len = strlen(APP_NODE_NAME);
  201. memcpy(&buffer[41], APP_NODE_NAME, name_len);
  202. const size_t total_size = 41 + name_len;
  203. /*
  204. * Transmitting; in this case we don't have to release the payload because it's empty anyway.
  205. */
  206. const int16_t resp_res = canardRequestOrRespond(ins,
  207. transfer->source_node_id,
  208. UAVCAN_GET_NODE_INFO_DATA_TYPE_SIGNATURE,
  209. UAVCAN_GET_NODE_INFO_DATA_TYPE_ID,
  210. &transfer->transfer_id,
  211. transfer->priority,
  212. CanardResponse,
  213. &buffer[0],
  214. (uint16_t)total_size);
  215. if (resp_res <= 0)
  216. {
  217. (void)fprintf(stderr, "Could not respond to GetNodeInfo; error %d\n", resp_res);
  218. }
  219. }
  220. }
  221. /**
  222. * This callback is invoked by the library when it detects beginning of a new transfer on the bus that can be received
  223. * by the local node.
  224. * If the callback returns true, the library will receive the transfer.
  225. * If the callback returns false, the library will ignore the transfer.
  226. * All transfers that are addressed to other nodes are always ignored.
  227. */
  228. static bool shouldAcceptTransfer(const CanardInstance* ins,
  229. uint64_t* out_data_type_signature,
  230. uint16_t data_type_id,
  231. CanardTransferType transfer_type,
  232. uint8_t source_node_id)
  233. {
  234. (void)source_node_id;
  235. if (canardGetLocalNodeID(ins) == CANARD_BROADCAST_NODE_ID)
  236. {
  237. /*
  238. * If we're in the process of allocation of dynamic node ID, accept only relevant transfers.
  239. */
  240. if ((transfer_type == CanardTransferTypeBroadcast) &&
  241. (data_type_id == UAVCAN_NODE_ID_ALLOCATION_DATA_TYPE_ID))
  242. {
  243. *out_data_type_signature = UAVCAN_NODE_ID_ALLOCATION_DATA_TYPE_SIGNATURE;
  244. return true;
  245. }
  246. }
  247. else
  248. {
  249. if ((transfer_type == CanardTransferTypeRequest) &&
  250. (data_type_id == UAVCAN_GET_NODE_INFO_DATA_TYPE_ID))
  251. {
  252. *out_data_type_signature = UAVCAN_GET_NODE_INFO_DATA_TYPE_SIGNATURE;
  253. return true;
  254. }
  255. }
  256. return false;
  257. }
  258. /**
  259. * This function is called at 1 Hz rate from the main loop.
  260. */
  261. static void process1HzTasks(uint64_t timestamp_usec)
  262. {
  263. /*
  264. * Purging transfers that are no longer transmitted. This will occasionally free up some memory.
  265. */
  266. canardCleanupStaleTransfers(&g_canard, timestamp_usec);
  267. /*
  268. * Printing the memory usage statistics.
  269. */
  270. {
  271. const CanardPoolAllocatorStatistics stats = canardGetPoolAllocatorStatistics(&g_canard);
  272. const uint16_t peak_percent = (uint16_t)(100U * stats.peak_usage_blocks / stats.capacity_blocks);
  273. printf("Memory pool stats: capacity %u blocks, usage %u blocks, peak usage %u blocks (%u%%)\n",
  274. stats.capacity_blocks, stats.current_usage_blocks, stats.peak_usage_blocks, peak_percent);
  275. /*
  276. * The recommended way to establish the minimal size of the memory pool is to stress-test the application and
  277. * record the worst case memory usage.
  278. */
  279. if (peak_percent > 70)
  280. {
  281. puts("WARNING: ENLARGE MEMORY POOL");
  282. }
  283. }
  284. /*
  285. * Transmitting the node status message periodically.
  286. */
  287. {
  288. uint8_t buffer[UAVCAN_NODE_STATUS_MESSAGE_SIZE];
  289. makeNodeStatusMessage(buffer);
  290. static uint8_t transfer_id; // Note that the transfer ID variable MUST BE STATIC (or heap-allocated)!
  291. const int16_t bc_res = canardBroadcast(&g_canard,
  292. UAVCAN_NODE_STATUS_DATA_TYPE_SIGNATURE,
  293. UAVCAN_NODE_STATUS_DATA_TYPE_ID,
  294. &transfer_id,
  295. CANARD_TRANSFER_PRIORITY_LOW,
  296. buffer,
  297. UAVCAN_NODE_STATUS_MESSAGE_SIZE);
  298. if (bc_res <= 0)
  299. {
  300. (void)fprintf(stderr, "Could not broadcast node status; error %d\n", bc_res);
  301. }
  302. }
  303. g_node_mode = UAVCAN_NODE_MODE_OPERATIONAL;
  304. }
  305. /**
  306. * Transmits all frames from the TX queue, receives up to one frame.
  307. */
  308. static void processTxRxOnce(SocketCANInstance* socketcan, int32_t timeout_msec)
  309. {
  310. // Transmitting
  311. for (const CanardCANFrame* txf = NULL; (txf = canardPeekTxQueue(&g_canard)) != NULL;)
  312. {
  313. const int16_t tx_res = socketcanTransmit(socketcan, txf, 0);
  314. if (tx_res < 0) // Failure - drop the frame and report
  315. {
  316. canardPopTxQueue(&g_canard);
  317. (void)fprintf(stderr, "Transmit error %d, frame dropped, errno '%s'\n", tx_res, strerror(errno));
  318. }
  319. else if (tx_res > 0) // Success - just drop the frame
  320. {
  321. canardPopTxQueue(&g_canard);
  322. }
  323. else // Timeout - just exit and try again later
  324. {
  325. break;
  326. }
  327. }
  328. // Receiving
  329. CanardCANFrame rx_frame;
  330. const uint64_t timestamp = getMonotonicTimestampUSec();
  331. const int16_t rx_res = socketcanReceive(socketcan, &rx_frame, timeout_msec);
  332. if (rx_res < 0) // Failure - report
  333. {
  334. (void)fprintf(stderr, "Receive error %d, errno '%s'\n", rx_res, strerror(errno));
  335. }
  336. else if (rx_res > 0) // Success - process the frame
  337. {
  338. canardHandleRxFrame(&g_canard, &rx_frame, timestamp);
  339. }
  340. else
  341. {
  342. ; // Timeout - nothing to do
  343. }
  344. }
  345. int main(int argc, char** argv)
  346. {
  347. if (argc < 2)
  348. {
  349. (void)fprintf(stderr,
  350. "Usage:\n"
  351. "\t%s <can iface name>\n",
  352. argv[0]);
  353. return 1;
  354. }
  355. /*
  356. * Initializing the CAN backend driver; in this example we're using SocketCAN
  357. */
  358. SocketCANInstance socketcan;
  359. const char* const can_iface_name = argv[1];
  360. int16_t res = socketcanInit(&socketcan, can_iface_name);
  361. if (res < 0)
  362. {
  363. (void)fprintf(stderr, "Failed to open CAN iface '%s'\n", can_iface_name);
  364. return 1;
  365. }
  366. /*
  367. * Initializing the Libcanard instance.
  368. */
  369. canardInit(&g_canard,
  370. g_canard_memory_pool,
  371. sizeof(g_canard_memory_pool),
  372. onTransferReceived,
  373. shouldAcceptTransfer,
  374. NULL);
  375. /*
  376. * Performing the dynamic node ID allocation procedure.
  377. */
  378. static const uint8_t PreferredNodeID = CANARD_BROADCAST_NODE_ID; ///< This can be made configurable, obviously
  379. g_node_id_allocation_unique_id_offset = 0;
  380. uint8_t node_id_allocation_transfer_id = 0;
  381. while (canardGetLocalNodeID(&g_canard) == CANARD_BROADCAST_NODE_ID)
  382. {
  383. puts("Waiting for dynamic node ID allocation...");
  384. g_send_next_node_id_allocation_request_at =
  385. getMonotonicTimestampUSec() + UAVCAN_NODE_ID_ALLOCATION_REQUEST_DELAY_OFFSET_USEC +
  386. (uint64_t)(getRandomFloat() * UAVCAN_NODE_ID_ALLOCATION_RANDOM_TIMEOUT_RANGE_USEC);
  387. while ((getMonotonicTimestampUSec() < g_send_next_node_id_allocation_request_at) &&
  388. (canardGetLocalNodeID(&g_canard) == CANARD_BROADCAST_NODE_ID))
  389. {
  390. processTxRxOnce(&socketcan, 1);
  391. }
  392. if (canardGetLocalNodeID(&g_canard) != CANARD_BROADCAST_NODE_ID)
  393. {
  394. break;
  395. }
  396. // Structure of the request is documented in the DSDL definition
  397. // See http://uavcan.org/Specification/6._Application_level_functions/#dynamic-node-id-allocation
  398. uint8_t allocation_request[CANARD_CAN_FRAME_MAX_DATA_LEN - 1];
  399. allocation_request[0] = (uint8_t)(PreferredNodeID << 1U);
  400. if (g_node_id_allocation_unique_id_offset == 0)
  401. {
  402. allocation_request[0] |= 1; // First part of unique ID
  403. }
  404. uint8_t my_unique_id[UNIQUE_ID_LENGTH_BYTES];
  405. readUniqueID(my_unique_id);
  406. static const uint8_t MaxLenOfUniqueIDInRequest = 6;
  407. uint8_t uid_size = (uint8_t)(UNIQUE_ID_LENGTH_BYTES - g_node_id_allocation_unique_id_offset);
  408. if (uid_size > MaxLenOfUniqueIDInRequest)
  409. {
  410. uid_size = MaxLenOfUniqueIDInRequest;
  411. }
  412. // Paranoia time
  413. assert(g_node_id_allocation_unique_id_offset < UNIQUE_ID_LENGTH_BYTES);
  414. assert(uid_size <= MaxLenOfUniqueIDInRequest);
  415. assert(uid_size > 0);
  416. assert((uid_size + g_node_id_allocation_unique_id_offset) <= UNIQUE_ID_LENGTH_BYTES);
  417. memmove(&allocation_request[1], &my_unique_id[g_node_id_allocation_unique_id_offset], uid_size);
  418. // Broadcasting the request
  419. const int16_t bcast_res = canardBroadcast(&g_canard,
  420. UAVCAN_NODE_ID_ALLOCATION_DATA_TYPE_SIGNATURE,
  421. UAVCAN_NODE_ID_ALLOCATION_DATA_TYPE_ID,
  422. &node_id_allocation_transfer_id,
  423. CANARD_TRANSFER_PRIORITY_LOW,
  424. &allocation_request[0],
  425. (uint16_t) (uid_size + 1));
  426. if (bcast_res < 0)
  427. {
  428. (void)fprintf(stderr, "Could not broadcast dynamic node ID allocation request; error %d\n", bcast_res);
  429. }
  430. // Preparing for timeout; if response is received, this value will be updated from the callback.
  431. g_node_id_allocation_unique_id_offset = 0;
  432. }
  433. printf("Dynamic node ID allocation complete [%d]\n", canardGetLocalNodeID(&g_canard));
  434. /*
  435. * Running the main loop.
  436. */
  437. uint64_t next_1hz_service_at = getMonotonicTimestampUSec();
  438. for (;;)
  439. {
  440. processTxRxOnce(&socketcan, 10);
  441. const uint64_t ts = getMonotonicTimestampUSec();
  442. if (ts >= next_1hz_service_at)
  443. {
  444. next_1hz_service_at += 1000000;
  445. process1HzTasks(ts);
  446. }
  447. }
  448. return 0;
  449. }