plugin.h
Go to the documentation of this file.
00001 //=================================================================================================
00002 // Copyright (c) 2016, Alexander Stumpf, TU Darmstadt
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 //     * Redistributions of source code must retain the above copyright
00008 //       notice, this list of conditions and the following disclaimer.
00009 //     * Redistributions in binary form must reproduce the above copyright
00010 //       notice, this list of conditions and the following disclaimer in the
00011 //       documentation and/or other materials provided with the distribution.
00012 //     * Neither the name of the Simulation, Systems Optimization and Robotics
00013 //       group, TU Darmstadt nor the names of its contributors may be used to
00014 //       endorse or promote products derived from this software without
00015 //       specific prior written permission.
00016 
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00018 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00019 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00020 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //=================================================================================================
00028 
00029 #ifndef VIGIR_PLUGINLIB_PLUGIN_H__
00030 #define VIGIR_PLUGINLIB_PLUGIN_H__
00031 
00032 #include <ros/ros.h>
00033 
00034 #include <vigir_generic_params/parameter_manager.h>
00035 
00036 #include <vigir_pluginlib_msgs/pluginlib_msgs.h>
00037 
00038 
00039 
00040 namespace vigir_pluginlib
00041 {
00042 std::string demangle(const char* name);
00043 
00044 class Plugin
00045 {
00046 public:
00047   // typedefs
00048   typedef boost::shared_ptr<Plugin> Ptr;
00049   typedef boost::shared_ptr<const Plugin> ConstPtr;
00050   typedef boost::weak_ptr<Plugin> WeakPtr;
00051   typedef boost::weak_ptr<const Plugin> ConstWeakPtr;
00052 
00053   Plugin(const std::string& name, const std::string& type_class_package = std::string(), const std::string& base_class_package = std::string(), const std::string& base_class = std::string());
00054   virtual ~Plugin();
00055 
00056 private:
00063   bool setup(ros::NodeHandle& nh, const vigir_generic_params::ParameterSet& global_params = vigir_generic_params::ParameterSet());
00064 
00065 public:
00071   virtual bool initialize(const vigir_generic_params::ParameterSet& global_params = vigir_generic_params::ParameterSet()) { return loadParams(global_params); }
00072 
00079   virtual bool postInitialize(const vigir_generic_params::ParameterSet& global_params = vigir_generic_params::ParameterSet()) { return true; }
00080 
00087   virtual bool loadParams(const vigir_generic_params::ParameterSet& /*global_params*/) { return true; }
00088 
00095   template <typename T>
00096   inline static std::string getTypeClass() { return T::template _typeClass<T>(); }
00097   const std::string& getTypeClass() const;
00098 
00099   const msgs::PluginDescription& getDescription() const;
00100   const std::string& getName() const;
00101   const std::string& getTypeClassPackage() const;
00102   const std::string& getBaseClassPackage() const;
00103   const std::string& getBaseClass() const;
00104 
00111   virtual bool isUnique() const { return true; }
00112 
00113   friend class PluginManager;
00114 
00115 protected:
00119   template <typename T>
00120   inline static std::string _typeClass(T* t = nullptr) { return demangle(t ? typeid(*t).name() : typeid(T).name()); }
00121 
00126   void updateDescription(const msgs::PluginDescription& description);
00127 
00132   inline const vigir_generic_params::ParameterSet& getParams() const { return params_; }
00133 
00142   template<typename T>
00143   bool getParam(const std::string& name, T& val, const T& def = T(), bool ignore_warnings = false) const
00144   {
00145     if (ignore_warnings && !params_.hasParam(name))
00146       return false;
00147 
00148     return params_.getParam(name, val, def);
00149   }
00150 
00158   template<typename T>
00159   T param(const std::string& name, const T& def = T(), bool ignore_warnings = false) const
00160   {
00161     T result;
00162     getParam(name, result, def, ignore_warnings);
00163     return result;
00164   }
00165 
00166   ros::NodeHandle nh_;
00167 
00168 private:
00169   void setNodehandle(const ros::NodeHandle& nh);
00170   void setParams(const vigir_generic_params::ParameterSet& params);
00171 
00172   vigir_generic_params::ParameterSet params_;
00173 
00174   msgs::PluginDescription description_;
00175 };
00176 }
00177 
00178 #endif


vigir_pluginlib
Author(s): Alexander Stumpf
autogenerated on Tue Sep 13 2016 03:47:30