Classes | Public Member Functions | Private Member Functions | Private Attributes | 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

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
 

Private Member Functions

 MOVEIT_CLASS_FORWARD (KinematicsLoaderImpl)
 

Private Attributes

unsigned int default_ik_attempts_
 
double default_search_resolution_
 
std::string default_solver_plugin_
 
double default_solver_timeout_
 
std::vector< std::string > groups_
 
std::map< std::string, unsigned int > ik_attempts_
 
std::map< std::string, double > ik_timeout_
 
KinematicsLoaderImplPtr loader_
 
std::string robot_description_
 

Detailed Description

Helper class for loading kinematics solvers.

Definition at line 50 of file kinematics_plugin_loader.h.

Constructor & Destructor Documentation

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.

Member Function Documentation

const std::map<std::string, unsigned int>& kinematics_plugin_loader::KinematicsPluginLoader::getIKAttempts ( ) const
inline

Get a map from group name to default IK attempts.

Definition at line 103 of file kinematics_plugin_loader.h.

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 97 of file kinematics_plugin_loader.h.

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 91 of file kinematics_plugin_loader.h.

robot_model::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 255 of file kinematics_plugin_loader.cpp.

robot_model::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 270 of file kinematics_plugin_loader.cpp.

kinematics_plugin_loader::KinematicsPluginLoader::MOVEIT_CLASS_FORWARD ( KinematicsLoaderImpl  )
private
void kinematics_plugin_loader::KinematicsPluginLoader::status ( ) const

Definition at line 247 of file kinematics_plugin_loader.cpp.

Member Data Documentation

unsigned int kinematics_plugin_loader::KinematicsPluginLoader::default_ik_attempts_
private

Definition at line 124 of file kinematics_plugin_loader.h.

double kinematics_plugin_loader::KinematicsPluginLoader::default_search_resolution_
private

Definition at line 112 of file kinematics_plugin_loader.h.

std::string kinematics_plugin_loader::KinematicsPluginLoader::default_solver_plugin_
private

Definition at line 122 of file kinematics_plugin_loader.h.

double kinematics_plugin_loader::KinematicsPluginLoader::default_solver_timeout_
private

Definition at line 123 of file kinematics_plugin_loader.h.

std::vector<std::string> kinematics_plugin_loader::KinematicsPluginLoader::groups_
private

Definition at line 117 of file kinematics_plugin_loader.h.

std::map<std::string, unsigned int> kinematics_plugin_loader::KinematicsPluginLoader::ik_attempts_
private

Definition at line 119 of file kinematics_plugin_loader.h.

std::map<std::string, double> kinematics_plugin_loader::KinematicsPluginLoader::ik_timeout_
private

Definition at line 118 of file kinematics_plugin_loader.h.

KinematicsLoaderImplPtr kinematics_plugin_loader::KinematicsPluginLoader::loader_
private

Definition at line 115 of file kinematics_plugin_loader.h.

std::string kinematics_plugin_loader::KinematicsPluginLoader::robot_description_
private

Definition at line 111 of file kinematics_plugin_loader.h.


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


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Wed Jul 10 2019 04:03:32