36 #include <pluginlib/class_loader.hpp>
37 #include <rclcpp/logger.hpp>
38 #include <rclcpp/logging.hpp>
41 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"collision_detection");
52 cache_ = std::make_shared<pluginlib::ClassLoader<CollisionPlugin>>(
"moveit_core",
53 "collision_detection::CollisionPlugin");
55 catch (pluginlib::PluginlibException& e)
57 RCLCPP_ERROR(LOGGER,
"Unable to construct collision plugin loader. Error: %s", e.what());
61 CollisionPluginPtr
load(
const std::string&
name)
63 CollisionPluginPtr plugin;
66 plugin = cache_->createUniqueInstance(
name);
67 plugins_[
name] = plugin;
69 catch (pluginlib::PluginlibException& ex)
71 RCLCPP_ERROR_STREAM(LOGGER,
"Exception while loading " <<
name <<
": " << ex.what());
78 std::map<std::string, CollisionPluginPtr>::iterator it = plugins_.find(
name);
79 if (it == plugins_.end())
81 const CollisionPluginPtr plugin =
load(
name);
84 return plugin->initialize(
scene);
90 return it->second->initialize(
scene);
96 std::shared_ptr<pluginlib::ClassLoader<CollisionPlugin>> cache_;
97 std::map<std::string, CollisionPluginPtr> plugins_;
102 cache_ = std::make_shared<CollisionPluginCacheImpl>();
bool activate(const std::string &name, const planning_scene::PlanningScenePtr &scene)
CollisionPluginCacheImpl()
CollisionPluginPtr load(const std::string &name)
bool activate(const std::string &name, const planning_scene::PlanningScenePtr &scene)
Activate a specific collision plugin for the given planning scene instance.