moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Helper class for loading kinematics solvers. More...
#include <kinematics_plugin_loader.h>
Classes | |
class | KinematicsLoaderImpl |
Public Member Functions | |
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 argument and as optional argument the name of the ROS parameter under which the robot description can be found. This is passed to the kinematics solver initialization as well as used to read the SRDF document when needed. | |
moveit::core::SolverAllocatorFn | getLoaderFunction (const srdf::ModelSharedPtr &srdf_model) |
Get a function pointer that allocates and initializes a kinematics solver. If not previously called, this function reads ROS parameters for the groups defined in the SRDF. | |
const std::vector< std::string > & | getKnownGroups () const |
Get the groups for which the function pointer returned by getLoaderFunction() can allocate a solver. | |
const std::map< std::string, double > & | getIKTimeout () const |
Get a map from group name to default IK timeout. | |
void | status () const |
Helper class for loading kinematics solvers.
Definition at line 50 of file kinematics_plugin_loader.h.
|
inline |
Load the kinematics solvers based on information on the ROS parameter server. Take node as an argument and as optional argument the name of the ROS parameter under which the robot description can be found. This is passed to the kinematics solver initialization as well as used to read the SRDF document when needed.
Definition at line 58 of file kinematics_plugin_loader.h.
|
inline |
Get a map from group name to default IK timeout.
Definition at line 77 of file kinematics_plugin_loader.h.
|
inline |
Get the groups for which the function pointer returned by getLoaderFunction() can allocate a solver.
Definition at line 71 of file kinematics_plugin_loader.h.
moveit::core::SolverAllocatorFn kinematics_plugin_loader::KinematicsPluginLoader::getLoaderFunction | ( | const srdf::ModelSharedPtr & | srdf_model | ) |
Get a function pointer that allocates and initializes a kinematics solver. If not previously called, this function reads ROS parameters for the groups defined in the SRDF.
Definition at line 241 of file kinematics_plugin_loader.cpp.
void kinematics_plugin_loader::KinematicsPluginLoader::status | ( | ) | const |
Definition at line 229 of file kinematics_plugin_loader.cpp.