39 static const std::string
LOGNAME =
"collision_detection";
50 cache_ = std::make_shared<pluginlib::ClassLoader<CollisionPlugin>>(
"moveit_core",
51 "collision_detection::CollisionPlugin");
55 ROS_ERROR(
"Unable to construct collision plugin loader. Error: %s", e.what());
59 CollisionPluginPtr
load(
const std::string& name)
61 CollisionPluginPtr plugin;
74 bool activate(
const std::string& name,
const planning_scene::PlanningScenePtr& scene,
bool exclusive)
76 std::map<std::string, CollisionPluginPtr>::iterator it =
plugins_.find(
name);
79 CollisionPluginPtr plugin =
load(
name);
82 return plugin->initialize(scene, exclusive);
88 return it->second->initialize(scene, exclusive);
94 std::shared_ptr<pluginlib::ClassLoader<CollisionPlugin>>
cache_;
95 std::map<std::string, CollisionPluginPtr>
plugins_;
100 cache_ = std::make_shared<CollisionPluginCacheImpl>();
108 return cache_->activate(
name, scene, exclusive);