realtime_publisher_tests.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2019, Open Source Robotics Foundation, 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 the 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 #include <gmock/gmock.h>
32 #include <std_msgs/String.h>
33 #include <chrono>
34 #include <mutex>
35 #include <thread>
36 
38 
39 TEST(RealtimePublisher, construct_destruct)
40 {
41  ros::NodeHandle nh;
42  RealtimePublisher<std_msgs::String> rt_pub(nh, "construct_destruct", 10);
43 }
44 
45 TEST(RealtimePublisher, construct_init_destruct)
46 {
48  ros::NodeHandle nh;
49  rt_pub.init(nh, "construct_init_destruct", 10);
50 }
51 
53 {
54  std_msgs::String msg_;
55  std::mutex mtx_;
56 
57  void callback(const std_msgs::String & msg)
58  {
59  std::unique_lock<std::mutex> lock(mtx_);
60  msg_ = msg;
61  }
62 };
63 
64 TEST(RealtimePublisher, rt_publish)
65 {
66  const size_t ATTEMPTS = 10;
67  const std::chrono::milliseconds DELAY(250);
68 
69  const char * expected_msg = "Hello World";
70  ros::NodeHandle nh;
71  const bool latching = true;
72  RealtimePublisher<std_msgs::String> rt_pub(nh, "rt_publish", 10, latching);
73  // publish a latched message
74  bool lock_is_held = rt_pub.trylock();
75  for (size_t i = 0; i < ATTEMPTS && !lock_is_held; ++i)
76  {
77  lock_is_held = rt_pub.trylock();
78  std::this_thread::sleep_for(DELAY);
79  }
80  ASSERT_TRUE(lock_is_held);
81  rt_pub.msg_.data = expected_msg;
82  rt_pub.unlockAndPublish();
83 
84  // make sure subscriber gets it
85  StringCallback str_callback;
86 
87  ros::Subscriber sub = nh.subscribe("rt_publish", 10, &StringCallback::callback, &str_callback);
88  for (size_t i = 0; i < ATTEMPTS && str_callback.msg_.data.empty(); ++i)
89  {
90  ros::spinOnce();
91  std::this_thread::sleep_for(DELAY);
92  }
93  EXPECT_STREQ(expected_msg, str_callback.msg_.data.c_str());
94 }
95 
96 int main(int argc, char ** argv) {
97  ::testing::InitGoogleTest(&argc, argv);
98  ros::init(argc, argv, "realtime_publisher_tests");
99  return RUN_ALL_TESTS();
100 }
const size_t ATTEMPTS
Msg msg_
The msg_ variable contains the data that will get published on the ROS topic.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void unlockAndPublish()
Unlock the msg_ variable.
int main(int argc, char **argv)
const std::chrono::milliseconds DELAY(250)
bool trylock()
Try to get the data lock from realtime.
TEST(RealtimePublisher, construct_destruct)
void init(const ros::NodeHandle &node, const std::string &topic, int queue_size, bool latched=false)
ROSCPP_DECL void spinOnce()
void callback(const std_msgs::String &msg)


realtime_tools
Author(s): Stuart Glaser
autogenerated on Mon Feb 28 2022 23:22:45