test_subscriber.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 #include <gtest/gtest.h>
36 
37 #include "ros/time.h"
38 #include "roscpp/Logger.h"
40 #include "message_filters/chain.h"
41 
42 using namespace message_filters;
43 typedef roscpp::Logger Msg;
44 typedef roscpp::LoggerPtr MsgPtr;
45 typedef roscpp::LoggerConstPtr MsgConstPtr;
46 
47 class Helper
48 {
49 public:
51  : count_(0)
52  {}
53 
54  void cb(const MsgConstPtr&)
55  {
56  ++count_;
57  }
58 
59  int32_t count_;
60 };
61 
62 TEST(Subscriber, simple)
63 {
64  ros::NodeHandle nh;
65  Helper h;
66  Subscriber<Msg> sub(nh, "test_topic", 0);
67  sub.registerCallback(boost::bind(&Helper::cb, &h, boost::placeholders::_1));
68  ros::Publisher pub = nh.advertise<Msg>("test_topic", 0);
69 
71  while (h.count_ == 0 && (ros::Time::now() - start) < ros::Duration(1.0))
72  {
73  pub.publish(Msg());
74  ros::Duration(0.01).sleep();
75  ros::spinOnce();
76  }
77 
78  ASSERT_GT(h.count_, 0);
79 }
80 
81 TEST(Subscriber, subUnsubSub)
82 {
83  ros::NodeHandle nh;
84  Helper h;
85  Subscriber<Msg> sub(nh, "test_topic", 0);
86  sub.registerCallback(boost::bind(&Helper::cb, &h, boost::placeholders::_1));
87  ros::Publisher pub = nh.advertise<Msg>("test_topic", 0);
88 
89  sub.unsubscribe();
90  sub.subscribe();
91 
93  while (h.count_ == 0 && (ros::Time::now() - start) < ros::Duration(1.0))
94  {
95  pub.publish(Msg());
96  ros::Duration(0.01).sleep();
97  ros::spinOnce();
98  }
99 
100  ASSERT_GT(h.count_, 0);
101 }
102 
103 TEST(Subscriber, subInChain)
104 {
105  ros::NodeHandle nh;
106  Helper h;
107  Chain<Msg> c;
108  c.addFilter(boost::make_shared<Subscriber<Msg> >(boost::ref(nh), "test_topic", 0));
109  c.registerCallback(boost::bind(&Helper::cb, &h, boost::placeholders::_1));
110  ros::Publisher pub = nh.advertise<Msg>("test_topic", 0);
111 
113  while (h.count_ == 0 && (ros::Time::now() - start) < ros::Duration(1.0))
114  {
115  pub.publish(Msg());
116  ros::Duration(0.01).sleep();
117  ros::spinOnce();
118  }
119 
120  ASSERT_GT(h.count_, 0);
121 }
122 
124 {
125  void cb(const MsgConstPtr& msg)
126  {
127  msg_ = msg;
128  }
129 
131 };
132 
134 {
135  void cb(const MsgPtr& msg)
136  {
137  msg_ = msg;
138  }
139 
141 };
142 
143 TEST(Subscriber, singleNonConstCallback)
144 {
145  ros::NodeHandle nh;
146  NonConstHelper h;
147  Subscriber<Msg> sub(nh, "test_topic", 0);
149  ros::Publisher pub = nh.advertise<Msg>("test_topic", 0);
150  MsgPtr msg(boost::make_shared<Msg>());
151  pub.publish(msg);
152 
153  ros::spinOnce();
154 
155  ASSERT_TRUE(h.msg_);
156  ASSERT_EQ(msg.get(), h.msg_.get());
157 }
158 
159 TEST(Subscriber, multipleNonConstCallbacksFilterSubscriber)
160 {
161  ros::NodeHandle nh;
162  NonConstHelper h, h2;
163  Subscriber<Msg> sub(nh, "test_topic", 0);
166  ros::Publisher pub = nh.advertise<Msg>("test_topic", 0);
167  MsgPtr msg(boost::make_shared<Msg>());
168  pub.publish(msg);
169 
170  ros::spinOnce();
171 
172  ASSERT_TRUE(h.msg_);
173  ASSERT_TRUE(h2.msg_);
174  EXPECT_NE(msg.get(), h.msg_.get());
175  EXPECT_NE(msg.get(), h2.msg_.get());
176  EXPECT_NE(h.msg_.get(), h2.msg_.get());
177 }
178 
179 TEST(Subscriber, multipleCallbacksSomeFilterSomeDirect)
180 {
181  ros::NodeHandle nh;
182  NonConstHelper h, h2;
183  Subscriber<Msg> sub(nh, "test_topic", 0);
185  ros::Subscriber sub2 = nh.subscribe("test_topic", 0, &NonConstHelper::cb, &h2);
186  ros::Publisher pub = nh.advertise<Msg>("test_topic", 0);
187  MsgPtr msg(boost::make_shared<Msg>());
188  pub.publish(msg);
189 
190  ros::spinOnce();
191 
192  ASSERT_TRUE(h.msg_);
193  ASSERT_TRUE(h2.msg_);
194  EXPECT_NE(msg.get(), h.msg_.get());
195  EXPECT_NE(msg.get(), h2.msg_.get());
196  EXPECT_NE(h.msg_.get(), h2.msg_.get());
197 }
198 
199 
200 int main(int argc, char **argv){
201  testing::InitGoogleTest(&argc, argv);
202 
203  ros::init(argc, argv, "test_subscriber");
204  ros::NodeHandle nh;
205 
206  return RUN_ALL_TESTS();
207 }
208 
209 
Helper::cb
void cb(const MsgConstPtr &)
Definition: test_subscriber.cpp:54
Helper
Definition: test_chain.cpp:49
Msg
Definition: msg_cache_unittest.cpp:50
ros::Publisher
ConstHelper
Definition: test_subscriber.cpp:123
boost::shared_ptr< Msg const >
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
Helper::cb
void cb()
Definition: test_chain.cpp:56
time.h
ros::spinOnce
ROSCPP_DECL void spinOnce()
main
int main(int argc, char **argv)
Definition: test_subscriber.cpp:200
TEST
TEST(Subscriber, simple)
Definition: test_subscriber.cpp:62
NonConstHelper
Definition: test_subscriber.cpp:133
subscriber.h
Helper::Helper
Helper()
Definition: test_subscriber.cpp:50
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
message_filters::Subscriber::unsubscribe
void unsubscribe()
Force immediate unsubscription of this subscriber from its topic.
Definition: subscriber.h:202
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ConstHelper::msg_
MsgConstPtr msg_
Definition: test_subscriber.cpp:130
message_filters::Subscriber
ROS subscription filter.
Definition: subscriber.h:127
Msg
roscpp::Logger Msg
Definition: test_subscriber.cpp:43
NonConstHelper::cb
void cb(const MsgPtr &msg)
Definition: test_subscriber.cpp:135
ConstHelper::cb
void cb(const MsgConstPtr &msg)
Definition: test_subscriber.cpp:125
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())
chain.h
MsgConstPtr
roscpp::LoggerConstPtr MsgConstPtr
Definition: test_subscriber.cpp:45
start
ROSCPP_DECL void start()
NonConstHelper::msg_
MsgPtr msg_
Definition: test_subscriber.cpp:140
ros::Time
message_filters::SimpleFilter::registerCallback
Connection registerCallback(const C &callback)
Register a callback to be called when this filter has passed.
Definition: simple_filter.h:137
ros::Duration::sleep
bool sleep() const
message_filters::Subscriber::subscribe
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
Subscribe to a topic.
Definition: subscriber.h:172
message_filters
Definition: cache.h:47
message_filters::Chain
Chains a dynamic number of simple filters together. Allows retrieval of filters by index after they a...
Definition: chain.h:143
message_filters::Chain::addFilter
size_t addFilter(F *filter)
Add a filter to this chain, by bare pointer. Returns the index of that filter in the chain.
Definition: chain.h:176
ros::Duration
MsgPtr
roscpp::LoggerPtr MsgPtr
Definition: test_subscriber.cpp:44
ros::NodeHandle
ros::Subscriber
Helper::count_
int32_t count_
Definition: test_chain.cpp:61
ros::Time::now
static Time now()


message_filters
Author(s): Josh Faust, Vijay Pradeep, Dirk Thomas , Jacob Perron
autogenerated on Thu Nov 23 2023 04:01:54