Helper class for loading kinematics solvers.
More...
#include <kinematics_plugin_loader.h>
|
const std::map< std::string, double > & | getIKTimeout () const |
| Get a map from group name to default IK timeout. More...
|
|
const std::vector< std::string > & | getKnownGroups () const |
| Get the groups for which the function pointer returned by getLoaderFunction() can allocate a solver. 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...
|
|
| KinematicsPluginLoader (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 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 std::string &solver_plugin, double solve_timeout, unsigned int, 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 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...
|
|
void | status () const |
|
Helper class for loading kinematics solvers.
Definition at line 81 of file kinematics_plugin_loader.h.
◆ KinematicsPluginLoader() [1/2]
kinematics_plugin_loader::KinematicsPluginLoader::KinematicsPluginLoader |
( |
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 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 89 of file kinematics_plugin_loader.h.
◆ KinematicsPluginLoader() [2/2]
kinematics_plugin_loader::KinematicsPluginLoader::KinematicsPluginLoader |
( |
const std::string & |
solver_plugin, |
|
|
double |
solve_timeout, |
|
|
unsigned int |
, |
|
|
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 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 102 of file kinematics_plugin_loader.h.
◆ getIKTimeout()
const std::map<std::string, double>& kinematics_plugin_loader::KinematicsPluginLoader::getIKTimeout |
( |
| ) |
const |
|
inline |
◆ getKnownGroups()
const std::vector<std::string>& kinematics_plugin_loader::KinematicsPluginLoader::getKnownGroups |
( |
| ) |
const |
|
inline |
◆ getLoaderFunction() [1/2]
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 287 of file kinematics_plugin_loader.cpp.
◆ getLoaderFunction() [2/2]
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 302 of file kinematics_plugin_loader.cpp.
◆ MOVEIT_CLASS_FORWARD()
◆ status()
void kinematics_plugin_loader::KinematicsPluginLoader::status |
( |
| ) |
const |
◆ default_search_resolution_
double kinematics_plugin_loader::KinematicsPluginLoader::default_search_resolution_ |
|
private |
◆ default_solver_plugin_
std::string kinematics_plugin_loader::KinematicsPluginLoader::default_solver_plugin_ |
|
private |
◆ default_solver_timeout_
double kinematics_plugin_loader::KinematicsPluginLoader::default_solver_timeout_ |
|
private |
◆ groups_
std::vector<std::string> kinematics_plugin_loader::KinematicsPluginLoader::groups_ |
|
private |
◆ ik_timeout_
std::map<std::string, double> kinematics_plugin_loader::KinematicsPluginLoader::ik_timeout_ |
|
private |
◆ loader_
KinematicsLoaderImplPtr kinematics_plugin_loader::KinematicsPluginLoader::loader_ |
|
private |
◆ robot_description_
std::string kinematics_plugin_loader::KinematicsPluginLoader::robot_description_ |
|
private |
The documentation for this class was generated from the following files: