moveit2
The MoveIt Motion Planning Framework for ROS 2.
Classes | Public Member Functions | List of all members
kinematics_plugin_loader::KinematicsPluginLoader Class Reference

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", double default_search_resolution=0.0)
 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. More...
 
 KinematicsPluginLoader (const rclcpp::Node::SharedPtr &node, const std::string &solver_plugin, double solve_timeout, const std::string &robot_description="robot_description", double default_search_resolution=0.0)
 Use a default kinematics solver (solver_plugin) for all the groups in the robot model. The default timeout for the solver is solve_timeout and the default number of IK attempts is ik_attempts. 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. More...
 
moveit::core::SolverAllocatorFn getLoaderFunction ()
 Get a function pointer that allocates and initializes a kinematics solver. If not previously called, this function reads the SRDF and calls the variant below. More...
 
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. More...
 
const std::vector< std::string > & getKnownGroups () const
 Get the groups for which the function pointer returned by getLoaderFunction() can allocate a solver. More...
 
const std::map< std::string, double > & getIKTimeout () const
 Get a map from group name to default IK timeout. More...
 
void status () const
 

Detailed Description

Helper class for loading kinematics solvers.

Definition at line 48 of file kinematics_plugin_loader.h.

Constructor & Destructor Documentation

◆ KinematicsPluginLoader() [1/2]

kinematics_plugin_loader::KinematicsPluginLoader::KinematicsPluginLoader ( const rclcpp::Node::SharedPtr &  node,
const std::string &  robot_description = "robot_description",
double  default_search_resolution = 0.0 
)
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 56 of file kinematics_plugin_loader.h.

◆ KinematicsPluginLoader() [2/2]

kinematics_plugin_loader::KinematicsPluginLoader::KinematicsPluginLoader ( const rclcpp::Node::SharedPtr &  node,
const std::string &  solver_plugin,
double  solve_timeout,
const std::string &  robot_description = "robot_description",
double  default_search_resolution = 0.0 
)
inline

Use a default kinematics solver (solver_plugin) for all the groups in the robot model. The default timeout for the solver is solve_timeout and the default number of IK attempts is ik_attempts. 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 70 of file kinematics_plugin_loader.h.

Member Function Documentation

◆ getIKTimeout()

const std::map<std::string, double>& kinematics_plugin_loader::KinematicsPluginLoader::getIKTimeout ( ) const
inline

Get a map from group name to default IK timeout.

Definition at line 96 of file kinematics_plugin_loader.h.

◆ getKnownGroups()

const std::vector<std::string>& kinematics_plugin_loader::KinematicsPluginLoader::getKnownGroups ( ) const
inline

Get the groups for which the function pointer returned by getLoaderFunction() can allocate a solver.

Definition at line 90 of file kinematics_plugin_loader.h.

◆ getLoaderFunction() [1/2]

moveit::core::SolverAllocatorFn kinematics_plugin_loader::KinematicsPluginLoader::getLoaderFunction ( )

Get a function pointer that allocates and initializes a kinematics solver. If not previously called, this function reads the SRDF and calls the variant below.

Definition at line 273 of file kinematics_plugin_loader.cpp.

Here is the call graph for this function:

◆ getLoaderFunction() [2/2]

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 285 of file kinematics_plugin_loader.cpp.

◆ status()

void kinematics_plugin_loader::KinematicsPluginLoader::status ( ) const

Definition at line 265 of file kinematics_plugin_loader.cpp.


The documentation for this class was generated from the following files: