52 Helper(
const rclcpp::Node::SharedPtr& node,
const constraint_samplers::ConstraintSamplerManagerPtr& csm)
53 : node_(node), logger_(
moveit::getLogger(
"moveit.ros.constraint_sampler_manager_loader"))
55 if (node_->has_parameter(
"constraint_samplers"))
61 constraint_sampler_plugin_loader_ =
62 std::make_unique<pluginlib::ClassLoader<constraint_samplers::ConstraintSamplerAllocator>>(
63 "moveit_core",
"constraint_samplers::ConstraintSamplerAllocator");
65 catch (pluginlib::PluginlibException& ex)
67 RCLCPP_ERROR(logger_,
"Exception while creating constraint sampling plugin loader %s", ex.what());
70 boost::char_separator<char> sep(
" ");
72 for (boost::tokenizer<boost::char_separator<char>>::iterator beg = tok.begin(); beg != tok.end(); ++beg)
76 constraint_samplers::ConstraintSamplerAllocatorPtr csa =
77 constraint_sampler_plugin_loader_->createUniqueInstance(*beg);
78 csm->registerSamplerAllocator(csa);
79 RCLCPP_INFO(logger_,
"Loaded constraint sampling plugin %s", std::string(*beg).c_str());
81 catch (pluginlib::PluginlibException& ex)
83 RCLCPP_ERROR(logger_,
"Exception while planning adapter plugin '%s': %s", std::string(*beg).c_str(),