swri_node_handle_test.cpp
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2022, Southwest Research Institute® (SwRI®)
4 // All rights reserved.
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are met:
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 Southwest Research Institute® (SwRI®) nor the
14 // names of its contributors may be used to endorse or promote products
15 // derived from 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 SOUTHWEST RESEARCH INSTITUTE BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //
28 // *****************************************************************************
29 
30 #include <gtest/gtest.h>
31 
32 #include <ros/ros.h>
34 #include <std_msgs/Empty.h>
35 
36 class SwriNodeHandleTest : public testing::Test
37 {
38 public:
39  SwriNodeHandleTest() : nh_(ros::NodeHandle(), ros::NodeHandle("~"), "Testing the swri::NodeHandle")
40  {
41  }
42 
43 protected:
44  void SetUp() override
45  {
46  }
47 
48  void spinNumTimes(size_t num) const
49  {
50  for (auto i=0; i < num; ++i)
51  {
52  ros::spinOnce();
53  delay_.sleep();
54  }
55  }
56 
59 };
60 
61 void emptyCb(const std_msgs::EmptyConstPtr &msg)
62 {
63  // Empty
64 }
65 
66 TEST_F(SwriNodeHandleTest, testConnectCbAdvertise)
67 {
68  bool connection_called = false;
69  auto connect_cb = [&connection_called](const ros::SingleSubscriberPublisher &){
70  connection_called = true;
71  };
72  ros::Publisher test_pub = nh_.advertise<std_msgs::Empty>("test", 1,
73  connect_cb,
76 
77  ros::Subscriber empty_sub = nh_.subscribe<std_msgs::Empty>("test",
78  1,
79  emptyCb,
80  "test subscribe");
81  spinNumTimes(2);
82  EXPECT_TRUE(connection_called);
83 
84  ASSERT_TRUE(nh_.getEnableDocs());
85  auto doc_msg = nh_.getDocMsg();
86 
87  bool found_test_topic=false;
88  for (const auto &topic : doc_msg.topics)
89  {
90  if (topic.name == "test")
91  {
92  found_test_topic = true;
93  }
94  }
95  EXPECT_TRUE(found_test_topic);
96 }
97 
98 TEST_F(SwriNodeHandleTest, testAdvertiseOptions)
99 {
100  bool cb_called=false;
101  auto empty_cb = [&cb_called](const std_msgs::EmptyConstPtr &msg){ cb_called = true; };
102  // Don't use swri nodehandle to only have 1 "test" topic doc in documentation message
103  ros::NodeHandle public_nh;
104  ros::Subscriber empty_sub = public_nh.subscribe<std_msgs::Empty>("test", 1, empty_cb);
105 
107  ops.init<std_msgs::Empty>("test", 1, ros::SubscriberStatusCallback(), ros::SubscriberStatusCallback());
108  ops.tracked_object = ros::VoidConstPtr();
109  ops.latch = false;
110  ros::Publisher empty_pub = nh_.advertise(ops);
111  empty_pub.publish(boost::make_shared<std_msgs::Empty>());
112 
113  spinNumTimes(3);
114  EXPECT_TRUE(cb_called);
115 
116  ASSERT_TRUE(nh_.getEnableDocs());
117  auto doc_msg = nh_.getDocMsg();
118 
119  bool found_test_topic=false;
120  for (const auto &topic : doc_msg.topics)
121  {
122  if (topic.name == "test")
123  {
124  found_test_topic = true;
125  }
126  }
127  EXPECT_TRUE(found_test_topic);
128 }
129 
130 int main(int argc, char **argv)
131 {
132  ros::init(argc, argv, "swri_node_handle_test");
133  testing::InitGoogleTest(&argc, argv);
134  int result = RUN_ALL_TESTS();
135  return result;
136 }
swri::NodeHandle
Definition: node_handle.h:51
SwriNodeHandleTest::SwriNodeHandleTest
SwriNodeHandleTest()
Definition: swri_node_handle_test.cpp:39
msg
msg
ros::Publisher
main
int main(int argc, char **argv)
Definition: swri_node_handle_test.cpp:130
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros
ros.h
ros::spinOnce
ROSCPP_DECL void spinOnce()
emptyCb
void emptyCb(const std_msgs::EmptyConstPtr &msg)
Definition: swri_node_handle_test.cpp:61
SwriNodeHandleTest::spinNumTimes
void spinNumTimes(size_t num) const
Definition: swri_node_handle_test.cpp:48
ros::SubscriberStatusCallback
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
SwriNodeHandleTest::nh_
swri::NodeHandle nh_
Definition: swri_node_handle_test.cpp:58
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::AdvertiseOptions
SwriNodeHandleTest
Definition: swri_node_handle_test.cpp:36
ros::SingleSubscriberPublisher
ros::VoidConstPtr
boost::shared_ptr< void const > VoidConstPtr
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())
SwriNodeHandleTest::SetUp
void SetUp() override
Definition: swri_node_handle_test.cpp:44
TEST_F
TEST_F(SwriNodeHandleTest, testConnectCbAdvertise)
Definition: swri_node_handle_test.cpp:66
ros::AdvertiseOptions::init
void init(const std::string &_topic, uint32_t _queue_size, const SubscriberStatusCallback &_connect_cb=SubscriberStatusCallback(), const SubscriberStatusCallback &_disconnect_cb=SubscriberStatusCallback())
SwriNodeHandleTest::delay_
ros::Duration delay_
Definition: swri_node_handle_test.cpp:57
ros::Duration::sleep
bool sleep() const
ros::Duration
node_handle.h
ros::NodeHandle
ros::Subscriber


swri_roscpp
Author(s): P. J. Reed
autogenerated on Thu Jun 6 2024 02:33:09