test_generic_lazy_pubsub.cpp
Go to the documentation of this file.
1 
9 #include "gtest/gtest.h"
10 
11 // HACK: we need to access TopicManager::subscriptions_
12 #define private public
13 #include <ros/topic_manager.h>
14 #undef private
15 
16 #include <memory>
17 #include <string>
18 
19 #include <ros/ros.h>
20 #include <ros/subscription.h>
21 #include <std_msgs/Header.h>
22 
25 
26 void spin(double duration, double wait)
27 {
28  double waited = 0;
29  while (waited < duration)
30  {
31  ros::spinOnce();
33  waited += wait;
34  }
35 }
36 
37 void spin(double duration)
38 {
39  spin(duration, duration / 1000.0);
40 }
41 
42 size_t getNumSubscriptions(const std::string& topic)
43 {
44  size_t num = 0;
45  auto subs = ros::TopicManager::instance()->subscriptions_;
46  for (const auto& sub : subs)
47  {
48  if (sub->getName() == topic)
49  {
50  num += sub->getNumCallbacks();
51  }
52  }
53  return num;
54 }
55 
57 {
58 public:
59  TestLazyPubSub(const ::std::string& topicIn, const ::std::string& topicOut, const ::ros::NodeHandle& nh = {},
60  const size_t inQueueSize = 10, const size_t outQueueSize = 10) :
63  {
64  }
65 
67  {
68  return this->pub;
69  }
70 
72  {
73  return this->sub;
74  }
75 
76 protected:
78  {
79  pub.publish(event.getConstMessage());
80  this->numProcessed++;
81  }
82 
83 public:
85  size_t numProcessed {0};
86 };
87 
88 TEST(GenericLazyPubSub, OverallTest) // NOLINT
89 {
90  ros::NodeHandle pnh({"test"}, "test1");
91  const auto ns = pnh.getNamespace();
92  auto inPub = pnh.advertise<std_msgs::Header>("in", 10);
93 
94  size_t numOutReceived = 0;
95 
96  spin(0.1);
97  EXPECT_EQ(0, inPub.getNumSubscribers());
98  EXPECT_EQ(0, getNumSubscriptions(ns + "/in"));
99 
100  boost::function<void(const std_msgs::Header&)> outCb = [&](const std_msgs::Header& h)
101  {
102  ++numOutReceived;
103  };
104 
105  auto lazySub = std::make_unique<TestLazyPubSub>("in", "out", pnh);
106 
107  spin(0.1);
108  EXPECT_EQ(0, lazySub->numProcessed);
109  EXPECT_FALSE(lazySub->getPub());
110  EXPECT_EQ(1, inPub.getNumSubscribers());
111  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
112  EXPECT_EQ(true, lazySub->isSubscribed());
113 
114  {
115  auto outSub = pnh.subscribe<std_msgs::Header>("out", 10, outCb);
116 
117  spin(0.1);
118  EXPECT_EQ(0, lazySub->numProcessed);
119  EXPECT_EQ(0, numOutReceived);
120  EXPECT_FALSE(lazySub->getPub());
121  EXPECT_EQ(1, inPub.getNumSubscribers());
122  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
123  EXPECT_EQ(1, getNumSubscriptions(ns + "/out"));
124  EXPECT_EQ(true, lazySub->isSubscribed());
125 
126  inPub.publish(std_msgs::Header());
127 
128  spin(0.2);
129  EXPECT_EQ(1, lazySub->numProcessed);
130  EXPECT_EQ(1, numOutReceived);
131  ASSERT_TRUE(lazySub->getPub());
132  EXPECT_EQ(1, lazySub->getPub().getNumSubscribers());
133  EXPECT_EQ(1, inPub.getNumSubscribers());
134  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
135  EXPECT_EQ(1, getNumSubscriptions(ns + "/out"));
136  EXPECT_EQ(true, lazySub->isSubscribed());
137  }
138 
139  spin(0.1);
140  EXPECT_EQ(1, lazySub->numProcessed);
141  EXPECT_EQ(1, numOutReceived);
142  ASSERT_TRUE(lazySub->getPub());
143  EXPECT_EQ(0, lazySub->getPub().getNumSubscribers());
144  EXPECT_EQ(0, inPub.getNumSubscribers());
145  EXPECT_EQ(0, getNumSubscriptions(ns + "/in"));
146  EXPECT_EQ(0, getNumSubscriptions(ns + "/out"));
147  EXPECT_EQ(false, lazySub->isSubscribed());
148 
149  inPub.publish(std_msgs::Header());
150 
151  spin(0.1);
152  EXPECT_EQ(1, lazySub->numProcessed);
153  EXPECT_EQ(1, numOutReceived);
154  ASSERT_TRUE(lazySub->getPub());
155  EXPECT_EQ(0, lazySub->getPub().getNumSubscribers());
156  EXPECT_EQ(0, inPub.getNumSubscribers());
157  EXPECT_EQ(0, getNumSubscriptions(ns + "/in"));
158  EXPECT_EQ(0, getNumSubscriptions(ns + "/out"));
159  EXPECT_EQ(false, lazySub->isSubscribed());
160 
161  {
162  auto outSub = pnh.subscribe<std_msgs::Header>("out", 10, outCb);
163  auto outSub2 = pnh.subscribe<std_msgs::Header>("out", 10, outCb);
164 
165  spin(0.1);
166  EXPECT_EQ(1, lazySub->numProcessed);
167  EXPECT_EQ(1, numOutReceived);
168  ASSERT_TRUE(lazySub->getPub());
169  EXPECT_EQ(1, lazySub->getPub().getNumSubscribers());
170  EXPECT_EQ(1, inPub.getNumSubscribers());
171  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
172  EXPECT_EQ(2, getNumSubscriptions(ns + "/out"));
173  EXPECT_EQ(true, lazySub->isSubscribed());
174 
175  // Simulate connection from a second node; this can't be done from within a single executable.
176  // This should not have any effect as we're only interested in the first or last subscriber.
177  lazySub->updateSubscription();
178 
179  spin(0.1);
180  EXPECT_EQ(1, lazySub->numProcessed);
181  EXPECT_EQ(1, numOutReceived);
182  ASSERT_TRUE(lazySub->getPub());
183  EXPECT_EQ(1, lazySub->getPub().getNumSubscribers());
184  EXPECT_EQ(1, inPub.getNumSubscribers());
185  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
186  EXPECT_EQ(2, getNumSubscriptions(ns + "/out"));
187  EXPECT_EQ(true, lazySub->isSubscribed());
188 
189  inPub.publish(std_msgs::Header());
190  inPub.publish(std_msgs::Header());
191 
192  spin(0.1);
193  EXPECT_EQ(3, lazySub->numProcessed);
194  EXPECT_EQ(5, numOutReceived);
195  ASSERT_TRUE(lazySub->getPub());
196  EXPECT_EQ(1, lazySub->getPub().getNumSubscribers());
197  EXPECT_EQ(1, inPub.getNumSubscribers());
198  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
199  EXPECT_EQ(2, getNumSubscriptions(ns + "/out"));
200  EXPECT_EQ(true, lazySub->isSubscribed());
201  }
202 
203  spin(0.1);
204  EXPECT_EQ(3, lazySub->numProcessed);
205  EXPECT_EQ(5, numOutReceived);
206  ASSERT_TRUE(lazySub->getPub());
207  EXPECT_EQ(0, lazySub->getPub().getNumSubscribers());
208  EXPECT_EQ(0, inPub.getNumSubscribers());
209  EXPECT_EQ(0, getNumSubscriptions(ns + "/in"));
210  EXPECT_EQ(0, getNumSubscriptions(ns + "/out"));
211  EXPECT_EQ(false, lazySub->isSubscribed());
212 
213  inPub.publish(std_msgs::Header());
214  inPub.publish(std_msgs::Header());
215  inPub.publish(std_msgs::Header());
216 
217  spin(0.1);
218  EXPECT_EQ(3, lazySub->numProcessed);
219  EXPECT_EQ(5, numOutReceived);
220  EXPECT_EQ(0, lazySub->getPub().getNumSubscribers());
221  EXPECT_EQ(0, inPub.getNumSubscribers());
222  EXPECT_EQ(0, getNumSubscriptions(ns + "/in"));
223  EXPECT_EQ(0, getNumSubscriptions(ns + "/out"));
224  EXPECT_EQ(false, lazySub->isSubscribed());
225 
226  {
227  auto outSub = pnh.subscribe<std_msgs::Header>("out", 10, outCb);
228 
229  spin(0.1);
230  EXPECT_EQ(3, lazySub->numProcessed);
231  EXPECT_EQ(5, numOutReceived);
232  EXPECT_EQ(1, lazySub->getPub().getNumSubscribers());
233  EXPECT_EQ(1, inPub.getNumSubscribers());
234  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
235  EXPECT_EQ(1, getNumSubscriptions(ns + "/out"));
236  EXPECT_EQ(true, lazySub->isSubscribed());
237 
238  // Delete the pubsub object - it should disconnect the subscriber.
239  lazySub.reset();
240 
241  spin(0.1);
242  EXPECT_EQ(5, numOutReceived);
243  EXPECT_EQ(0, inPub.getNumSubscribers());
244  EXPECT_EQ(0, getNumSubscriptions(ns + "/in"));
245  EXPECT_EQ(1, getNumSubscriptions(ns + "/out"));
246  }
247 }
248 
249 TEST(GenericLazyPubSub, StartSequenceNothing) // NOLINT
250 {
251  ros::NodeHandle pnh({"test"}, "test2");
252  const auto ns = pnh.getNamespace();
253  size_t numOutReceived = 0;
254 
255  EXPECT_EQ(0, getNumSubscriptions(ns + "/in"));
256 
257  boost::function<void(const std_msgs::Header&)> outCb = [&](const std_msgs::Header& h)
258  {
259  ++numOutReceived;
260  };
261 
262  auto lazySub = std::make_unique<TestLazyPubSub>("in", "out", pnh);
263 
264  spin(0.1);
265  EXPECT_EQ(0, lazySub->numProcessed);
266  EXPECT_FALSE(lazySub->getPub());
267  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
268  EXPECT_EQ(0, getNumSubscriptions(ns + "/out"));
269  EXPECT_EQ(true, lazySub->isSubscribed());
270 
271  {
272  auto inPub = pnh.advertise<std_msgs::Header>("in", 10);
273 
274  spin(0.1);
275  EXPECT_EQ(0, lazySub->numProcessed);
276  EXPECT_EQ(0, numOutReceived);
277  EXPECT_FALSE(lazySub->getPub());
278  EXPECT_EQ(1, inPub.getNumSubscribers());
279  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
280  EXPECT_EQ(0, getNumSubscriptions(ns + "/out"));
281  EXPECT_EQ(true, lazySub->isSubscribed());
282 
283  auto outSub = pnh.subscribe<std_msgs::Header>("out", 10, outCb);
284 
285  spin(0.1);
286  EXPECT_EQ(0, lazySub->numProcessed);
287  EXPECT_EQ(0, numOutReceived);
288  EXPECT_FALSE(lazySub->getPub());
289  EXPECT_EQ(1, inPub.getNumSubscribers());
290  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
291  EXPECT_EQ(1, getNumSubscriptions(ns + "/out"));
292  EXPECT_EQ(true, lazySub->isSubscribed());
293 
294  for (size_t i = 0; i < 10; ++i)
295  inPub.publish(std_msgs::Header());
296 
297  spin(0.1);
298  EXPECT_EQ(10, lazySub->numProcessed);
299  EXPECT_EQ(10, numOutReceived);
300  ASSERT_TRUE(lazySub->getPub());
301  EXPECT_EQ(1, lazySub->getPub().getNumSubscribers());
302  EXPECT_EQ(1, inPub.getNumSubscribers());
303  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
304  EXPECT_EQ(1, getNumSubscriptions(ns + "/out"));
305  EXPECT_EQ(true, lazySub->isSubscribed());
306  }
307 
308  spin(0.1);
309  EXPECT_EQ(10, lazySub->numProcessed);
310  EXPECT_EQ(10, numOutReceived);
311  ASSERT_TRUE(lazySub->getPub());
312  EXPECT_EQ(0, lazySub->getPub().getNumSubscribers());
313  EXPECT_EQ(0, getNumSubscriptions(ns + "/in"));
314  EXPECT_EQ(0, getNumSubscriptions(ns + "/out"));
315  EXPECT_EQ(false, lazySub->isSubscribed());
316 }
317 
318 TEST(GenericLazyPubSub, StartSequenceIn) // NOLINT
319 {
320  ros::NodeHandle pnh({"test"}, "test3");
321  const auto ns = pnh.getNamespace();
322  size_t numOutReceived = 0;
323 
324  EXPECT_EQ(0, getNumSubscriptions(ns + "/in"));
325  EXPECT_EQ(0, getNumSubscriptions(ns + "/out"));
326 
327  boost::function<void(const std_msgs::Header&)> outCb = [&](const std_msgs::Header& h)
328  {
329  ++numOutReceived;
330  };
331 
332  auto inPub = pnh.advertise<std_msgs::Header>("in", 10);
333 
334  spin(0.1);
335  EXPECT_EQ(0, inPub.getNumSubscribers());
336  EXPECT_EQ(0, getNumSubscriptions(ns + "/in"));
337 
338  auto lazySub = std::make_unique<TestLazyPubSub>("in", "out", pnh);
339 
340  spin(0.1);
341  EXPECT_EQ(0, lazySub->numProcessed);
342  EXPECT_FALSE(lazySub->getPub());
343  EXPECT_EQ(1, inPub.getNumSubscribers());
344  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
345  EXPECT_EQ(0, getNumSubscriptions(ns + "/out"));
346  EXPECT_EQ(true, lazySub->isSubscribed());
347 
348  {
349  auto outSub = pnh.subscribe<std_msgs::Header>("out", 10, outCb);
350 
351  spin(0.1);
352  EXPECT_EQ(0, lazySub->numProcessed);
353  EXPECT_EQ(0, numOutReceived);
354  EXPECT_FALSE(lazySub->getPub());
355  EXPECT_EQ(1, inPub.getNumSubscribers());
356  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
357  EXPECT_EQ(1, getNumSubscriptions(ns + "/out"));
358  EXPECT_EQ(true, lazySub->isSubscribed());
359 
360  for (size_t i = 0; i < 10; ++i)
361  inPub.publish(std_msgs::Header());
362 
363  spin(0.1);
364  EXPECT_EQ(10, lazySub->numProcessed);
365  EXPECT_EQ(10, numOutReceived);
366  ASSERT_TRUE(lazySub->getPub());
367  EXPECT_EQ(1, lazySub->getPub().getNumSubscribers());
368  EXPECT_EQ(1, inPub.getNumSubscribers());
369  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
370  EXPECT_EQ(1, getNumSubscriptions(ns + "/out"));
371  EXPECT_EQ(true, lazySub->isSubscribed());
372  }
373 
374  spin(0.1);
375  EXPECT_EQ(10, lazySub->numProcessed);
376  EXPECT_EQ(10, numOutReceived);
377  ASSERT_TRUE(lazySub->getPub());
378  EXPECT_EQ(0, lazySub->getPub().getNumSubscribers());
379  EXPECT_EQ(0, inPub.getNumSubscribers());
380  EXPECT_EQ(0, getNumSubscriptions(ns + "/in"));
381  EXPECT_EQ(0, getNumSubscriptions(ns + "/out"));
382  EXPECT_EQ(false, lazySub->isSubscribed());
383 }
384 
385 TEST(GenericLazyPubSub, StartSequenceOut) // NOLINT
386 {
387  ros::NodeHandle pnh({"test"}, "test4");
388  const auto ns = pnh.getNamespace();
389  size_t numOutReceived = 0;
390 
391  EXPECT_EQ(0, getNumSubscriptions(ns + "/in"));
392  EXPECT_EQ(0, getNumSubscriptions(ns + "/out"));
393 
394  boost::function<void(const std_msgs::Header&)> outCb = [&](const std_msgs::Header& h)
395  {
396  ++numOutReceived;
397  };
398 
399  auto outSub = pnh.subscribe<std_msgs::Header>("out", 10, outCb);
400 
401  spin(0.1);
402  EXPECT_EQ(0, outSub.getNumPublishers());
403  EXPECT_EQ(0, getNumSubscriptions(ns + "/in"));
404  EXPECT_EQ(1, getNumSubscriptions(ns + "/out"));
405 
406  auto lazySub = std::make_unique<TestLazyPubSub>("in", "out", pnh);
407 
408  spin(0.1);
409  EXPECT_EQ(0, lazySub->numProcessed);
410  EXPECT_FALSE(lazySub->getPub());
411  EXPECT_EQ(0, outSub.getNumPublishers());
412  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
413  EXPECT_EQ(1, getNumSubscriptions(ns + "/out"));
414  EXPECT_EQ(true, lazySub->isSubscribed());
415 
416  {
417  auto inPub = pnh.advertise<std_msgs::Header>("in", 10);
418 
419  spin(0.1);
420  EXPECT_EQ(0, lazySub->numProcessed);
421  EXPECT_EQ(0, numOutReceived);
422  EXPECT_FALSE(lazySub->getPub());
423  EXPECT_EQ(1, inPub.getNumSubscribers());
424  EXPECT_EQ(0, outSub.getNumPublishers());
425  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
426  EXPECT_EQ(1, getNumSubscriptions(ns + "/out"));
427  EXPECT_EQ(true, lazySub->isSubscribed());
428 
429  for (size_t i = 0; i < 10; ++i)
430  inPub.publish(std_msgs::Header());
431 
432  spin(0.1);
433  EXPECT_EQ(10, lazySub->numProcessed);
434  EXPECT_EQ(10, numOutReceived);
435  ASSERT_TRUE(lazySub->getPub());
436  EXPECT_EQ(1, lazySub->getPub().getNumSubscribers());
437  EXPECT_EQ(1, inPub.getNumSubscribers());
438  EXPECT_EQ(1, outSub.getNumPublishers());
439  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
440  EXPECT_EQ(1, getNumSubscriptions(ns + "/out"));
441  EXPECT_EQ(true, lazySub->isSubscribed());
442  }
443 
444  spin(0.1);
445  EXPECT_EQ(10, lazySub->numProcessed);
446  EXPECT_EQ(10, numOutReceived);
447  ASSERT_TRUE(lazySub->getPub());
448  EXPECT_EQ(1, lazySub->getPub().getNumSubscribers());
449  EXPECT_EQ(1, outSub.getNumPublishers());
450  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
451  EXPECT_EQ(1, getNumSubscriptions(ns + "/out"));
452  EXPECT_EQ(true, lazySub->isSubscribed());
453 }
454 
455 TEST(GenericLazyPubSub, StartSequenceInOut) // NOLINT
456 {
457  ros::NodeHandle pnh({"test"}, "test5");
458  const auto ns = pnh.getNamespace();
459  size_t numOutReceived = 0;
460 
461  EXPECT_EQ(0, getNumSubscriptions(ns + "/in"));
462  EXPECT_EQ(0, getNumSubscriptions(ns + "/out"));
463 
464  boost::function<void(const std_msgs::Header&)> outCb = [&](const std_msgs::Header& h)
465  {
466  ++numOutReceived;
467  };
468 
469  auto inPub = pnh.advertise<std_msgs::Header>("in", 10);
470  auto outSub = pnh.subscribe<std_msgs::Header>("out", 10, outCb);
471 
472  spin(0.1);
473  EXPECT_EQ(0, outSub.getNumPublishers());
474  EXPECT_EQ(0, getNumSubscriptions(ns + "/in"));
475  EXPECT_EQ(1, getNumSubscriptions(ns + "/out"));
476 
477  auto lazySub = std::make_unique<TestLazyPubSub>("in", "out", pnh);
478 
479  spin(0.1);
480  EXPECT_EQ(0, lazySub->numProcessed);
481  EXPECT_EQ(0, numOutReceived);
482  EXPECT_FALSE(lazySub->getPub());
483  EXPECT_EQ(1, inPub.getNumSubscribers());
484  EXPECT_EQ(0, outSub.getNumPublishers());
485  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
486  EXPECT_EQ(1, getNumSubscriptions(ns + "/out"));
487  EXPECT_EQ(true, lazySub->isSubscribed());
488 
489  for (size_t i = 0; i < 10; ++i)
490  inPub.publish(std_msgs::Header());
491 
492  spin(0.1);
493  EXPECT_EQ(10, lazySub->numProcessed);
494  EXPECT_EQ(10, numOutReceived);
495  ASSERT_TRUE(lazySub->getPub());
496  EXPECT_EQ(1, lazySub->getPub().getNumSubscribers());
497  EXPECT_EQ(1, inPub.getNumSubscribers());
498  EXPECT_EQ(1, outSub.getNumPublishers());
499  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
500  EXPECT_EQ(1, getNumSubscriptions(ns + "/out"));
501  EXPECT_EQ(true, lazySub->isSubscribed());
502 }
503 
504 TEST(GenericLazyPubSub, StartSequenceNoOut) // NOLINT
505 {
506  ros::NodeHandle pnh({"test"}, "test5");
507  const auto ns = pnh.getNamespace();
508 
509  EXPECT_EQ(0, getNumSubscriptions(ns + "/in"));
510  EXPECT_EQ(0, getNumSubscriptions(ns + "/out"));
511 
512  auto inPub = pnh.advertise<std_msgs::Header>("in", 10);
513 
514  spin(0.1);
515  EXPECT_EQ(0, getNumSubscriptions(ns + "/in"));
516  EXPECT_EQ(0, getNumSubscriptions(ns + "/out"));
517 
518  auto lazySub = std::make_unique<TestLazyPubSub>("in", "out", pnh);
519 
520  spin(0.1);
521  EXPECT_EQ(0, lazySub->numProcessed);
522  EXPECT_FALSE(lazySub->getPub());
523  EXPECT_EQ(1, inPub.getNumSubscribers());
524  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
525  EXPECT_EQ(0, getNumSubscriptions(ns + "/out"));
526  EXPECT_EQ(true, lazySub->isSubscribed());
527 
528  inPub.publish(std_msgs::Header());
529 
530  spin(0.1);
531  EXPECT_EQ(1, lazySub->numProcessed);
532  ASSERT_TRUE(lazySub->getPub());
533  EXPECT_EQ(0, lazySub->getPub().getNumSubscribers());
534  EXPECT_EQ(0, inPub.getNumSubscribers());
535  EXPECT_EQ(0, getNumSubscriptions(ns + "/in"));
536  EXPECT_EQ(0, getNumSubscriptions(ns + "/out"));
537  EXPECT_EQ(false, lazySub->isSubscribed());
538 }
539 
540 TEST(GenericLazyPubSub, QueueSize) // NOLINT
541 {
542  ros::NodeHandle pnh({"test"}, "test8");
543  size_t numOutReceived = 0;
544 
545  boost::function<void(const std_msgs::Header&)> outCb = [&](const std_msgs::Header& h)
546  {
547  ++numOutReceived;
548  };
549 
550  auto inPub = pnh.advertise<std_msgs::Header>("in", 10);
551  auto outSub = pnh.subscribe<std_msgs::Header>("out", 10, outCb);
552  auto lazySub = std::make_unique<TestLazyPubSub>("in", "out", pnh, 5, 3);
553 
554  spin(0.1);
555 
556  for (size_t i = 0; i < 10; ++i)
557  inPub.publish(std_msgs::Header());
558 
559  spin(0.1);
560  EXPECT_LE(5, lazySub->numProcessed);
561  EXPECT_GE(6, lazySub->numProcessed);
562  EXPECT_LE(5, numOutReceived); // ideally would be 3, but there's no way to test it with local-only connections
563  EXPECT_GE(6, numOutReceived);
564 }
565 
566 TEST(GenericLazyPubSub, MultiLatchedInputs) // NOLINT
567 {
568  ros::NodeHandle pnh({"test"}, "test9");
569  size_t numOutReceived = 0;
570 
571  boost::function<void(const std_msgs::Header&)> outCb = [&](const std_msgs::Header& h)
572  {
573  ++numOutReceived;
574  };
575 
576  // Topic /latch has 5 latched publishers in the rostest launch file. This test tests whether the relay works well for
577  // a large inrush of messages at the beginning.
578  auto outSub = pnh.subscribe<std_msgs::Header>("out", 10, outCb);
579  auto lazySub = std::make_unique<TestLazyPubSub>("/latched", "out", pnh);
580 
581  spin(0.5);
582 
583  EXPECT_EQ(5, lazySub->numProcessed);
584  EXPECT_EQ(5, numOutReceived);
585 }
586 
588 {
589 public:
590  TestAdvertiseOptions(const std::string& topicIn, const std::string& topicOut, const ros::NodeHandle& nh) :
592  {
593  }
594 
595 protected:
597  {
598  auto opts = GenericLazyPubSub::createAdvertiseOptions(event);
599  opts.topic = "topic_from_opts";
600  return opts;
601  }
602 };
603 
604 TEST(GenericLazyPubSub, OverrideAdvertiseOptions) // NOLINT
605 {
606  ros::NodeHandle pnh({"test"}, "test10");
607  size_t numOutReceived = 0;
608 
609  boost::function<void(const std_msgs::Header&)> outCb = [&](const std_msgs::Header& h)
610  {
611  ++numOutReceived;
612  };
613 
614  auto inPub = pnh.advertise<std_msgs::Header>("in", 10);
615  auto outSub = pnh.subscribe<std_msgs::Header>("topic_from_opts", 10, outCb);
616  auto lazySub = std::make_unique<TestAdvertiseOptions>("in", "out", pnh);
617 
618  spin(0.1);
619 
620  for (size_t i = 0; i < 10; ++i)
621  inPub.publish(std_msgs::Header());
622 
623  spin(0.1);
624  EXPECT_EQ(10, lazySub->numProcessed);
625  EXPECT_EQ(10, numOutReceived);
626  EXPECT_FALSE(lazySub->getPub().isLatched());
627 }
628 
629 TEST(GenericLazyPubSub, LatchIsRetained) // NOLINT
630 {
631  ros::NodeHandle pnh({"test"}, "test11");
632  size_t numOutReceived = 0;
633 
634  boost::function<void(const std_msgs::Header&)> outCb = [&](const std_msgs::Header& h)
635  {
636  ++numOutReceived;
637  };
638 
639  auto inPub = pnh.advertise<std_msgs::Header>("in", 10, true);
640  auto outSub = pnh.subscribe<std_msgs::Header>("out", 10, outCb);
641  auto lazySub = std::make_unique<TestLazyPubSub>("in", "out", pnh);
642 
643  spin(0.1);
644 
645  for (size_t i = 0; i < 10; ++i)
646  inPub.publish(std_msgs::Header());
647 
648  spin(0.1);
649  EXPECT_EQ(10, lazySub->numProcessed);
650  EXPECT_EQ(10, numOutReceived);
651  EXPECT_TRUE(lazySub->getPub().isLatched());
652 }
653 
654 TEST(GenericLazyPubSub, SetLazy) // NOLINT
655 {
656  ros::NodeHandle pnh({"test"}, "test6");
657  const auto ns = pnh.getNamespace();
658  auto inPub = pnh.advertise<std_msgs::Header>("in", 10);
659 
660  size_t numOutReceived = 0;
661  boost::function<void(const std_msgs::Header&)> outCb = [&](const std_msgs::Header& h)
662  {
663  ++numOutReceived;
664  };
665 
666  auto lazySub = std::make_unique<TestLazyPubSub>("in", "out", pnh);
667 
668  spin(0.1);
669  EXPECT_EQ(0, lazySub->numProcessed);
670  EXPECT_EQ(0, numOutReceived);
671  EXPECT_FALSE(lazySub->getPub());
672  EXPECT_EQ(1, inPub.getNumSubscribers());
673  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
674  EXPECT_EQ(0, getNumSubscriptions(ns + "/out"));
675  EXPECT_EQ(true, lazySub->isSubscribed());
676  EXPECT_EQ(true, lazySub->isLazy());
677 
678  lazySub->setLazy(false);
679 
680  spin(0.1);
681  EXPECT_EQ(0, lazySub->numProcessed);
682  EXPECT_EQ(0, numOutReceived);
683  EXPECT_FALSE(lazySub->getPub());
684  EXPECT_EQ(1, inPub.getNumSubscribers());
685  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
686  EXPECT_EQ(0, getNumSubscriptions(ns + "/out"));
687  EXPECT_EQ(true, lazySub->isSubscribed());
688  EXPECT_EQ(false, lazySub->isLazy());
689 
690  inPub.publish(std_msgs::Header());
691 
692  spin(0.1);
693  EXPECT_EQ(1, lazySub->numProcessed);
694  EXPECT_EQ(0, numOutReceived);
695  ASSERT_TRUE(lazySub->getPub());
696  EXPECT_EQ(0, lazySub->getPub().getNumSubscribers());
697  EXPECT_EQ(1, inPub.getNumSubscribers());
698  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
699  EXPECT_EQ(0, getNumSubscriptions(ns + "/out"));
700  EXPECT_EQ(true, lazySub->isSubscribed());
701  EXPECT_EQ(false, lazySub->isLazy());
702 
703  {
704  auto outSub = pnh.subscribe<std_msgs::Header>("out", 10, outCb);
705 
706  spin(0.1);
707  EXPECT_EQ(1, lazySub->numProcessed);
708  EXPECT_EQ(0, numOutReceived);
709  ASSERT_TRUE(lazySub->getPub());
710  EXPECT_EQ(1, lazySub->getPub().getNumSubscribers());
711  EXPECT_EQ(1, inPub.getNumSubscribers());
712  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
713  EXPECT_EQ(1, getNumSubscriptions(ns + "/out"));
714  EXPECT_EQ(true, lazySub->isSubscribed());
715  EXPECT_EQ(false, lazySub->isLazy());
716 
717  inPub.publish(std_msgs::Header());
718 
719  spin(0.1);
720  EXPECT_EQ(2, lazySub->numProcessed);
721  EXPECT_EQ(1, numOutReceived);
722  ASSERT_TRUE(lazySub->getPub());
723  EXPECT_EQ(1, lazySub->getPub().getNumSubscribers());
724  EXPECT_EQ(1, inPub.getNumSubscribers());
725  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
726  EXPECT_EQ(1, getNumSubscriptions(ns + "/out"));
727  EXPECT_EQ(true, lazySub->isSubscribed());
728  EXPECT_EQ(false, lazySub->isLazy());
729  }
730 
731  spin(0.1);
732  EXPECT_EQ(2, lazySub->numProcessed);
733  EXPECT_EQ(1, numOutReceived);
734  ASSERT_TRUE(lazySub->getPub());
735  EXPECT_EQ(0, lazySub->getPub().getNumSubscribers());
736  EXPECT_EQ(1, inPub.getNumSubscribers());
737  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
738  EXPECT_EQ(0, getNumSubscriptions(ns + "/out"));
739  EXPECT_EQ(true, lazySub->isSubscribed());
740  EXPECT_EQ(false, lazySub->isLazy());
741 
742  lazySub->setLazy(true);
743 
744  spin(0.1);
745  EXPECT_EQ(2, lazySub->numProcessed);
746  EXPECT_EQ(1, numOutReceived);
747  ASSERT_TRUE(lazySub->getPub());
748  EXPECT_EQ(0, lazySub->getPub().getNumSubscribers());
749  EXPECT_EQ(0, inPub.getNumSubscribers());
750  EXPECT_EQ(0, getNumSubscriptions(ns + "/in"));
751  EXPECT_EQ(0, getNumSubscriptions(ns + "/out"));
752  EXPECT_EQ(false, lazySub->isSubscribed());
753  EXPECT_EQ(true, lazySub->isLazy());
754 
755  {
756  auto outSub = pnh.subscribe<std_msgs::Header>("out", 10, outCb);
757 
758  spin(0.1);
759  EXPECT_EQ(2, lazySub->numProcessed);
760  EXPECT_EQ(1, numOutReceived);
761  ASSERT_TRUE(lazySub->getPub());
762  EXPECT_EQ(1, lazySub->getPub().getNumSubscribers());
763  EXPECT_EQ(1, inPub.getNumSubscribers());
764  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
765  EXPECT_EQ(1, getNumSubscriptions(ns + "/out"));
766  EXPECT_EQ(true, lazySub->isSubscribed());
767  EXPECT_EQ(true, lazySub->isLazy());
768 
769  inPub.publish(std_msgs::Header());
770 
771  spin(0.1);
772  EXPECT_EQ(3, lazySub->numProcessed);
773  EXPECT_EQ(2, numOutReceived);
774  ASSERT_TRUE(lazySub->getPub());
775  EXPECT_EQ(1, lazySub->getPub().getNumSubscribers());
776  EXPECT_EQ(1, inPub.getNumSubscribers());
777  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
778  EXPECT_EQ(1, getNumSubscriptions(ns + "/out"));
779  EXPECT_EQ(true, lazySub->isSubscribed());
780  EXPECT_EQ(true, lazySub->isLazy());
781  }
782 
783  spin(0.1);
784  EXPECT_EQ(3, lazySub->numProcessed);
785  EXPECT_EQ(2, numOutReceived);
786  ASSERT_TRUE(lazySub->getPub());
787  EXPECT_EQ(0, lazySub->getPub().getNumSubscribers());
788  EXPECT_EQ(0, inPub.getNumSubscribers());
789  EXPECT_EQ(0, getNumSubscriptions(ns + "/in"));
790  EXPECT_EQ(0, getNumSubscriptions(ns + "/out"));
791  EXPECT_EQ(false, lazySub->isSubscribed());
792  EXPECT_EQ(true, lazySub->isLazy());
793 
794  lazySub->setLazy(false);
795 
796  spin(0.1);
797  EXPECT_EQ(3, lazySub->numProcessed);
798  EXPECT_EQ(2, numOutReceived);
799  ASSERT_TRUE(lazySub->getPub());
800  EXPECT_EQ(0, lazySub->getPub().getNumSubscribers());
801  EXPECT_EQ(1, inPub.getNumSubscribers());
802  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
803  EXPECT_EQ(0, getNumSubscriptions(ns + "/out"));
804  EXPECT_EQ(true, lazySub->isSubscribed());
805  EXPECT_EQ(false, lazySub->isLazy());
806 }
807 
808 TEST(GenericLazyPubSub, Chain) // NOLINT
809 {
810  ros::NodeHandle pnh({"test"}, "test7");
811  const auto ns = pnh.getNamespace();
812  auto inPub = pnh.advertise<std_msgs::Header>("in", 10);
813 
814  size_t numOutReceived = 0;
815  boost::function<void(const std_msgs::Header&)> outCb = [&](const std_msgs::Header& h)
816  {
817  ++numOutReceived;
818  };
819  TestLazyPubSub lazySub1("in", "inter1", pnh);
820  TestLazyPubSub lazySub2("inter1", "inter2", pnh);
821  TestLazyPubSub lazySub3("inter2", "out", pnh);
822 
823  spin(0.1);
824  EXPECT_EQ(0, lazySub1.numProcessed);
825  EXPECT_EQ(0, lazySub2.numProcessed);
826  EXPECT_EQ(0, lazySub3.numProcessed);
827  EXPECT_EQ(0, numOutReceived);
828  EXPECT_EQ(1, inPub.getNumSubscribers());
829  EXPECT_FALSE(lazySub1.getPub());
830  EXPECT_FALSE(lazySub2.getPub());
831  EXPECT_FALSE(lazySub3.getPub());
832  EXPECT_EQ(true, lazySub1.isSubscribed());
833  EXPECT_EQ(true, lazySub2.isSubscribed());
834  EXPECT_EQ(true, lazySub3.isSubscribed());
835  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
836  EXPECT_EQ(1, getNumSubscriptions(ns + "/inter1"));
837  EXPECT_EQ(1, getNumSubscriptions(ns + "/inter2"));
838  EXPECT_EQ(0, getNumSubscriptions(ns + "/out"));
839 
840  {
841  auto outSub = pnh.subscribe<std_msgs::Header>("out", 10, outCb);
842 
843  spin(0.1);
844  EXPECT_EQ(0, lazySub1.numProcessed);
845  EXPECT_EQ(0, lazySub2.numProcessed);
846  EXPECT_EQ(0, lazySub3.numProcessed);
847  EXPECT_EQ(0, numOutReceived);
848  EXPECT_EQ(1, inPub.getNumSubscribers());
849  EXPECT_FALSE(lazySub1.getPub());
850  EXPECT_FALSE(lazySub2.getPub());
851  EXPECT_FALSE(lazySub3.getPub());
852  EXPECT_EQ(true, lazySub1.isSubscribed());
853  EXPECT_EQ(true, lazySub2.isSubscribed());
854  EXPECT_EQ(true, lazySub3.isSubscribed());
855  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
856  EXPECT_EQ(1, getNumSubscriptions(ns + "/inter1"));
857  EXPECT_EQ(1, getNumSubscriptions(ns + "/inter2"));
858  EXPECT_EQ(1, getNumSubscriptions(ns + "/out"));
859 
860  inPub.publish(std_msgs::Header());
861 
862  spin(0.1);
863  EXPECT_EQ(1, lazySub1.numProcessed);
864  EXPECT_EQ(1, lazySub2.numProcessed);
865  EXPECT_EQ(1, lazySub3.numProcessed);
866  EXPECT_EQ(1, numOutReceived);
867  EXPECT_EQ(1, inPub.getNumSubscribers());
868  ASSERT_TRUE(lazySub1.getPub());
869  EXPECT_EQ(1, lazySub1.getPub().getNumSubscribers());
870  ASSERT_TRUE(lazySub2.getPub());
871  EXPECT_EQ(1, lazySub2.getPub().getNumSubscribers());
872  ASSERT_TRUE(lazySub3.getPub());
873  EXPECT_EQ(true, lazySub1.isSubscribed());
874  EXPECT_EQ(true, lazySub2.isSubscribed());
875  EXPECT_EQ(true, lazySub3.isSubscribed());
876  EXPECT_EQ(1, lazySub3.getPub().getNumSubscribers());
877  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
878  EXPECT_EQ(1, getNumSubscriptions(ns + "/inter1"));
879  EXPECT_EQ(1, getNumSubscriptions(ns + "/inter2"));
880  EXPECT_EQ(1, getNumSubscriptions(ns + "/out"));
881 
882  inPub.publish(std_msgs::Header());
883 
884  spin(0.1);
885  EXPECT_EQ(2, lazySub1.numProcessed);
886  EXPECT_EQ(2, lazySub2.numProcessed);
887  EXPECT_EQ(2, lazySub3.numProcessed);
888  EXPECT_EQ(2, numOutReceived);
889  EXPECT_EQ(1, inPub.getNumSubscribers());
890  ASSERT_TRUE(lazySub1.getPub());
891  EXPECT_EQ(1, lazySub1.getPub().getNumSubscribers());
892  ASSERT_TRUE(lazySub2.getPub());
893  EXPECT_EQ(1, lazySub2.getPub().getNumSubscribers());
894  ASSERT_TRUE(lazySub3.getPub());
895  EXPECT_EQ(1, lazySub3.getPub().getNumSubscribers());
896  EXPECT_EQ(true, lazySub1.isSubscribed());
897  EXPECT_EQ(true, lazySub2.isSubscribed());
898  EXPECT_EQ(true, lazySub3.isSubscribed());
899  EXPECT_EQ(1, getNumSubscriptions(ns + "/in"));
900  EXPECT_EQ(1, getNumSubscriptions(ns + "/inter1"));
901  EXPECT_EQ(1, getNumSubscriptions(ns + "/inter2"));
902  EXPECT_EQ(1, getNumSubscriptions(ns + "/out"));
903  }
904 
905  spin(0.1);
906  EXPECT_EQ(2, lazySub1.numProcessed);
907  EXPECT_EQ(2, lazySub2.numProcessed);
908  EXPECT_EQ(2, lazySub3.numProcessed);
909  EXPECT_EQ(2, numOutReceived);
910  EXPECT_EQ(0, inPub.getNumSubscribers());
911  ASSERT_TRUE(lazySub1.getPub());
912  EXPECT_EQ(0, lazySub1.getPub().getNumSubscribers());
913  ASSERT_TRUE(lazySub2.getPub());
914  EXPECT_EQ(0, lazySub2.getPub().getNumSubscribers());
915  ASSERT_TRUE(lazySub3.getPub());
916  EXPECT_EQ(0, lazySub3.getPub().getNumSubscribers());
917  EXPECT_EQ(false, lazySub1.isSubscribed());
918  EXPECT_EQ(false, lazySub2.isSubscribed());
919  EXPECT_EQ(false, lazySub3.isSubscribed());
920  EXPECT_EQ(0, getNumSubscriptions(ns + "/in"));
921  EXPECT_EQ(0, getNumSubscriptions(ns + "/inter1"));
922  EXPECT_EQ(0, getNumSubscriptions(ns + "/inter2"));
923  EXPECT_EQ(0, getNumSubscriptions(ns + "/out"));
924 
925  inPub.publish(std_msgs::Header());
926 
927  spin(0.1);
928  EXPECT_EQ(2, lazySub1.numProcessed);
929  EXPECT_EQ(2, lazySub2.numProcessed);
930  EXPECT_EQ(2, lazySub3.numProcessed);
931  EXPECT_EQ(2, numOutReceived);
932  EXPECT_EQ(0, inPub.getNumSubscribers());
933  ASSERT_TRUE(lazySub1.getPub());
934  EXPECT_EQ(0, lazySub1.getPub().getNumSubscribers());
935  ASSERT_TRUE(lazySub2.getPub());
936  EXPECT_EQ(0, lazySub2.getPub().getNumSubscribers());
937  ASSERT_TRUE(lazySub3.getPub());
938  EXPECT_EQ(0, lazySub3.getPub().getNumSubscribers());
939  EXPECT_EQ(false, lazySub1.isSubscribed());
940  EXPECT_EQ(false, lazySub2.isSubscribed());
941  EXPECT_EQ(false, lazySub3.isSubscribed());
942  EXPECT_EQ(0, getNumSubscriptions(ns + "/in"));
943  EXPECT_EQ(0, getNumSubscriptions(ns + "/inter1"));
944  EXPECT_EQ(0, getNumSubscriptions(ns + "/inter2"));
945  EXPECT_EQ(0, getNumSubscriptions(ns + "/out"));
946 }
947 
948 int main(int argc, char **argv)
949 {
950  testing::InitGoogleTest(&argc, argv);
951  ros::init(argc, argv, "test_generic_lazy_pubsub");
954  // This prevents the ROS background threads from shutting down after the first test's nodehandles disappear
955  ros::NodeHandle nh;
956  return RUN_ALL_TESTS();
957 }
cras::GenericLazyPubSub
A pair of lazy subscriber and publisher which use the same message type (unknown at compile time).
Definition: generic_lazy_pubsub.hpp:44
ros::WallDuration::sleep
bool sleep() const
ros::Publisher
cras::ConditionalSubscriber::updateSubscription
void updateSubscription()
The callback called when the condition might have changed.
Definition: lazy_subscriber.cpp:67
TestLazyPubSub
Definition: test_generic_lazy_pubsub.cpp:56
topic_manager.h
TestLazyPubSub::TestLazyPubSub
TestLazyPubSub(const ::std::string &topicIn, const ::std::string &topicOut, const ::ros::NodeHandle &nh={}, const size_t inQueueSize=10, const size_t outQueueSize=10)
Definition: test_generic_lazy_pubsub.cpp:59
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
TEST
TEST(GenericLazyPubSub, OverallTest)
Definition: test_generic_lazy_pubsub.cpp:88
TestAdvertiseOptions
Definition: test_generic_lazy_pubsub.cpp:587
ros.h
ros::spinOnce
ROSCPP_DECL void spinOnce()
getNumSubscriptions
size_t getNumSubscriptions(const std::string &topic)
Definition: test_generic_lazy_pubsub.cpp:42
TestLazyPubSub::processMessage
void processMessage(const ros::MessageEvent< topic_tools::ShapeShifter const > &event, ros::Publisher &pub)
Definition: test_generic_lazy_pubsub.cpp:77
wait
void wait(int seconds)
subscription.h
ros::console::set_logger_level
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
ros::MessageEvent::getConstMessage
const boost::shared_ptr< ConstMessage > & getConstMessage() const
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::AdvertiseOptions
cras::GenericLazyPubSub::sub
::ros::Subscriber sub
The input subscriber.
Definition: generic_lazy_pubsub.hpp:194
TestAdvertiseOptions::createAdvertiseOptions
ros::AdvertiseOptions createAdvertiseOptions(const ros::MessageEvent< topic_tools::ShapeShifter const > &event) override
Definition: test_generic_lazy_pubsub.cpp:596
functional.hpp
TestLazyPubSub::getPub
ros::Publisher & getPub()
Definition: test_generic_lazy_pubsub.cpp:66
cras::ConditionalSubscriber::isSubscribed
bool isSubscribed() const
Whether the subscriber is currently subscribed to its topic or not.
Definition: lazy_subscriber.cpp:61
generic_lazy_pubsub.hpp
Lazy subscriber that subscribes only when a paired publisher has subscribers. Version for unknown mes...
ros::console::levels::Debug
Debug
cras::GenericLazyPubSub::outQueueSize
size_t outQueueSize
Queue size of the output publisher.
Definition: generic_lazy_pubsub.hpp:188
cras::GenericLazyPubSub::pub
::ros::Publisher pub
The output publisher. It will be invalid until first message is received.
Definition: generic_lazy_pubsub.hpp:191
cras::GenericLazyPubSub::inQueueSize
size_t inQueueSize
Queue size of the input subscriber.
Definition: generic_lazy_pubsub.hpp:185
spin
void spin(double duration, double wait)
Definition: test_generic_lazy_pubsub.cpp:26
TestAdvertiseOptions::TestAdvertiseOptions
TestAdvertiseOptions(const std::string &topicIn, const std::string &topicOut, const ros::NodeHandle &nh)
Definition: test_generic_lazy_pubsub.cpp:590
cras::bind_front
auto bind_front(F &&f, Args &&... args)
ros::console::notifyLoggerLevelsChanged
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
ros::TopicManager::instance
static const TopicManagerPtr & instance()
cras::GenericLazyPubSub::topicIn
::std::string topicIn
Input topic (relative to nh).
Definition: generic_lazy_pubsub.hpp:179
TestLazyPubSub::numProcessed
size_t numProcessed
Definition: test_generic_lazy_pubsub.cpp:85
TestLazyPubSub::getSub
ros::Subscriber & getSub()
Definition: test_generic_lazy_pubsub.cpp:71
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
ROSCONSOLE_DEFAULT_NAME
#define ROSCONSOLE_DEFAULT_NAME
ros::WallDuration
main
int main(int argc, char **argv)
Definition: test_generic_lazy_pubsub.cpp:948
ros::NodeHandle
ros::MessageEvent
ros::Subscriber
cras::GenericLazyPubSub::topicOut
::std::string topicOut
Output topic (relative to nh).
Definition: generic_lazy_pubsub.hpp:182


cras_topic_tools
Author(s): Martin Pecka
autogenerated on Sun Mar 2 2025 03:51:09