42#include <kinematics_parameters.hpp>
59 const std::string& robot_description =
"robot_description")
61 , robot_description_(robot_description)
62 , logger_(
moveit::getLogger(
"moveit.ros.kinematics_plugin_loader"))
85 const rclcpp::Node::SharedPtr node_;
86 std::unordered_map<std::string, std::shared_ptr<kinematics::ParamListener>> group_param_listener_;
87 std::unordered_map<std::string, kinematics::Params> group_params_;
88 std::string robot_description_;
91 KinematicsLoaderImplPtr loader_;
93 std::vector<std::string> groups_;
94 std::map<std::string, double> ik_timeout_;
95 rclcpp::Logger logger_;
#define MOVEIT_CLASS_FORWARD(C)
Helper class for loading kinematics solvers.
const std::vector< std::string > & getKnownGroups() const
Get the groups for which the function pointer returned by getLoaderFunction() can allocate a solver.
moveit::core::SolverAllocatorFn getLoaderFunction(const srdf::ModelSharedPtr &srdf_model)
Get a function pointer that allocates and initializes a kinematics solver. If not previously called,...
KinematicsPluginLoader(const rclcpp::Node::SharedPtr &node, const std::string &robot_description="robot_description")
Load the kinematics solvers based on information on the ROS parameter server. Take node as an argumen...
const std::map< std::string, double > & getIKTimeout() const
Get a map from group name to default IK timeout.
std::function< kinematics::KinematicsBasePtr(const JointModelGroup *)> SolverAllocatorFn
Function type that allocates a kinematics solver for a particular group.
Main namespace for MoveIt.