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 MCL_3DL_COMPAT_COMPATIBILITY_H
00031 #define MCL_3DL_COMPAT_COMPATIBILITY_H
00032
00033 #include <ros/ros.h>
00034
00035 #include <string>
00036
00037 namespace mcl_3dl_compat
00038 {
00039 #define STATIC_ASSERT(EXPR) static_assert(EXPR, #EXPR)
00040
00041
00042
00043
00044
00045
00046 const int current_level = 1;
00047 const int supported_level = 0;
00048 const int default_level = supported_level;
00049
00050 STATIC_ASSERT(supported_level <= current_level && current_level <= supported_level + 1);
00051 STATIC_ASSERT(supported_level <= default_level && default_level <= current_level);
00052
00053 int getCompat()
00054 {
00055 int compat(default_level);
00056 ros::NodeHandle("~").param("compatible", compat, compat);
00057
00058 return compat;
00059 }
00060 void checkCompatMode()
00061 {
00062 if (getCompat() < supported_level)
00063 {
00064 const std::string message =
00065 "======= [Obsolated] your configuration for " + ros::this_node::getName() + " is outdated =======";
00066 ROS_FATAL("%s", message.c_str());
00067 ros::shutdown();
00068 throw std::runtime_error(message);
00069 }
00070 else if (getCompat() > current_level)
00071 {
00072 const std::string message =
00073 "======= [Unsupported] your configuration for " + ros::this_node::getName() + " is futuredated =======";
00074 ROS_FATAL("%s", message.c_str());
00075 ros::shutdown();
00076 throw std::runtime_error(message);
00077 }
00078 else if (getCompat() != current_level)
00079 {
00080 ROS_ERROR_ONCE(
00081 "======= [Deprecated] %s is run in compatible mode =======\n"
00082 "=========================================================\n"
00083 "Set _compatible:=%d to switch to new topic namespaces.\n"
00084 "Compatible mode will be obsolated in the future update.\n"
00085 "=========================================================",
00086 ros::this_node::getName().c_str(), current_level);
00087 }
00088 }
00089 std::string getSimplifiedNamespace(ros::NodeHandle& nh)
00090 {
00091 if (nh.getUnresolvedNamespace() == ros::this_node::getName())
00092 return std::string("~/");
00093 if (nh.getUnresolvedNamespace() == std::string())
00094 return std::string();
00095 return nh.getNamespace() + "/";
00096 }
00097 template <class M, class T>
00098 ros::Subscriber subscribe(
00099 ros::NodeHandle& nh_new,
00100 const std::string& topic_new,
00101 ros::NodeHandle& nh_old,
00102 const std::string& topic_old,
00103 uint32_t queue_size,
00104 void (T::*fp)(M) const,
00105 T* obj,
00106 const ros::TransportHints& transport_hints = ros::TransportHints())
00107 {
00108 if (getCompat() != current_level)
00109 {
00110 ROS_ERROR(
00111 "Use %s (%s%s) topic instead of %s (%s%s)",
00112 nh_new.resolveName(topic_new, false).c_str(),
00113 getSimplifiedNamespace(nh_new).c_str(), topic_new.c_str(),
00114 nh_old.resolveName(topic_old, false).c_str(),
00115 getSimplifiedNamespace(nh_old).c_str(), topic_old.c_str());
00116 return nh_old.subscribe(topic_old, queue_size, fp, obj, transport_hints);
00117 }
00118 else
00119 {
00120 return nh_new.subscribe(topic_new, queue_size, fp, obj, transport_hints);
00121 }
00122 }
00123 template <class M, class T>
00124 ros::Subscriber subscribe(
00125 ros::NodeHandle& nh_new,
00126 const std::string& topic_new,
00127 ros::NodeHandle& nh_old,
00128 const std::string& topic_old,
00129 uint32_t queue_size,
00130 void (T::*fp)(M),
00131 T* obj,
00132 const ros::TransportHints& transport_hints = ros::TransportHints())
00133 {
00134 if (getCompat() != current_level)
00135 {
00136 ROS_ERROR(
00137 "Use %s (%s%s) topic instead of %s (%s%s)",
00138 nh_new.resolveName(topic_new, false).c_str(),
00139 getSimplifiedNamespace(nh_new).c_str(), topic_new.c_str(),
00140 nh_old.resolveName(topic_old, false).c_str(),
00141 getSimplifiedNamespace(nh_old).c_str(), topic_old.c_str());
00142 return nh_old.subscribe(topic_old, queue_size, fp, obj, transport_hints);
00143 }
00144 else
00145 {
00146 return nh_new.subscribe(topic_new, queue_size, fp, obj, transport_hints);
00147 }
00148 }
00149 template <class M>
00150 ros::Publisher advertise(
00151 ros::NodeHandle& nh_new,
00152 const std::string& topic_new,
00153 ros::NodeHandle& nh_old,
00154 const std::string& topic_old,
00155 uint32_t queue_size,
00156 bool latch = false)
00157 {
00158 if (getCompat() != current_level)
00159 {
00160 ROS_ERROR(
00161 "Use %s (%s%s) topic instead of %s (%s%s)",
00162 nh_new.resolveName(topic_new, false).c_str(),
00163 getSimplifiedNamespace(nh_new).c_str(), topic_new.c_str(),
00164 nh_old.resolveName(topic_old, false).c_str(),
00165 getSimplifiedNamespace(nh_old).c_str(), topic_old.c_str());
00166 return nh_old.advertise<M>(topic_old, queue_size, latch);
00167 }
00168 else
00169 {
00170 return nh_new.advertise<M>(topic_new, queue_size, latch);
00171 }
00172 }
00173 template <class T, class MReq, class MRes>
00174 ros::ServiceServer advertiseService(
00175 ros::NodeHandle& nh_new,
00176 const std::string& service_new,
00177 ros::NodeHandle& nh_old,
00178 const std::string& service_old,
00179 bool (T::*srv_func)(MReq&, MRes&),
00180 T* obj)
00181 {
00182 if (getCompat() != current_level)
00183 {
00184 ROS_ERROR(
00185 "Use %s (%s%s) service instead of %s (%s%s)",
00186 nh_new.resolveName(service_new, false).c_str(),
00187 getSimplifiedNamespace(nh_new).c_str(), service_new.c_str(),
00188 nh_old.resolveName(service_old, false).c_str(),
00189 getSimplifiedNamespace(nh_old).c_str(), service_old.c_str());
00190 return nh_old.advertiseService(service_old, srv_func, obj);
00191 }
00192 else
00193 {
00194 return nh_new.advertiseService(service_new, srv_func, obj);
00195 }
00196 }
00197
00198 template <typename T>
00199 void paramRename(
00200 ros::NodeHandle& nh,
00201 const std::string& param_name_new,
00202 const std::string& param_name_old)
00203 {
00204 if (nh.hasParam(param_name_old))
00205 {
00206 ROS_ERROR(
00207 "Use %s parameter instead of %s",
00208 nh.resolveName(param_name_new, false).c_str(),
00209 nh.resolveName(param_name_old, false).c_str());
00210 if (nh.hasParam(param_name_new))
00211 {
00212 ROS_ERROR(
00213 "%s is also defined. Ignoring %s.",
00214 nh.resolveName(param_name_new, false).c_str(),
00215 nh.resolveName(param_name_old, false).c_str());
00216 return;
00217 }
00218 T value;
00219 nh.getParam(param_name_old, value);
00220 nh.setParam(param_name_new, value);
00221 }
00222 }
00223 }
00224
00225 #endif // MCL_3DL_COMPAT_COMPATIBILITY_H