30 #ifndef NEONAVIGATION_COMMON_COMPATIBILITY_H 31 #define NEONAVIGATION_COMMON_COMPATIBILITY_H 41 #define STATIC_ASSERT(EXPR) static_assert(EXPR, #EXPR) 52 STATIC_ASSERT(supported_level <= current_level && current_level <= supported_level + 1);
53 STATIC_ASSERT(supported_level <= default_level && default_level <= current_level);
57 int compat(default_level);
66 const std::string message =
70 throw std::runtime_error(message);
74 const std::string message =
78 throw std::runtime_error(message);
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 "=========================================================",
94 return std::string(
"~/");
102 const std::string& topic_new,
104 const std::string& topic_old,
112 "Use %s (%s%s) topic instead of %s (%s%s)",
117 return nh_old.
subscribe(topic_old, queue_size, fp, transport_hints);
121 return nh_new.
subscribe(topic_new, queue_size, fp, transport_hints);
124 template <
class M,
class T>
127 const std::string& topic_new,
129 const std::string& topic_old,
131 void (T::*fp)(M)
const,
138 "Use %s (%s%s) topic instead of %s (%s%s)",
143 return nh_old.
subscribe(topic_old, queue_size, fp, obj, transport_hints);
147 return nh_new.
subscribe(topic_new, queue_size, fp, obj, transport_hints);
150 template <
class M,
class T>
153 const std::string& topic_new,
155 const std::string& topic_old,
164 "Use %s (%s%s) topic instead of %s (%s%s)",
169 return nh_old.
subscribe(topic_old, queue_size, fp, obj, transport_hints);
173 return nh_new.
subscribe(topic_new, queue_size, fp, obj, transport_hints);
179 const std::string& topic_new,
181 const std::string& topic_old,
190 "Use %s (%s%s) topic instead of %s (%s%s)",
195 return nh_old.
subscribe(topic_old, queue_size, callback, tracked_object, transport_hints);
199 return nh_new.
subscribe(topic_new, queue_size, callback, tracked_object, transport_hints);
205 const std::string& topic_new,
207 const std::string& topic_old,
214 "Use %s (%s%s) topic instead of %s (%s%s)",
219 return nh_old.
advertise<M>(topic_old, queue_size, latch);
223 return nh_new.
advertise<M>(topic_new, queue_size, latch);
226 template <
class T,
class MReq,
class MRes>
229 const std::string& service_new,
231 const std::string& service_old,
232 bool (T::*srv_func)(MReq&, MRes&),
238 "Use %s (%s%s) service instead of %s (%s%s)",
251 template <
typename T>
254 const std::string& key,
256 const T& default_value)
261 "Use of the parameter %s is deprecated. Don't use this.",
264 nh.
param(key, param, default_value);
269 #endif // NEONAVIGATION_COMMON_COMPATIBILITY_H std::string getSimplifiedNamespace(ros::NodeHandle &nh)
const std::string & getUnresolvedNamespace() const
STATIC_ASSERT(supported_level<=current_level &¤t_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 ¶m_name, T ¶m_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()
const int supported_level
bool hasParam(const std::string &key) const
void deprecatedParam(const ros::NodeHandle &nh, const std::string &key, T ¶m, const T &default_value)