Helper class for loading kinematics solvers.
More...
#include <kinematics_plugin_loader.h>
|
const std::map< std::string, unsigned int > & | getIKAttempts () const |
| Get a map from group name to default IK attempts. More...
|
|
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...
|
|
robot_model::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...
|
|
robot_model::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 ik_attempts, 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 50 of file kinematics_plugin_loader.h.
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 58 of file kinematics_plugin_loader.h.
kinematics_plugin_loader::KinematicsPluginLoader::KinematicsPluginLoader |
( |
const std::string & |
solver_plugin, |
|
|
double |
solve_timeout, |
|
|
unsigned int |
ik_attempts, |
|
|
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 71 of file kinematics_plugin_loader.h.
const std::map<std::string, unsigned int>& kinematics_plugin_loader::KinematicsPluginLoader::getIKAttempts |
( |
| ) |
const |
|
inline |
const std::map<std::string, double>& kinematics_plugin_loader::KinematicsPluginLoader::getIKTimeout |
( |
| ) |
const |
|
inline |
const std::vector<std::string>& kinematics_plugin_loader::KinematicsPluginLoader::getKnownGroups |
( |
| ) |
const |
|
inline |
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 255 of file kinematics_plugin_loader.cpp.
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 270 of file kinematics_plugin_loader.cpp.
void kinematics_plugin_loader::KinematicsPluginLoader::status |
( |
| ) |
const |
unsigned int kinematics_plugin_loader::KinematicsPluginLoader::default_ik_attempts_ |
|
private |
double kinematics_plugin_loader::KinematicsPluginLoader::default_search_resolution_ |
|
private |
std::string kinematics_plugin_loader::KinematicsPluginLoader::default_solver_plugin_ |
|
private |
double kinematics_plugin_loader::KinematicsPluginLoader::default_solver_timeout_ |
|
private |
std::vector<std::string> kinematics_plugin_loader::KinematicsPluginLoader::groups_ |
|
private |
std::map<std::string, unsigned int> kinematics_plugin_loader::KinematicsPluginLoader::ik_attempts_ |
|
private |
std::map<std::string, double> kinematics_plugin_loader::KinematicsPluginLoader::ik_timeout_ |
|
private |
KinematicsLoaderImplPtr kinematics_plugin_loader::KinematicsPluginLoader::loader_ |
|
private |
std::string kinematics_plugin_loader::KinematicsPluginLoader::robot_description_ |
|
private |
The documentation for this class was generated from the following files: