30 #ifndef COMPATIBILITY_H 31 #define COMPATIBILITY_H 39 #define STATIC_ASSERT(EXPR) static_assert(EXPR, #EXPR) 50 STATIC_ASSERT(supported_level <= current_level && current_level <= supported_level + 1);
51 STATIC_ASSERT(supported_level <= default_level && default_level <= current_level);
64 const std::string message =
68 throw std::runtime_error(message);
72 const std::string message =
76 throw std::runtime_error(message);
81 "======= [Deprecated] %s is run in compatible mode =======\n" 82 "=========================================================\n" 83 "Set _compatible:=%d to switch to new topic namespaces.\n" 84 "Compatible mode will be obsolated in the future update.\n" 85 "=========================================================",
92 return std::string(
"~/");
97 template <
class M,
class T>
100 const std::string &topic_new,
102 const std::string &topic_old,
104 void (T::*fp)(M)
const,
111 "Use %s (%s%s) topic instead of %s (%s%s)",
116 return nh_old.
subscribe(topic_old, queue_size, fp, obj, transport_hints);
120 return nh_new.
subscribe(topic_new, queue_size, fp, obj, transport_hints);
123 template <
class M,
class T>
126 const std::string &topic_new,
128 const std::string &topic_old,
137 "Use %s (%s%s) topic instead of %s (%s%s)",
142 return nh_old.
subscribe(topic_old, queue_size, fp, obj, transport_hints);
146 return nh_new.
subscribe(topic_new, queue_size, fp, obj, transport_hints);
152 const std::string &topic_new,
154 const std::string &topic_old,
163 "Use %s (%s%s) topic instead of %s (%s%s)",
168 return nh_old.
subscribe(topic_old, queue_size, callback, tracked_object, transport_hints);
172 return nh_new.
subscribe(topic_new, queue_size, callback, tracked_object, transport_hints);
178 const std::string &topic_new,
180 const std::string &topic_old,
187 "Use %s (%s%s) topic instead of %s (%s%s)",
192 return nh_old.
advertise<M>(topic_old, queue_size, latch);
196 return nh_new.
advertise<M>(topic_new, queue_size, latch);
199 template <
class T,
class MReq,
class MRes>
202 const std::string &service_new,
204 const std::string &service_old,
205 bool (T::*srv_func)(MReq &, MRes &),
211 "Use %s (%s%s) service instead of %s (%s%s)",
225 #endif // COMPATIBILITY_H const std::string & getUnresolvedNamespace() const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
STATIC_ASSERT(supported_level<=current_level &¤t_level<=supported_level+1)
std::string resolveName(const std::string &name, bool remap=true) const
const int supported_level
ROSCPP_DECL const std::string & getName()
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)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
#define ROS_ERROR_ONCE(...)
const std::string & getNamespace() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::string getSimplifiedNamespace(ros::NodeHandle &nh)
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 void shutdown()
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(T::*fp)(M) const, T *obj, const ros::TransportHints &transport_hints=ros::TransportHints())