test_compat.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018-2020, the neonavigation authors
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 copyright holder 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 <cstdlib>
31 
32 #include <ros/ros.h>
33 #include <std_msgs/Bool.h>
34 #include <std_srvs/Empty.h>
35 
36 #include <gtest/gtest.h>
37 
38 #define UNDEF_COMPATIBILITY_LEVEL
39 
40 namespace neonavigation_common
41 {
42 namespace compat
43 {
44 int current_level;
45 int supported_level;
46 int default_level;
47 } // namespace compat
48 } // namespace neonavigation_common
50 
51 TEST(NeonavigationCompat, CompatMode)
52 {
56 
57  ros::NodeHandle("/").setParam("neonavigation_compatible", 2);
58  ASSERT_NO_THROW(
59  {
61  }); // NOLINT(whitespace/braces)
62 
63  ros::NodeHandle("/").setParam("neonavigation_compatible", 3);
64  ASSERT_NO_THROW(
65  {
67  }); // NOLINT(whitespace/braces)
68 
69  ros::NodeHandle("/").setParam("neonavigation_compatible", 4);
70  ASSERT_THROW(
71  {
73  }, // NOLINT(whitespace/braces)
74  std::runtime_error);
75 
76  ros::NodeHandle("/").setParam("neonavigation_compatible", 1);
77  ASSERT_THROW(
78  {
80  }, // NOLINT(whitespace/braces)
81  std::runtime_error);
82 }
83 
85 {
86 public:
89  std_msgs::Bool::ConstPtr msg_;
90  mutable std_msgs::Bool::ConstPtr msg_const_;
92 
93  void cb(const std_msgs::Bool::ConstPtr& msg)
94  {
95  msg_ = msg;
96  }
97  void cbConst(const std_msgs::Bool::ConstPtr& msg) const
98  {
99  msg_const_ = msg;
100  }
101 
102  bool cbSrv(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res)
103  {
104  srv_called_ = true;
105  return true;
106  }
107 
109  : pnh_("~")
110  , srv_called_(false)
111  {
112  }
113 };
114 
115 TEST(NeonavigationCompat, Subscribe)
116 {
120 
122 
123  ros::Publisher pub_old = cls.pnh_.advertise<std_msgs::Bool>("test_old", 1, true);
124  ros::Publisher pub_new = cls.nh_.advertise<std_msgs::Bool>("test_new", 1, true);
125  std_msgs::Bool msg;
126  msg.data = false;
127  pub_old.publish(msg);
128  msg.data = true;
129  pub_new.publish(msg);
130 
131  {
132  ros::NodeHandle("/").setParam("neonavigation_compatible", 2);
134  cls.nh_, "test_new",
135  cls.pnh_, "test_old",
136  1,
138  ros::Duration(0.1).sleep();
139  ros::spinOnce();
140  ASSERT_TRUE(static_cast<bool>(cls.msg_));
141  ASSERT_EQ(false, static_cast<bool>(cls.msg_->data));
142  }
143 
144  {
145  ros::NodeHandle("/").setParam("neonavigation_compatible", 3);
146  cls.msg_ = nullptr;
148  cls.nh_, "test_new",
149  cls.pnh_, "test_old",
150  1,
152  ros::Duration(0.1).sleep();
153  ros::spinOnce();
154  ASSERT_TRUE(static_cast<bool>(cls.msg_));
155  ASSERT_EQ(true, static_cast<bool>(cls.msg_->data));
156  }
157 
158  {
159  ros::NodeHandle("/").setParam("neonavigation_compatible", 2);
160  cls.msg_ = nullptr;
162  cls.nh_, "test_new",
163  cls.pnh_, "test_old",
164  1,
166  ros::Duration(0.1).sleep();
167  ros::spinOnce();
168  ASSERT_TRUE(static_cast<bool>(cls.msg_const_));
169  ASSERT_EQ(false, static_cast<bool>(cls.msg_const_->data));
170  }
171 
172  {
173  ros::NodeHandle("/").setParam("neonavigation_compatible", 3);
174  cls.msg_ = nullptr;
176  cls.nh_, "test_new",
177  cls.pnh_, "test_old",
178  1,
180  ros::Duration(0.1).sleep();
181  ros::spinOnce();
182  ASSERT_TRUE(static_cast<bool>(cls.msg_const_));
183  ASSERT_EQ(true, static_cast<bool>(cls.msg_const_->data));
184  }
185 }
186 
187 TEST(NeonavigationCompat, AdvertiseService)
188 {
192 
194  ros::ServiceClient cli_new = cls.nh_.serviceClient<std_srvs::Empty>("srv_new");
195  ros::ServiceClient cli_old = cls.pnh_.serviceClient<std_srvs::Empty>("srv_old");
196 
197  ros::AsyncSpinner spinner(1);
198  spinner.start();
199 
200  {
201  ros::NodeHandle("/").setParam("neonavigation_compatible", 2);
202 
204  cls.nh_, "srv_new",
205  cls.pnh_, "srv_old",
207  ros::Duration(0.1).sleep();
208  std_srvs::Empty empty;
209  ASSERT_TRUE(cli_old.call(empty.request, empty.response));
210  }
211 
212  {
213  ros::NodeHandle("/").setParam("neonavigation_compatible", 3);
214 
216  cls.nh_, "srv_new",
217  cls.pnh_, "srv_old",
219  ros::Duration(0.1).sleep();
220  std_srvs::Empty empty;
221  ASSERT_TRUE(cli_new.call(empty.request, empty.response));
222  }
223 
224  spinner.stop();
225 }
226 
227 int main(int argc, char** argv)
228 {
229  testing::InitGoogleTest(&argc, argv);
230  ros::init(argc, argv, "test_compat");
231 
232  return RUN_ALL_TESTS();
233 }
ros::Publisher
compatibility.h
NeonavigationCompatCallbacks::NeonavigationCompatCallbacks
NeonavigationCompatCallbacks()
Definition: test_compat.cpp:108
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
NeonavigationCompatCallbacks::srv_called_
bool srv_called_
Definition: test_compat.cpp:91
ros::AsyncSpinner
ros::NodeHandle::serviceClient
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ros::spinOnce
ROSCPP_DECL void spinOnce()
NeonavigationCompatCallbacks::cb
void cb(const std_msgs::Bool::ConstPtr &msg)
Definition: test_compat.cpp:93
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
neonavigation_common::compat::subscribe
ros::Subscriber subscribe(ros::NodeHandle &nh_new, const std::string &topic_new, ros::NodeHandle &nh_old, const std::string &topic_old, uint32_t queue_size, void(*fp)(M), const ros::TransportHints &transport_hints=ros::TransportHints())
Definition: compatibility.h:102
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ServiceServer
neonavigation_common::compat::advertiseService
ros::ServiceServer advertiseService(ros::NodeHandle &nh_new, const std::string &service_new, ros::NodeHandle &nh_old, const std::string &service_old, bool(T::*srv_func)(MReq &, MRes &), T *obj)
Definition: compatibility.h:229
main
int main(int argc, char **argv)
Definition: test_compat.cpp:227
NeonavigationCompatCallbacks::msg_const_
std_msgs::Bool::ConstPtr msg_const_
Definition: test_compat.cpp:90
NeonavigationCompatCallbacks::cbSrv
bool cbSrv(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Definition: test_compat.cpp:102
neonavigation_common::compat::current_level
const int current_level
Definition: compatibility.h:49
ros::ServiceClient
NeonavigationCompatCallbacks
Definition: test_compat.cpp:84
neonavigation_common::compat::checkCompatMode
void checkCompatMode()
Definition: compatibility.h:64
NeonavigationCompatCallbacks::nh_
ros::NodeHandle nh_
Definition: test_compat.cpp:87
TEST
TEST(NeonavigationCompat, CompatMode)
Definition: test_compat.cpp:51
neonavigation_common::compat::supported_level
const int supported_level
Definition: compatibility.h:50
NeonavigationCompatCallbacks::msg_
std_msgs::Bool::ConstPtr msg_
Definition: test_compat.cpp:89
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
neonavigation_common::compat::default_level
const int default_level
Definition: compatibility.h:51
ros::Duration::sleep
bool sleep() const
neonavigation_common
Definition: compatibility.h:37
ros::Duration
NeonavigationCompatCallbacks::pnh_
ros::NodeHandle pnh_
Definition: test_compat.cpp:88
ros::NodeHandle
ros::Subscriber
NeonavigationCompatCallbacks::cbConst
void cbConst(const std_msgs::Bool::ConstPtr &msg) const
Definition: test_compat.cpp:97


neonavigation_common
Author(s): Atsushi Watanabe
autogenerated on Fri May 16 2025 02:15:07