Go to the documentation of this file.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 #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
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& ) { 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