publishers.cpp
Go to the documentation of this file.
1 #include <gtest/gtest.h>
2 
3 #include <ros/master.h>
4 #include <std_msgs/Int32.h>
5 #include <ros/duration.h>
6 #include <ros/subscriber.h>
7 #include <ros/node_handle.h>
8 
9 #include <atomic>
10 #include <iostream>
11 #include <string>
12 
13 static double CALLBACK_TEST_TIME_LIMIT_ = 1.0;
14 
16 {
17 public:
18  explicit Int32CallbackTest(const std::string& topic) : got_msg_(false)
19  {
20  ros::NodeHandle node_handle;
21  int queue_size = 1;
22  ros::Subscriber subscriber = node_handle.subscribe(topic, queue_size, &Int32CallbackTest::callback, this);
23 
25 
26  while (subscriber.getNumPublishers() == 0 && ros::Time::now() < time_out && ros::ok())
27  {
28  ros::Duration(0.001).sleep();
29  }
30 
31  while (!got_msg_.load() && ros::Time::now() < time_out && ros::ok())
32  {
33  ros::spinOnce();
34  ros::Duration(0.001).sleep();
35  }
36  }
37 
39  {
40  EXPECT_TRUE(got_msg_.load());
41  }
42 
43  void callback(const std_msgs::Int32Ptr& number)
44  {
45  got_msg_ = true;
46  }
47 
48 private:
49  std::atomic<bool> got_msg_;
50 };
51 
52 TEST(Publishers, internal)
53 {
54  Int32CallbackTest("fibonacci_publisher_internal");
55 }
56 
57 TEST(Publishers, other)
58 {
59  Int32CallbackTest("fibonacci_publisher_other");
60 }
61 
62 int main(int argc, char **argv)
63 {
64  testing::InitGoogleTest(&argc, argv);
65  int time_seed = static_cast<int>(time(0));
66  srand(time_seed);
67 
68  ros::init(argc, argv, "publishers");
69 
70  ros::NodeHandle node_handle("~");
71  node_handle.getParam("single_test_time_limit", CALLBACK_TEST_TIME_LIMIT_);
72 
73  return RUN_ALL_TESTS();
74 }
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
TEST(Publishers, internal)
Definition: publishers.cpp:52
static double CALLBACK_TEST_TIME_LIMIT_
Definition: publishers.cpp:13
void callback(const std_msgs::Int32Ptr &number)
Definition: publishers.cpp:43
int main(int argc, char **argv)
Definition: publishers.cpp:62
uint32_t getNumPublishers() const
ROSCPP_DECL bool ok()
Int32CallbackTest(const std::string &topic)
Definition: publishers.cpp:18
bool getParam(const std::string &key, std::string &s) const
static Time now()
std::atomic< bool > got_msg_
Definition: publishers.cpp:49
ROSCPP_DECL void spinOnce()


ros1_ros_cpptemplate
Author(s): Alexander Reimann
autogenerated on Sat Sep 2 2017 02:38:06