00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #ifndef NEONAVIGATION_COMMON_COMPATIBILITY_H
00031 #define NEONAVIGATION_COMMON_COMPATIBILITY_H
00032
00033 #include <ros/ros.h>
00034
00035 #include <string>
00036
00037 namespace neonavigation_common
00038 {
00039 namespace compat
00040 {
00041 #define STATIC_ASSERT(EXPR) static_assert(EXPR, #EXPR)
00042
00043
00044
00045
00046
00047
00048 const int current_level = 1;
00049 const int supported_level = 0;
00050 const int default_level = supported_level;
00051
00052 STATIC_ASSERT(supported_level <= current_level && current_level <= supported_level + 1);
00053 STATIC_ASSERT(supported_level <= default_level && default_level <= current_level);
00054
00055 int getCompat()
00056 {
00057 int compat(default_level);
00058 ros::NodeHandle("/").param("neonavigation_compatible", compat, compat);
00059
00060 return compat;
00061 }
00062 void checkCompatMode()
00063 {
00064 if (getCompat() < supported_level)
00065 {
00066 const std::string message =
00067 "======= [Obsolated] your configuration for " + ros::this_node::getName() + " is outdated =======";
00068 ROS_FATAL("%s", message.c_str());
00069 ros::shutdown();
00070 throw std::runtime_error(message);
00071 }
00072 else if (getCompat() > current_level)
00073 {
00074 const std::string message =
00075 "======= [Unsupported] your configuration for " + ros::this_node::getName() + " is futuredated =======";
00076 ROS_FATAL("%s", message.c_str());
00077 ros::shutdown();
00078 throw std::runtime_error(message);
00079 }
00080 else if (getCompat() != current_level)
00081 {
00082 ROS_ERROR_ONCE(
00083 "======= [Deprecated] %s is run in compatible mode =======\n"
00084 "=========================================================\n"
00085 "Set _compatible:=%d to switch to new topic namespaces.\n"
00086 "Compatible mode will be obsolated in the future update.\n"
00087 "=========================================================",
00088 ros::this_node::getName().c_str(), current_level);
00089 }
00090 }
00091 std::string getSimplifiedNamespace(ros::NodeHandle& nh)
00092 {
00093 if (nh.getUnresolvedNamespace() == ros::this_node::getName())
00094 return std::string("~/");
00095 if (nh.getUnresolvedNamespace() == std::string())
00096 return std::string();
00097 return nh.getNamespace() + "/";
00098 }
00099 template <class M>
00100 ros::Subscriber subscribe(
00101 ros::NodeHandle& nh_new,
00102 const std::string& topic_new,
00103 ros::NodeHandle& nh_old,
00104 const std::string& topic_old,
00105 uint32_t queue_size,
00106 void (*fp)(M),
00107 const ros::TransportHints& transport_hints = ros::TransportHints())
00108 {
00109 if (getCompat() != current_level)
00110 {
00111 ROS_ERROR(
00112 "Use %s (%s%s) topic instead of %s (%s%s)",
00113 nh_new.resolveName(topic_new, false).c_str(),
00114 getSimplifiedNamespace(nh_new).c_str(), topic_new.c_str(),
00115 nh_old.resolveName(topic_old, false).c_str(),
00116 getSimplifiedNamespace(nh_old).c_str(), topic_old.c_str());
00117 return nh_old.subscribe(topic_old, queue_size, fp, transport_hints);
00118 }
00119 else
00120 {
00121 return nh_new.subscribe(topic_new, queue_size, fp, transport_hints);
00122 }
00123 }
00124 template <class M, class T>
00125 ros::Subscriber subscribe(
00126 ros::NodeHandle& nh_new,
00127 const std::string& topic_new,
00128 ros::NodeHandle& nh_old,
00129 const std::string& topic_old,
00130 uint32_t queue_size,
00131 void (T::*fp)(M) const,
00132 T* obj,
00133 const ros::TransportHints& transport_hints = ros::TransportHints())
00134 {
00135 if (getCompat() != current_level)
00136 {
00137 ROS_ERROR(
00138 "Use %s (%s%s) topic instead of %s (%s%s)",
00139 nh_new.resolveName(topic_new, false).c_str(),
00140 getSimplifiedNamespace(nh_new).c_str(), topic_new.c_str(),
00141 nh_old.resolveName(topic_old, false).c_str(),
00142 getSimplifiedNamespace(nh_old).c_str(), topic_old.c_str());
00143 return nh_old.subscribe(topic_old, queue_size, fp, obj, transport_hints);
00144 }
00145 else
00146 {
00147 return nh_new.subscribe(topic_new, queue_size, fp, obj, transport_hints);
00148 }
00149 }
00150 template <class M, class T>
00151 ros::Subscriber subscribe(
00152 ros::NodeHandle& nh_new,
00153 const std::string& topic_new,
00154 ros::NodeHandle& nh_old,
00155 const std::string& topic_old,
00156 uint32_t queue_size,
00157 void (T::*fp)(M),
00158 T* obj,
00159 const ros::TransportHints& transport_hints = ros::TransportHints())
00160 {
00161 if (getCompat() != current_level)
00162 {
00163 ROS_ERROR(
00164 "Use %s (%s%s) topic instead of %s (%s%s)",
00165 nh_new.resolveName(topic_new, false).c_str(),
00166 getSimplifiedNamespace(nh_new).c_str(), topic_new.c_str(),
00167 nh_old.resolveName(topic_old, false).c_str(),
00168 getSimplifiedNamespace(nh_old).c_str(), topic_old.c_str());
00169 return nh_old.subscribe(topic_old, queue_size, fp, obj, transport_hints);
00170 }
00171 else
00172 {
00173 return nh_new.subscribe(topic_new, queue_size, fp, obj, transport_hints);
00174 }
00175 }
00176 template <class M>
00177 ros::Subscriber subscribe(
00178 ros::NodeHandle& nh_new,
00179 const std::string& topic_new,
00180 ros::NodeHandle& nh_old,
00181 const std::string& topic_old,
00182 uint32_t queue_size,
00183 const boost::function<void(const boost::shared_ptr<M const>&)>& callback,
00184 const ros::VoidConstPtr& tracked_object = ros::VoidConstPtr(),
00185 const ros::TransportHints& transport_hints = ros::TransportHints())
00186 {
00187 if (getCompat() != current_level)
00188 {
00189 ROS_ERROR(
00190 "Use %s (%s%s) topic instead of %s (%s%s)",
00191 nh_new.resolveName(topic_new, false).c_str(),
00192 getSimplifiedNamespace(nh_new).c_str(), topic_new.c_str(),
00193 nh_old.resolveName(topic_old, false).c_str(),
00194 getSimplifiedNamespace(nh_old).c_str(), topic_old.c_str());
00195 return nh_old.subscribe(topic_old, queue_size, callback, tracked_object, transport_hints);
00196 }
00197 else
00198 {
00199 return nh_new.subscribe(topic_new, queue_size, callback, tracked_object, transport_hints);
00200 }
00201 }
00202 template <class M>
00203 ros::Publisher advertise(
00204 ros::NodeHandle& nh_new,
00205 const std::string& topic_new,
00206 ros::NodeHandle& nh_old,
00207 const std::string& topic_old,
00208 uint32_t queue_size,
00209 bool latch = false)
00210 {
00211 if (getCompat() != current_level)
00212 {
00213 ROS_ERROR(
00214 "Use %s (%s%s) topic instead of %s (%s%s)",
00215 nh_new.resolveName(topic_new, false).c_str(),
00216 getSimplifiedNamespace(nh_new).c_str(), topic_new.c_str(),
00217 nh_old.resolveName(topic_old, false).c_str(),
00218 getSimplifiedNamespace(nh_old).c_str(), topic_old.c_str());
00219 return nh_old.advertise<M>(topic_old, queue_size, latch);
00220 }
00221 else
00222 {
00223 return nh_new.advertise<M>(topic_new, queue_size, latch);
00224 }
00225 }
00226 template <class T, class MReq, class MRes>
00227 ros::ServiceServer advertiseService(
00228 ros::NodeHandle& nh_new,
00229 const std::string& service_new,
00230 ros::NodeHandle& nh_old,
00231 const std::string& service_old,
00232 bool (T::*srv_func)(MReq&, MRes&),
00233 T* obj)
00234 {
00235 if (getCompat() != current_level)
00236 {
00237 ROS_ERROR(
00238 "Use %s (%s%s) service instead of %s (%s%s)",
00239 nh_new.resolveName(service_new, false).c_str(),
00240 getSimplifiedNamespace(nh_new).c_str(), service_new.c_str(),
00241 nh_old.resolveName(service_old, false).c_str(),
00242 getSimplifiedNamespace(nh_old).c_str(), service_old.c_str());
00243 return nh_old.advertiseService(service_old, srv_func, obj);
00244 }
00245 else
00246 {
00247 return nh_new.advertiseService(service_new, srv_func, obj);
00248 }
00249 }
00250
00251 template <typename T>
00252 void deprecatedParam(
00253 const ros::NodeHandle& nh,
00254 const std::string& key,
00255 T& param,
00256 const T& default_value)
00257 {
00258 if (nh.hasParam(key))
00259 {
00260 ROS_ERROR(
00261 "Use of the parameter %s is deprecated. Don't use this.",
00262 nh.resolveName(key, false).c_str());
00263 }
00264 nh.param(key, param, default_value);
00265 }
00266 }
00267 }
00268
00269 #endif // NEONAVIGATION_COMMON_COMPATIBILITY_H