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
00031
00032
00033
00034
00035 #include <moveit/collision_plugin_loader/collision_plugin_loader.h>
00036 #include <pluginlib/class_loader.h>
00037
00038 namespace collision_detection
00039 {
00040 class CollisionPluginLoader::CollisionPluginLoaderImpl
00041 {
00042 public:
00043 CollisionPluginLoaderImpl()
00044 {
00045 try
00046 {
00047 loader_.reset(new pluginlib::ClassLoader<CollisionPlugin>("moveit_core", "collision_detection::CollisionPlugin"));
00048 }
00049 catch (pluginlib::PluginlibException& e)
00050 {
00051 ROS_ERROR("Unable to construct colllision plugin loader. Error: %s", e.what());
00052 }
00053 }
00054
00055 CollisionPluginPtr load(const std::string& name)
00056 {
00057 CollisionPluginPtr plugin;
00058 try
00059 {
00060 plugin.reset(loader_->createUnmanagedInstance(name));
00061 plugins_[name] = plugin;
00062 }
00063 catch (pluginlib::PluginlibException& ex)
00064 {
00065 ROS_ERROR_STREAM("Exception while loading " << name << ": " << ex.what());
00066 }
00067 return plugin;
00068 }
00069
00070 bool activate(const std::string& name, const planning_scene::PlanningScenePtr& scene, bool exclusive)
00071 {
00072 std::map<std::string, CollisionPluginPtr>::iterator it = plugins_.find(name);
00073 if (it == plugins_.end())
00074 {
00075 CollisionPluginPtr plugin = load(name);
00076 if (plugin)
00077 {
00078 return plugin->initialize(scene, exclusive);
00079 }
00080 return false;
00081 }
00082 if (it->second)
00083 {
00084 return it->second->initialize(scene, exclusive);
00085 }
00086 return false;
00087 }
00088
00089 private:
00090 boost::shared_ptr<pluginlib::ClassLoader<CollisionPlugin> > loader_;
00091 std::map<std::string, CollisionPluginPtr> plugins_;
00092 };
00093
00094 CollisionPluginLoader::CollisionPluginLoader()
00095 {
00096 loader_.reset(new CollisionPluginLoaderImpl());
00097 }
00098
00099 CollisionPluginLoader::~CollisionPluginLoader()
00100 {
00101 }
00102
00103 bool CollisionPluginLoader::activate(const std::string& name, const planning_scene::PlanningScenePtr& scene,
00104 bool exclusive)
00105 {
00106 return loader_->activate(name, scene, exclusive);
00107 }
00108
00109 void CollisionPluginLoader::setupScene(ros::NodeHandle& nh, const planning_scene::PlanningScenePtr& scene)
00110 {
00111 if (!scene)
00112 return;
00113
00114 std::string param_name;
00115 std::string collision_detector_name;
00116
00117 if (nh.searchParam("collision_detector", param_name))
00118 {
00119 nh.getParam(param_name, collision_detector_name);
00120 }
00121 else if (nh.hasParam("/move_group/collision_detector"))
00122 {
00123
00124
00125 nh.getParam("/move_group/collision_detector", collision_detector_name);
00126 }
00127 else
00128 {
00129 return;
00130 }
00131
00132 if (collision_detector_name == "")
00133 {
00134
00135 return;
00136 }
00137
00138 activate(collision_detector_name, scene, true);
00139 ROS_INFO_STREAM("Using collision detector:" << scene->getActiveCollisionDetectorName().c_str());
00140 }
00141
00142 }