test_node.hpp 7.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270
  1. /*
  2. * Copyright (C) 2014 Pavel Kirienko <pavel.kirienko@gmail.com>
  3. */
  4. #pragma once
  5. #if __GNUC__
  6. // We need auto_ptr for compatibility reasons
  7. # pragma GCC diagnostic ignored "-Wdeprecated-declarations"
  8. # pragma GCC diagnostic ignored "-Wzero-as-null-pointer-constant"
  9. #endif
  10. #include <uavcan/node/abstract_node.hpp>
  11. #include <uavcan/helpers/heap_based_pool_allocator.hpp>
  12. #include <memory>
  13. #include <set>
  14. #include <queue>
  15. #include "../transport/can/can.hpp"
  16. #include <uavcan/util/method_binder.hpp>
  17. #include <uavcan/node/subscriber.hpp>
  18. struct TestNode : public uavcan::INode
  19. {
  20. /*
  21. * This class used to use the simple pool allocator instead:
  22. * uavcan::PoolAllocator<uavcan::MemPoolBlockSize * 1024, uavcan::MemPoolBlockSize> pool;
  23. * It has been replaced because unlike the simple allocator, heap-based one is not tested as extensively.
  24. * Moreover, heap based allocator prints and error message upon destruction if some memory has not been freed.
  25. */
  26. uavcan::HeapBasedPoolAllocator<uavcan::MemPoolBlockSize> pool;
  27. uavcan::Scheduler scheduler;
  28. uint64_t internal_failure_count;
  29. TestNode(uavcan::ICanDriver& can_driver, uavcan::ISystemClock& clock_driver, uavcan::NodeID self_node_id) :
  30. pool(1024),
  31. scheduler(can_driver, pool, clock_driver),
  32. internal_failure_count(0)
  33. {
  34. setNodeID(self_node_id);
  35. }
  36. virtual void registerInternalFailure(const char* msg)
  37. {
  38. std::cout << "TestNode internal failure: " << msg << std::endl;
  39. internal_failure_count++;
  40. }
  41. virtual uavcan::IPoolAllocator& getAllocator() { return pool; }
  42. virtual uavcan::Scheduler& getScheduler() { return scheduler; }
  43. virtual const uavcan::Scheduler& getScheduler() const { return scheduler; }
  44. };
  45. struct PairableCanDriver : public uavcan::ICanDriver, public uavcan::ICanIface
  46. {
  47. uavcan::ISystemClock& clock;
  48. std::set<PairableCanDriver*> others;
  49. std::queue<uavcan::CanFrame> read_queue;
  50. std::queue<uavcan::CanFrame> loopback_queue;
  51. uint64_t error_count;
  52. PairableCanDriver(uavcan::ISystemClock& clock)
  53. : clock(clock)
  54. , error_count(0)
  55. { }
  56. void linkTogether(PairableCanDriver* with)
  57. {
  58. this->others.insert(with);
  59. with->others.insert(this);
  60. others.erase(this);
  61. }
  62. virtual uavcan::ICanIface* getIface(uavcan::uint8_t iface_index)
  63. {
  64. return (iface_index == 0) ? this : UAVCAN_NULLPTR;
  65. }
  66. virtual const uavcan::ICanIface* getIface(uavcan::uint8_t iface_index) const
  67. {
  68. return (iface_index == 0) ? this : UAVCAN_NULLPTR;
  69. }
  70. virtual uavcan::uint8_t getNumIfaces() const { return 1; }
  71. virtual uavcan::int16_t select(uavcan::CanSelectMasks& inout_masks,
  72. const uavcan::CanFrame* (&)[uavcan::MaxCanIfaces],
  73. uavcan::MonotonicTime blocking_deadline)
  74. {
  75. if (inout_masks.read == 1)
  76. {
  77. inout_masks.read = (!read_queue.empty() || !loopback_queue.empty()) ? 1 : 0;
  78. }
  79. if (inout_masks.read || inout_masks.write)
  80. {
  81. return 1;
  82. }
  83. while (clock.getMonotonic() < blocking_deadline)
  84. {
  85. usleep(1000);
  86. }
  87. return 0;
  88. }
  89. virtual uavcan::int16_t send(const uavcan::CanFrame& frame, uavcan::MonotonicTime, uavcan::CanIOFlags flags)
  90. {
  91. assert(!others.empty());
  92. for (std::set<PairableCanDriver*>::iterator it = others.begin(); it != others.end(); ++it)
  93. {
  94. (*it)->read_queue.push(frame);
  95. }
  96. if (flags & uavcan::CanIOFlagLoopback)
  97. {
  98. loopback_queue.push(frame);
  99. }
  100. return 1;
  101. }
  102. virtual uavcan::int16_t receive(uavcan::CanFrame& out_frame, uavcan::MonotonicTime& out_ts_monotonic,
  103. uavcan::UtcTime& out_ts_utc, uavcan::CanIOFlags& out_flags)
  104. {
  105. out_flags = 0;
  106. if (loopback_queue.empty())
  107. {
  108. assert(read_queue.size());
  109. out_frame = read_queue.front();
  110. read_queue.pop();
  111. }
  112. else
  113. {
  114. out_flags |= uavcan::CanIOFlagLoopback;
  115. out_frame = loopback_queue.front();
  116. loopback_queue.pop();
  117. }
  118. out_ts_monotonic = clock.getMonotonic();
  119. out_ts_utc = clock.getUtc();
  120. return 1;
  121. }
  122. void pushRxToAllIfaces(const uavcan::CanFrame& can_frame)
  123. {
  124. read_queue.push(can_frame);
  125. }
  126. virtual uavcan::int16_t configureFilters(const uavcan::CanFilterConfig*, uavcan::uint16_t) { return -1; }
  127. virtual uavcan::uint16_t getNumFilters() const { return 0; }
  128. virtual uavcan::uint64_t getErrorCount() const { return error_count; }
  129. };
  130. template <typename ClockType>
  131. struct InterlinkedTestNodes
  132. {
  133. ClockType clock_a;
  134. ClockType clock_b;
  135. PairableCanDriver can_a;
  136. PairableCanDriver can_b;
  137. TestNode a;
  138. TestNode b;
  139. InterlinkedTestNodes(uavcan::NodeID nid_first, uavcan::NodeID nid_second)
  140. : can_a(clock_a)
  141. , can_b(clock_b)
  142. , a(can_a, clock_a, nid_first)
  143. , b(can_b, clock_b, nid_second)
  144. {
  145. can_a.linkTogether(&can_b);
  146. }
  147. InterlinkedTestNodes()
  148. : can_a(clock_a)
  149. , can_b(clock_b)
  150. , a(can_a, clock_a, 1)
  151. , b(can_b, clock_b, 2)
  152. {
  153. can_a.linkTogether(&can_b);
  154. }
  155. int spinBoth(uavcan::MonotonicDuration duration)
  156. {
  157. assert(!duration.isNegative());
  158. unsigned nspins2 = unsigned(duration.toMSec() / 2);
  159. nspins2 = nspins2 ? nspins2 : 1;
  160. while (nspins2 --> 0)
  161. {
  162. int ret = a.spin(uavcan::MonotonicDuration::fromMSec(1));
  163. if (ret < 0)
  164. {
  165. return ret;
  166. }
  167. ret = b.spin(uavcan::MonotonicDuration::fromMSec(1));
  168. if (ret < 0)
  169. {
  170. return ret;
  171. }
  172. }
  173. return 0;
  174. }
  175. };
  176. typedef InterlinkedTestNodes<SystemClockDriver> InterlinkedTestNodesWithSysClock;
  177. typedef InterlinkedTestNodes<SystemClockMock> InterlinkedTestNodesWithClockMock;
  178. template <unsigned NumNodes>
  179. struct TestNetwork
  180. {
  181. struct NodeEnvironment
  182. {
  183. SystemClockDriver clock;
  184. PairableCanDriver can_driver;
  185. TestNode node;
  186. NodeEnvironment(uavcan::NodeID node_id)
  187. : can_driver(clock)
  188. , node(can_driver, clock, node_id)
  189. { }
  190. };
  191. std::auto_ptr<NodeEnvironment> nodes[NumNodes];
  192. TestNetwork(uavcan::uint8_t first_node_id = 1)
  193. {
  194. for (uavcan::uint8_t i = 0; i < NumNodes; i++)
  195. {
  196. nodes[i].reset(new NodeEnvironment(uint8_t(first_node_id + i)));
  197. }
  198. for (uavcan::uint8_t i = 0; i < NumNodes; i++)
  199. {
  200. for (uavcan::uint8_t k = 0; k < NumNodes; k++)
  201. {
  202. nodes[i]->can_driver.linkTogether(&nodes[k]->can_driver);
  203. }
  204. }
  205. for (uavcan::uint8_t i = 0; i < NumNodes; i++)
  206. {
  207. assert(nodes[i]->can_driver.others.size() == (NumNodes - 1));
  208. }
  209. }
  210. int spinAll(uavcan::MonotonicDuration duration)
  211. {
  212. assert(!duration.isNegative());
  213. unsigned nspins = unsigned(duration.toMSec() / NumNodes);
  214. nspins = nspins ? nspins : 1;
  215. while (nspins --> 0)
  216. {
  217. for (uavcan::uint8_t i = 0; i < NumNodes; i++)
  218. {
  219. int ret = nodes[i]->node.spin(uavcan::MonotonicDuration::fromMSec(1));
  220. if (ret < 0)
  221. {
  222. return ret;
  223. }
  224. }
  225. }
  226. return 0;
  227. }
  228. TestNode& operator[](unsigned index)
  229. {
  230. if (index >= NumNodes)
  231. {
  232. throw std::out_of_range("No such test node");
  233. }
  234. return nodes[index]->node;
  235. }
  236. };