multiple_latched_publishers.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018, Intermodalics BVBA.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 /* Author: Hans-Joachim Krauch */
31 
32 /*
33  * Verify that every latched publisher sends its last published message to
34  * a newly connected subscriber.
35  */
36 
37 #include <chrono>
38 #include <future>
39 #include <vector>
40 
41 #include <gtest/gtest.h>
42 #include "ros/ros.h"
43 #include "ros/topic_manager.h"
44 #include <std_msgs/builtin_bool.h>
45 
46 
47 TEST(MultipleLatchedPublishers, LatchedPublisherReceiveMultiple)
48 {
49  ros::NodeHandle nh;
50  std::vector<ros::Publisher> latched_publishers = {
51  nh.advertise<bool>("foo", 10, true),
52  nh.advertise<bool>("foo", 10, true),
53  nh.advertise<bool>("foo", 10, true),
54  };
55  std::vector<ros::Publisher> unlatched_publishers = {
56  nh.advertise<bool>("foo", 10, false),
57  nh.advertise<bool>("foo", 10, false),
58  };
59 
60  for (auto& pub : latched_publishers) {
61  pub.publish(true);
62  }
63  for (auto& pub : unlatched_publishers) {
64  pub.publish(true);
65  }
66 
67  std::size_t msg_count = 0;
68  std::promise<bool> received_promise;
69  auto received_future = received_promise.get_future();
70 
71  const auto sub = nh.subscribe<std_msgs::Bool>("foo", 10, [&](const std_msgs::Bool::ConstPtr&) {
72  if (++msg_count == latched_publishers.size()) {
73  received_promise.set_value(true);
74  }
75  });
76 
77  ASSERT_EQ(std::future_status::ready, received_future.wait_for(std::chrono::seconds(1)));
78  const auto received = received_future.get();
79  EXPECT_TRUE(received);
80  EXPECT_EQ(latched_publishers.size(), msg_count);
81 }
82 
83 TEST(MultipleLatchedPublishers, TopicManagerIsLatched)
84 {
85  ros::NodeHandle nh;
86  std::vector<ros::Publisher> publishers_bar = {
87  nh.advertise<bool>("bar", 10, false),
88  nh.advertise<bool>("bar", 10, true),
89  nh.advertise<bool>("bar", 10, false),
90  };
91  EXPECT_TRUE(ros::TopicManager::instance()->isLatched("/bar"));
92 
93  std::vector<ros::Publisher> publishers_baz = {
94  nh.advertise<bool>("baz", 10, false),
95  nh.advertise<bool>("baz", 10, false),
96  };
97  EXPECT_FALSE(ros::TopicManager::instance()->isLatched("/baz"));
98 }
99 
100 TEST(MultipleLatchedPublishers, TopicManagerLatchShutdown)
101 {
102  ros::NodeHandle nh;
103  ros::Publisher qux_latched = nh.advertise<bool>("qux", 10, true);
104  ros::Publisher qux_unlatched = nh.advertise<bool>("qux", 10, false);
105  EXPECT_TRUE(ros::TopicManager::instance()->isLatched("/qux"));
106 
107  qux_latched.shutdown();
108  EXPECT_FALSE(ros::TopicManager::instance()->isLatched("/qux"));
109 }
110 
111 int main(int argc, char **argv) {
112  ::testing::InitGoogleTest(&argc, argv);
113  ros::init(argc, argv, "test_multiple_latched_publishers");
114  ros::AsyncSpinner spinner(1);
115  spinner.start();
116  return RUN_ALL_TESTS();
117 }
118 
ros::Publisher
topic_manager.h
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
builtin_bool.h
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::Publisher::shutdown
void shutdown()
main
int main(int argc, char **argv)
Definition: multiple_latched_publishers.cpp:111
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())
ros::TopicManager::instance
static const TopicManagerPtr & instance()
TEST
TEST(MultipleLatchedPublishers, LatchedPublisherReceiveMultiple)
Definition: multiple_latched_publishers.cpp:47
ros::NodeHandle


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