22 #include <gtest/gtest.h> 23 #include <std_msgs/Empty.h> 32 void process_pending_events()
34 using namespace std::chrono_literals;
35 std::this_thread::sleep_for(50ms);
40 TEST(fkie_message_filters_ros_integration, PublisherMessage)
42 std::size_t received_msgs = 0;
44 ros::Subscriber sub = nh.
subscribe<std_msgs::Empty>(
"publisher_test", 1, [&received_msgs](
const std_msgs::EmptyConstPtr&) { ++received_msgs; });
47 src.connect_to_sink(pub);
50 process_pending_events();
52 ASSERT_EQ(0, received_msgs);
53 src(std_msgs::Empty());
54 process_pending_events();
55 ASSERT_EQ(1, received_msgs);
58 TEST(fkie_message_filters_ros_integration, PublisherMessageConstPtr)
60 std::size_t received_msgs = 0;
62 ros::Subscriber sub = nh.
subscribe<std_msgs::Empty>(
"publisher_test", 1, [&received_msgs](
const std_msgs::EmptyConstPtr&) { ++received_msgs; });
65 src.connect_to_sink(pub);
68 process_pending_events();
70 ASSERT_EQ(0, received_msgs);
71 src(std_msgs::Empty::ConstPtr(
new std_msgs::Empty()));
72 process_pending_events();
73 ASSERT_EQ(1, received_msgs);
76 TEST(fkie_message_filters_ros_integration, PublisherMessageStdSharedPtr)
78 std::size_t received_msgs = 0;
80 ros::Subscriber sub = nh.
subscribe<std_msgs::Empty>(
"publisher_test", 1, [&received_msgs](
const std_msgs::EmptyConstPtr&) { ++received_msgs; });
83 src.connect_to_sink(pub);
86 process_pending_events();
88 ASSERT_EQ(0, received_msgs);
89 src(std::shared_ptr<const std_msgs::Empty>(
new std_msgs::Empty()));
90 process_pending_events();
91 ASSERT_EQ(1, received_msgs);
94 TEST(fkie_message_filters_ros_integration, PublisherMessageEvent)
96 std::size_t received_msgs = 0;
98 ros::Subscriber sub = nh.
subscribe<std_msgs::Empty>(
"publisher_test", 1, [&received_msgs](
const std_msgs::EmptyConstPtr&) { ++received_msgs; });
101 src.connect_to_sink(pub);
104 process_pending_events();
106 ASSERT_EQ(0, received_msgs);
108 process_pending_events();
109 ASSERT_EQ(1, received_msgs);
112 TEST(fkie_message_filters_ros_integration, PublisherWithSubscriberCB)
114 std::size_t received_msgs = 0, connected_cbs = 0, disconnected_cbs = 0;
123 process_pending_events();
125 ASSERT_EQ(0, connected_cbs);
126 ASSERT_EQ(0, disconnected_cbs);
127 ros::Subscriber sub = nh.
subscribe<std_msgs::Empty>(
"publisher_test", 1, [&received_msgs](
const std_msgs::EmptyConstPtr&) { ++received_msgs; });
128 process_pending_events();
130 ASSERT_EQ(0, received_msgs);
131 ASSERT_EQ(1, connected_cbs);
132 ASSERT_EQ(0, disconnected_cbs);
133 src(std_msgs::Empty());
134 process_pending_events();
135 ASSERT_EQ(1, received_msgs);
137 process_pending_events();
138 ASSERT_EQ(1, connected_cbs);
139 ASSERT_EQ(1, disconnected_cbs);
142 TEST(fkie_message_filters_ros_integration, SubscriberMessageEvent)
144 std::size_t received_msgs = 0;
152 sub.subscribe(nh,
"subscriber_test", 1);
153 process_pending_events();
155 ASSERT_EQ(0, received_msgs);
156 pub.
publish<std_msgs::Empty>(std_msgs::Empty());
157 process_pending_events();
158 ASSERT_EQ(1, received_msgs);
161 TEST(fkie_message_filters_ros_integration, SubscriberMessageConstPtr)
163 std::size_t received_msgs = 0;
169 flt.
set_processing_function([&received_msgs](
const std_msgs::Empty::ConstPtr&) ->
bool { ++received_msgs;
return true; });
171 sub.subscribe(nh,
"subscriber_test", 1);
172 process_pending_events();
174 ASSERT_EQ(0, received_msgs);
175 pub.
publish<std_msgs::Empty>(std_msgs::Empty());
176 process_pending_events();
177 ASSERT_EQ(1, received_msgs);
180 TEST(fkie_message_filters_ros_integration, SubscriberMessageStdSharedPtr)
182 std::size_t received_msgs = 0;
188 flt.
set_processing_function([&received_msgs](
const std::shared_ptr<const std_msgs::Empty>&) ->
bool { ++received_msgs;
return true; });
190 sub.subscribe(nh,
"subscriber_test", 1);
191 process_pending_events();
193 ASSERT_EQ(0, received_msgs);
194 pub.
publish<std_msgs::Empty>(std_msgs::Empty());
195 process_pending_events();
196 ASSERT_EQ(1, received_msgs);
199 TEST(fkie_message_filters_ros_integration, SubscriberMessage)
201 std::size_t received_msgs = 0;
207 flt.
set_processing_function([&received_msgs](
const std_msgs::Empty&) ->
bool { ++received_msgs;
return true; });
209 sub.subscribe(nh,
"subscriber_test", 1);
210 process_pending_events();
212 ASSERT_EQ(0, received_msgs);
213 pub.
publish<std_msgs::Empty>(std_msgs::Empty());
214 process_pending_events();
215 ASSERT_EQ(1, received_msgs);
218 int main (
int argc,
char** argv)
220 testing::InitGoogleTest(&argc, argv);
221 ros::init (argc, argv,
"test_publish_subscribe");
223 return RUN_ALL_TESTS();
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void set_processing_function(const ProcessingFunction &f) noexcept
Set the user-defined processing function.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
uint32_t getNumPublishers() const
Publish consumed data on a ROS topic.
Subscribe to a ROS topic as data provider.
void advertise(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, bool latch=false, ros::CallbackQueueInterface *callback_queue=nullptr) noexcept
Advertise ROS topic.
int main(int argc, char **argv)
void publish(const boost::shared_ptr< M > &message) const
Connection connect_to_sink(Sink< Outputs... > &dst) noexcept
Connect this source to a sink.
TEST(fkie_message_filters_ros_integration, PublisherMessage)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
Manually operated data source.
uint32_t getNumSubscribers() const
Simplified filter with user-defined callback function.
ROSCPP_DECL void spinOnce()
virtual bool is_active() const noexcept override
Check if the ROS publisher has at least one subscriber.