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