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
00030 #include <ros/types.h>
00031
00032 #include "rve_pluginloader/loader.h"
00033 #include "rve_pluginloader/plugin.h"
00034
00035 #include <ros/assert.h>
00036 #include <ros/package.h>
00037
00038 namespace rve_pluginloader
00039 {
00040
00041 static L_Plugin g_plugins;
00042 static int32_t g_init_count = 0;
00043
00044 void init()
00045 {
00046 ++g_init_count;
00047 }
00048
00049 void shutdown()
00050 {
00051 if (--g_init_count == 0)
00052 {
00053 g_plugins.clear();
00054 }
00055 }
00056
00057 const L_Plugin& getPlugins()
00058 {
00059 return g_plugins;
00060 }
00061
00062 void loadDescriptions(const std::string& registry_package)
00063 {
00064 ros::package::V_string plugins;
00065 ros::package::getPlugins(registry_package, "plugin", plugins);
00066
00067 ros::package::V_string::iterator it = plugins.begin();
00068 ros::package::V_string::iterator end = plugins.end();
00069 for (; it != end; ++it)
00070 {
00071 const std::string& plugin = *it;
00072 loadDescription(plugin);
00073 }
00074 }
00075
00076 void loadAllPlugins(const std::string& registry_package)
00077 {
00078 loadDescriptions(registry_package);
00079 L_Plugin::iterator it = g_plugins.begin();
00080 L_Plugin::iterator end = g_plugins.end();
00081 for (; it != end; ++it)
00082 {
00083 const PluginPtr& plugin = *it;
00084 try
00085 {
00086 plugin->load();
00087 }
00088 catch (std::runtime_error& e)
00089 {
00090 ROS_ERROR("Error loading plugin [%s]: %s", plugin->getDescriptionPath().c_str(), e.what());
00091 }
00092 }
00093 }
00094
00095 PluginPtr getPlugin(const std::string& description_file)
00096 {
00097 L_Plugin::iterator it = g_plugins.begin();
00098 L_Plugin::iterator end = g_plugins.end();
00099 for (; it != end; ++it)
00100 {
00101 const PluginPtr& plugin = *it;
00102
00103 if (plugin->getDescriptionPath() == description_file)
00104 {
00105 return plugin;
00106 }
00107 }
00108
00109 return PluginPtr();
00110 }
00111
00112 PluginPtr getPluginByPackage(const std::string& package)
00113 {
00114 L_Plugin::iterator it = g_plugins.begin();
00115 L_Plugin::iterator end = g_plugins.end();
00116 for (; it != end; ++it)
00117 {
00118 const PluginPtr& plugin = *it;
00119
00120 if (plugin->getPackageName() == package)
00121 {
00122 return plugin;
00123 }
00124 }
00125
00126 return PluginPtr();
00127 }
00128
00129 PluginPtr loadDescription(const std::string& description_path)
00130 {
00131 PluginPtr plugin = getPlugin(description_path);
00132 if (plugin)
00133 {
00134 return plugin;
00135 }
00136
00137 plugin.reset(new Plugin);
00138
00139 try
00140 {
00141 plugin->loadDescription(description_path);
00142 }
00143 catch (std::runtime_error& e)
00144 {
00145 ROS_ERROR("Error loading plugin description [%s]: %s", description_path.c_str(), e.what());
00146 }
00147
00148 g_plugins.push_back(plugin);
00149
00150 return plugin;
00151 }
00152
00153 PluginPtr loadPlugin(const std::string& description_file)
00154 {
00155 PluginPtr plugin = loadDescription(description_file);
00156 plugin->load();
00157 return plugin;
00158 }
00159
00160 PluginPtr getPluginForClass(const std::string& base_class, const std::string& derived_class)
00161 {
00162 L_Plugin::iterator it = g_plugins.begin();
00163 L_Plugin::iterator end = g_plugins.end();
00164 for (; it != end; ++it)
00165 {
00166 const PluginPtr& plugin = *it;
00167 if (plugin->hasClass(base_class, derived_class))
00168 {
00169 return plugin;
00170 }
00171 }
00172
00173 return PluginPtr();
00174 }
00175
00176 void* create(const std::string& base_class, const std::string& derived_class)
00177 {
00178 PluginPtr plugin = getPluginForClass(base_class, derived_class);
00179 if (!plugin)
00180 {
00181 return 0;
00182 }
00183
00184 return plugin->create(base_class, derived_class);
00185 }
00186
00187 boost::shared_ptr<void> createShared(const std::string& base_class, const std::string& derived_class)
00188 {
00189 PluginPtr plugin = getPluginForClass(base_class, derived_class);
00190 if (!plugin)
00191 {
00192 return boost::shared_ptr<void>();
00193 }
00194
00195 return plugin->createShared(base_class, derived_class);
00196 }
00197
00198 void destroy(void* mem)
00199 {
00200 L_Plugin::iterator it = g_plugins.begin();
00201 L_Plugin::iterator end = g_plugins.end();
00202 for (; it != end; ++it)
00203 {
00204 const PluginPtr& plugin = *it;
00205 if (plugin->ownsAllocation(mem))
00206 {
00207 plugin->destroy(mem);
00208 return;
00209 }
00210 }
00211
00212 ROS_BREAK();
00213 }
00214
00215 }