compatibility.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2018, the mcl_3dl authors
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the copyright holder nor the names of its 
00014  *       contributors may be used to endorse or promote products derived from 
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #ifndef COMPATIBILITY_H
00031 #define COMPATIBILITY_H
00032 
00033 #include <ros/ros.h>
00034 
00035 #include <string>
00036 
00037 namespace compat
00038 {
00039 #define STATIC_ASSERT(EXPR) static_assert(EXPR, #EXPR)
00040 
00041 // Update cycle
00042 // 1. Increment current_level and indicate topic changes using mcl_3dl_compat::subscribe/advertise.
00043 //    Set default_level to supported_level.
00044 // 2. Set default_level to current_level.
00045 // 3. Increment supported_level and remove old topic names.
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::Subscriber subscribe(
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     const boost::function<void(const boost::shared_ptr<M const> &)> &callback,
00157     const ros::VoidConstPtr &tracked_object = ros::VoidConstPtr(),
00158     const ros::TransportHints &transport_hints = ros::TransportHints())
00159 {
00160   if (getCompat() != current_level)
00161   {
00162     ROS_ERROR(
00163         "Use %s (%s%s) topic instead of %s (%s%s)",
00164         nh_new.resolveName(topic_new, false).c_str(),
00165         getSimplifiedNamespace(nh_new).c_str(), topic_new.c_str(),
00166         nh_old.resolveName(topic_old, false).c_str(),
00167         getSimplifiedNamespace(nh_old).c_str(), topic_old.c_str());
00168     return nh_old.subscribe(topic_old, queue_size, callback, tracked_object, transport_hints);
00169   }
00170   else
00171   {
00172     return nh_new.subscribe(topic_new, queue_size, callback, tracked_object, transport_hints);
00173   }
00174 }
00175 template <class M>
00176 ros::Publisher advertise(
00177     ros::NodeHandle &nh_new,
00178     const std::string &topic_new,
00179     ros::NodeHandle &nh_old,
00180     const std::string &topic_old,
00181     uint32_t queue_size,
00182     bool latch = false)
00183 {
00184   if (getCompat() != current_level)
00185   {
00186     ROS_ERROR(
00187         "Use %s (%s%s) topic instead of %s (%s%s)",
00188         nh_new.resolveName(topic_new, false).c_str(),
00189         getSimplifiedNamespace(nh_new).c_str(), topic_new.c_str(),
00190         nh_old.resolveName(topic_old, false).c_str(),
00191         getSimplifiedNamespace(nh_old).c_str(), topic_old.c_str());
00192     return nh_old.advertise<M>(topic_old, queue_size, latch);
00193   }
00194   else
00195   {
00196     return nh_new.advertise<M>(topic_new, queue_size, latch);
00197   }
00198 }
00199 template <class T, class MReq, class MRes>
00200 ros::ServiceServer advertiseService(
00201     ros::NodeHandle &nh_new,
00202     const std::string &service_new,
00203     ros::NodeHandle &nh_old,
00204     const std::string &service_old,
00205     bool (T::*srv_func)(MReq &, MRes &),
00206     T *obj)
00207 {
00208   if (getCompat() != current_level)
00209   {
00210     ROS_ERROR(
00211         "Use %s (%s%s) service instead of %s (%s%s)",
00212         nh_new.resolveName(service_new, false).c_str(),
00213         getSimplifiedNamespace(nh_new).c_str(), service_new.c_str(),
00214         nh_old.resolveName(service_old, false).c_str(),
00215         getSimplifiedNamespace(nh_old).c_str(), service_old.c_str());
00216     return nh_old.advertiseService(service_old, srv_func, obj);
00217   }
00218   else
00219   {
00220     return nh_new.advertiseService(service_new, srv_func, obj);
00221   }
00222 }
00223 }  // namespace compat
00224 
00225 #endif  // COMPATIBILITY_H


ypspur_ros
Author(s): Atsushi Watanabe
autogenerated on Thu Jun 6 2019 20:19:02