topic_statistic_frequency.cpp
Go to the documentation of this file.
1 #include <map>
2 #include <string>
3 
4 #include <ros/ros.h>
5 #include <gtest/gtest.h>
6 #include <rosgraph_msgs/TopicStatistics.h>
7 #include <boost/thread.hpp>
8 #include <std_msgs/Int8MultiArray.h>
9 
10 class Aggregator {
11 public:
12  std::map<std::string, ros::Duration> topic_period_mean_map_;
13 
14  void cb(const rosgraph_msgs::TopicStatistics& msg) {
15  topic_period_mean_map_[msg.topic] = msg.period_mean;
16  }
17 
18  bool frequencyAcceptable(const std::string& topic, float expected) {
19  float errorMargin = 0.1;
20  float foundFreq = 1.f / topic_period_mean_map_[topic].toSec();
21  return std::fabs(foundFreq - expected) / expected <= errorMargin;
22  }
23 };
24 
25 void assertEventuallyHasTopic(const Aggregator& agg, const std::string& topic) {
26  ros::Duration timeout(5.0);
27  auto start = ros::Time::now();
28  while (ros::Time::now() - start < timeout && !agg.topic_period_mean_map_.count(topic)) {
29  ros::Duration(0.5).sleep();
30  }
31  ASSERT_EQ(agg.topic_period_mean_map_.count(topic), 1u);
32 }
33 
34 TEST(TopicStatisticFrequency, statisticFrequency)
35 {
36  ros::NodeHandle nh;
37  Aggregator agg;
38  ros::Subscriber stat_sub = nh.subscribe("/statistics", 1, &Aggregator::cb, &agg);
39 
40  ros::AsyncSpinner spinner(4);
41  spinner.start();
42 
43  ros::Duration(5.0).sleep();
44 
45  assertEventuallyHasTopic(agg, "/very_fast_chatter");
46  assertEventuallyHasTopic(agg, "/fast_chatter");
47  assertEventuallyHasTopic(agg, "/slow_chatter");
48  assertEventuallyHasTopic(agg, "/very_slow_chatter");
49 
50  ros::shutdown();
51 
52  ASSERT_TRUE(agg.frequencyAcceptable("/very_fast_chatter", 171));
53  ASSERT_TRUE(agg.frequencyAcceptable("/fast_chatter", 53));
54  ASSERT_TRUE(agg.frequencyAcceptable("/slow_chatter", 18));
55  ASSERT_TRUE(agg.frequencyAcceptable("/very_slow_chatter", 0.8));
56 }
57 
58 
59 int main(int argc, char** argv)
60 {
61  testing::InitGoogleTest(&argc, argv);
62  ros::init(argc, argv, "topic_statistic_frequency");
63  ros::NodeHandle nh;
64  return RUN_ALL_TESTS();
65 }
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::AsyncSpinner::start
void start()
ros.h
ros::AsyncSpinner
ros::shutdown
ROSCPP_DECL void shutdown()
Aggregator::frequencyAcceptable
bool frequencyAcceptable(const std::string &topic, float expected)
Definition: topic_statistic_frequency.cpp:18
Aggregator
Definition: topic_statistic_frequency.cpp:10
Aggregator::topic_period_mean_map_
std::map< std::string, ros::Duration > topic_period_mean_map_
Definition: topic_statistic_frequency.cpp:12
assertEventuallyHasTopic
void assertEventuallyHasTopic(const Aggregator &agg, const std::string &topic)
Definition: topic_statistic_frequency.cpp:25
main
int main(int argc, char **argv)
Definition: topic_statistic_frequency.cpp:59
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
start
ROSCPP_DECL void start()
TEST
TEST(TopicStatisticFrequency, statisticFrequency)
Definition: topic_statistic_frequency.cpp:34
ros::Duration::sleep
bool sleep() const
Aggregator::cb
void cb(const rosgraph_msgs::TopicStatistics &msg)
Definition: topic_statistic_frequency.cpp:14
ros::Duration
ros::NodeHandle
ros::Subscriber
ros::Time::now
static Time now()


test_roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas , Jacob Perron
autogenerated on Thu Nov 23 2023 04:02:02