compatibility.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018, 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 #ifndef NEONAVIGATION_COMMON_COMPATIBILITY_H
31 #define NEONAVIGATION_COMMON_COMPATIBILITY_H
32 
33 #include <ros/ros.h>
34 
35 #include <string>
36 
38 {
39 namespace compat
40 {
41 #define STATIC_ASSERT(EXPR) static_assert(EXPR, #EXPR)
42 
43 // Update cycle
44 // 1. Increment current_level and indicate topic changes using mcl_3dl_compat::subscribe/advertise.
45 // Set default_level to supported_level.
46 // 2. Set default_level to current_level.
47 // 3. Increment supported_level and remove old topic names.
48 const int current_level = 1;
49 const int supported_level = 0;
51 
52 STATIC_ASSERT(supported_level <= current_level && current_level <= supported_level + 1);
53 STATIC_ASSERT(supported_level <= default_level && default_level <= current_level);
54 
55 int getCompat()
56 {
57  int compat(default_level);
58  ros::NodeHandle("/").param("neonavigation_compatible", compat, compat);
59 
60  return compat;
61 }
63 {
64  if (getCompat() < supported_level)
65  {
66  const std::string message =
67  "======= [Obsolated] your configuration for " + ros::this_node::getName() + " is outdated =======";
68  ROS_FATAL("%s", message.c_str());
69  ros::shutdown();
70  throw std::runtime_error(message);
71  }
72  else if (getCompat() > current_level)
73  {
74  const std::string message =
75  "======= [Unsupported] your configuration for " + ros::this_node::getName() + " is futuredated =======";
76  ROS_FATAL("%s", message.c_str());
77  ros::shutdown();
78  throw std::runtime_error(message);
79  }
80  else if (getCompat() != current_level)
81  {
83  "======= [Deprecated] %s is run in compatible mode =======\n"
84  "=========================================================\n"
85  "Set _compatible:=%d to switch to new topic namespaces.\n"
86  "Compatible mode will be obsolated in the future update.\n"
87  "=========================================================",
88  ros::this_node::getName().c_str(), current_level);
89  }
90 }
92 {
94  return std::string("~/");
95  if (nh.getUnresolvedNamespace() == std::string())
96  return std::string();
97  return nh.getNamespace() + "/";
98 }
99 template <class M>
101  ros::NodeHandle& nh_new,
102  const std::string& topic_new,
103  ros::NodeHandle& nh_old,
104  const std::string& topic_old,
105  uint32_t queue_size,
106  void (*fp)(M),
107  const ros::TransportHints& transport_hints = ros::TransportHints())
108 {
109  if (getCompat() != current_level)
110  {
111  ROS_ERROR(
112  "Use %s (%s%s) topic instead of %s (%s%s)",
113  nh_new.resolveName(topic_new, false).c_str(),
114  getSimplifiedNamespace(nh_new).c_str(), topic_new.c_str(),
115  nh_old.resolveName(topic_old, false).c_str(),
116  getSimplifiedNamespace(nh_old).c_str(), topic_old.c_str());
117  return nh_old.subscribe(topic_old, queue_size, fp, transport_hints);
118  }
119  else
120  {
121  return nh_new.subscribe(topic_new, queue_size, fp, transport_hints);
122  }
123 }
124 template <class M, class T>
126  ros::NodeHandle& nh_new,
127  const std::string& topic_new,
128  ros::NodeHandle& nh_old,
129  const std::string& topic_old,
130  uint32_t queue_size,
131  void (T::*fp)(M) const,
132  T* obj,
133  const ros::TransportHints& transport_hints = ros::TransportHints())
134 {
135  if (getCompat() != current_level)
136  {
137  ROS_ERROR(
138  "Use %s (%s%s) topic instead of %s (%s%s)",
139  nh_new.resolveName(topic_new, false).c_str(),
140  getSimplifiedNamespace(nh_new).c_str(), topic_new.c_str(),
141  nh_old.resolveName(topic_old, false).c_str(),
142  getSimplifiedNamespace(nh_old).c_str(), topic_old.c_str());
143  return nh_old.subscribe(topic_old, queue_size, fp, obj, transport_hints);
144  }
145  else
146  {
147  return nh_new.subscribe(topic_new, queue_size, fp, obj, transport_hints);
148  }
149 }
150 template <class M, class T>
152  ros::NodeHandle& nh_new,
153  const std::string& topic_new,
154  ros::NodeHandle& nh_old,
155  const std::string& topic_old,
156  uint32_t queue_size,
157  void (T::*fp)(M),
158  T* obj,
159  const ros::TransportHints& transport_hints = ros::TransportHints())
160 {
161  if (getCompat() != current_level)
162  {
163  ROS_ERROR(
164  "Use %s (%s%s) topic instead of %s (%s%s)",
165  nh_new.resolveName(topic_new, false).c_str(),
166  getSimplifiedNamespace(nh_new).c_str(), topic_new.c_str(),
167  nh_old.resolveName(topic_old, false).c_str(),
168  getSimplifiedNamespace(nh_old).c_str(), topic_old.c_str());
169  return nh_old.subscribe(topic_old, queue_size, fp, obj, transport_hints);
170  }
171  else
172  {
173  return nh_new.subscribe(topic_new, queue_size, fp, obj, transport_hints);
174  }
175 }
176 template <class M>
178  ros::NodeHandle& nh_new,
179  const std::string& topic_new,
180  ros::NodeHandle& nh_old,
181  const std::string& topic_old,
182  uint32_t queue_size,
183  const boost::function<void(const boost::shared_ptr<M const>&)>& callback,
184  const ros::VoidConstPtr& tracked_object = ros::VoidConstPtr(),
185  const ros::TransportHints& transport_hints = ros::TransportHints())
186 {
187  if (getCompat() != current_level)
188  {
189  ROS_ERROR(
190  "Use %s (%s%s) topic instead of %s (%s%s)",
191  nh_new.resolveName(topic_new, false).c_str(),
192  getSimplifiedNamespace(nh_new).c_str(), topic_new.c_str(),
193  nh_old.resolveName(topic_old, false).c_str(),
194  getSimplifiedNamespace(nh_old).c_str(), topic_old.c_str());
195  return nh_old.subscribe(topic_old, queue_size, callback, tracked_object, transport_hints);
196  }
197  else
198  {
199  return nh_new.subscribe(topic_new, queue_size, callback, tracked_object, transport_hints);
200  }
201 }
202 template <class M>
204  ros::NodeHandle& nh_new,
205  const std::string& topic_new,
206  ros::NodeHandle& nh_old,
207  const std::string& topic_old,
208  uint32_t queue_size,
209  bool latch = false)
210 {
211  if (getCompat() != current_level)
212  {
213  ROS_ERROR(
214  "Use %s (%s%s) topic instead of %s (%s%s)",
215  nh_new.resolveName(topic_new, false).c_str(),
216  getSimplifiedNamespace(nh_new).c_str(), topic_new.c_str(),
217  nh_old.resolveName(topic_old, false).c_str(),
218  getSimplifiedNamespace(nh_old).c_str(), topic_old.c_str());
219  return nh_old.advertise<M>(topic_old, queue_size, latch);
220  }
221  else
222  {
223  return nh_new.advertise<M>(topic_new, queue_size, latch);
224  }
225 }
226 template <class T, class MReq, class MRes>
228  ros::NodeHandle& nh_new,
229  const std::string& service_new,
230  ros::NodeHandle& nh_old,
231  const std::string& service_old,
232  bool (T::*srv_func)(MReq&, MRes&),
233  T* obj)
234 {
235  if (getCompat() != current_level)
236  {
237  ROS_ERROR(
238  "Use %s (%s%s) service instead of %s (%s%s)",
239  nh_new.resolveName(service_new, false).c_str(),
240  getSimplifiedNamespace(nh_new).c_str(), service_new.c_str(),
241  nh_old.resolveName(service_old, false).c_str(),
242  getSimplifiedNamespace(nh_old).c_str(), service_old.c_str());
243  return nh_old.advertiseService(service_old, srv_func, obj);
244  }
245  else
246  {
247  return nh_new.advertiseService(service_new, srv_func, obj);
248  }
249 }
250 
251 template <typename T>
253  const ros::NodeHandle& nh,
254  const std::string& key,
255  T& param,
256  const T& default_value)
257 {
258  if (nh.hasParam(key))
259  {
260  ROS_ERROR(
261  "Use of the parameter %s is deprecated. Don't use this.",
262  nh.resolveName(key, false).c_str());
263  }
264  nh.param(key, param, default_value);
265 }
266 } // namespace compat
267 } // namespace neonavigation_common
268 
269 #endif // NEONAVIGATION_COMMON_COMPATIBILITY_H
std::string getSimplifiedNamespace(ros::NodeHandle &nh)
Definition: compatibility.h:91
const std::string & getUnresolvedNamespace() const
#define ROS_FATAL(...)
STATIC_ASSERT(supported_level<=current_level &&current_level<=supported_level+1)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::string resolveName(const std::string &name, bool remap=true) const
ros::Publisher advertise(ros::NodeHandle &nh_new, const std::string &topic_new, ros::NodeHandle &nh_old, const std::string &topic_old, uint32_t queue_size, bool latch=false)
ROSCPP_DECL const std::string & getName()
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())
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
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)
#define ROS_ERROR_ONCE(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
const std::string & getNamespace() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ROSCPP_DECL void shutdown()
bool hasParam(const std::string &key) const
void deprecatedParam(const ros::NodeHandle &nh, const std::string &key, T &param, const T &default_value)
#define ROS_ERROR(...)


neonavigation_common
Author(s): Atsushi Watanabe
autogenerated on Tue Jul 9 2019 04:59:45