latching_publisher.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
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: Josh Faust */
31 
32 #include <string>
33 #include <sstream>
34 #include <fstream>
35 
36 #include <gtest/gtest.h>
37 
38 #include <time.h>
39 #include <stdlib.h>
40 
41 #include "ros/ros.h"
42 #include <test_roscpp/TestArray.h>
43 
44 using namespace ros;
45 using namespace test_roscpp;
46 
47 std::string g_node_name = "test_latching_publisher";
48 
49 class Helper
50 {
51 public:
53  : count_(0)
54  {}
55 
56  void cb(const ros::MessageEvent<TestArray>& msg_event)
57  {
58  ++count_;
59  last_msg_event_ = msg_event;
60  }
61 
62  int32_t count_;
64 };
65 
66 TEST(RoscppLatchingPublisher, nonLatching)
67 {
69  ros::Publisher pub = n.advertise<TestArray>("test", 1, false);
70  TestArray arr;
71  pub.publish(arr);
72 
73  Helper h;
74  ros::Subscriber sub = n.subscribe("test", 1, &Helper::cb, &h);
75  ros::Duration(0.1).sleep();
76  ros::spinOnce();
77 
78  ASSERT_EQ(h.count_, 0);
79 }
80 
81 TEST(RoscppLatchingPublisher, latching)
82 {
84  ros::Publisher pub = n.advertise<TestArray>("test", 1, true);
85  TestArray arr;
86  pub.publish(arr);
87 
88  Helper h;
89  ros::Subscriber sub = n.subscribe("test", 1, &Helper::cb, &h);
90  ros::Duration(0.1).sleep();
91  ros::spinOnce();
92 
93  ASSERT_EQ(h.count_, 1);
94 
95  ASSERT_STREQ(h.last_msg_event_.getConnectionHeader()["latching"].c_str(), "1");
96 }
97 
98 TEST(RoscppLatchingPublisher, latchingMultipleSubscriptions)
99 {
100  ros::NodeHandle n;
101  ros::Publisher pub = n.advertise<TestArray>("test", 1, true);
102  TestArray arr;
103  pub.publish(arr);
104 
105  Helper h1, h2;
106  ros::Subscriber sub1 = n.subscribe("test", 1, &Helper::cb, &h1);
107  ros::Duration(0.1).sleep();
108  ros::spinOnce();
109 
110  ASSERT_EQ(h1.count_, 1);
111  ASSERT_EQ(h2.count_, 0);
112 
113  ros::Subscriber sub2 = n.subscribe("test", 1, &Helper::cb, &h2);
114  ros::spinOnce();
115 
116  ASSERT_EQ(h1.count_, 1);
117  ASSERT_EQ(h2.count_, 1);
118 }
119 
120 int main(int argc, char** argv)
121 {
122  testing::InitGoogleTest(&argc, argv);
123  ros::init(argc, argv, g_node_name);
124 
125  ros::NodeHandle nh;
126 
127  return RUN_ALL_TESTS();
128 }
129 
void publish(const boost::shared_ptr< M > &message) const
int32_t count_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool sleep() const
M_string & getConnectionHeader() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::string g_node_name
TEST(RoscppLatchingPublisher, nonLatching)
int main(int argc, char **argv)
void cb(const ros::MessageEvent< TestArray > &msg_event)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ROSCPP_DECL void spinOnce()
ros::MessageEvent< TestArray > last_msg_event_


test_roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas
autogenerated on Mon Nov 2 2020 03:52:46