30 #ifndef NEONAVIGATION_COMMON_COMPATIBILITY_H 31 #define NEONAVIGATION_COMMON_COMPATIBILITY_H 41 #define STATIC_ASSERT(EXPR) static_assert(EXPR, #EXPR) 48 #ifndef UNDEF_COMPATIBILITY_LEVEL 53 STATIC_ASSERT(supported_level <= current_level && current_level <= supported_level + 1);
54 STATIC_ASSERT(supported_level <= default_level && default_level <= current_level);
59 int compat(default_level);
68 const std::string message =
72 throw std::runtime_error(message);
76 const std::string message =
80 throw std::runtime_error(message);
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 "=========================================================",
96 return std::string(
"~/");
104 const std::string& topic_new,
106 const std::string& topic_old,
114 "Use %s (%s%s) topic instead of %s (%s%s)",
119 return nh_old.
subscribe(topic_old, queue_size, fp, transport_hints);
123 return nh_new.
subscribe(topic_new, queue_size, fp, transport_hints);
126 template <
class M,
class T>
129 const std::string& topic_new,
131 const std::string& topic_old,
133 void (T::*fp)(M)
const,
140 "Use %s (%s%s) topic instead of %s (%s%s)",
145 return nh_old.
subscribe(topic_old, queue_size, fp, obj, transport_hints);
149 return nh_new.
subscribe(topic_new, queue_size, fp, obj, transport_hints);
152 template <
class M,
class T>
155 const std::string& topic_new,
157 const std::string& topic_old,
166 "Use %s (%s%s) topic instead of %s (%s%s)",
171 return nh_old.
subscribe(topic_old, queue_size, fp, obj, transport_hints);
175 return nh_new.
subscribe(topic_new, queue_size, fp, obj, transport_hints);
181 const std::string& topic_new,
183 const std::string& topic_old,
192 "Use %s (%s%s) topic instead of %s (%s%s)",
197 return nh_old.
subscribe(topic_old, queue_size, callback, tracked_object, transport_hints);
201 return nh_new.
subscribe(topic_new, queue_size, callback, tracked_object, transport_hints);
207 const std::string& topic_new,
209 const std::string& topic_old,
216 "Use %s (%s%s) topic instead of %s (%s%s)",
221 return nh_old.
advertise<M>(topic_old, queue_size, latch);
225 return nh_new.
advertise<M>(topic_new, queue_size, latch);
228 template <
class T,
class MReq,
class MRes>
231 const std::string& service_new,
233 const std::string& service_old,
234 bool (T::*srv_func)(MReq&, MRes&),
240 "Use %s (%s%s) service instead of %s (%s%s)",
253 template <
typename T>
256 const std::string& key,
258 const T& default_value)
263 "Use of the parameter %s is deprecated. Don't use this.",
266 nh.
param(key, param, default_value);
271 #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()
bool hasParam(const std::string &key) const
const int supported_level
void deprecatedParam(const ros::NodeHandle &nh, const std::string &key, T ¶m, const T &default_value)