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

Public Member Functions

 KinematicsLoaderImpl (const rclcpp::Node::SharedPtr &node, const std::string &robot_description, const std::map< std::string, std::vector< std::string >> &possible_kinematics_solvers, const std::map< std::string, std::vector< double >> &search_res, const std::map< std::string, std::vector< std::string >> &iksolver_to_tip_links)
 Pimpl Implementation of KinematicsLoader. More...
 
std::vector< std::string > chooseTipFrames (const moveit::core::JointModelGroup *jmg)
 Helper function to decide which, and how many, tip frames a planning group has. More...
 
kinematics::KinematicsBasePtr allocKinematicsSolver (const moveit::core::JointModelGroup *jmg)
 
kinematics::KinematicsBasePtr allocKinematicsSolverWithCache (const moveit::core::JointModelGroup *jmg)
 
void status () const
 

Detailed Description

Definition at line 64 of file kinematics_plugin_loader.cpp.

Constructor & Destructor Documentation

◆ KinematicsLoaderImpl()

kinematics_plugin_loader::KinematicsPluginLoader::KinematicsLoaderImpl::KinematicsLoaderImpl ( const rclcpp::Node::SharedPtr &  node,
const std::string &  robot_description,
const std::map< std::string, std::vector< std::string >> &  possible_kinematics_solvers,
const std::map< std::string, std::vector< double >> &  search_res,
const std::map< std::string, std::vector< std::string >> &  iksolver_to_tip_links 
)
inline

Pimpl Implementation of KinematicsLoader.

Parameters
robot_description
possible_kinematics_solvers
search_res
iksolver_to_tip_links- a map between each ik solver and a vector of custom-specified tip link(s)

Definition at line 74 of file kinematics_plugin_loader.cpp.

Member Function Documentation

◆ allocKinematicsSolver()

kinematics::KinematicsBasePtr kinematics_plugin_loader::KinematicsPluginLoader::KinematicsLoaderImpl::allocKinematicsSolver ( const moveit::core::JointModelGroup jmg)
inline

Definition at line 143 of file kinematics_plugin_loader.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ allocKinematicsSolverWithCache()

kinematics::KinematicsBasePtr kinematics_plugin_loader::KinematicsPluginLoader::KinematicsLoaderImpl::allocKinematicsSolverWithCache ( const moveit::core::JointModelGroup jmg)
inline

Definition at line 227 of file kinematics_plugin_loader.cpp.

Here is the call graph for this function:

◆ chooseTipFrames()

std::vector<std::string> kinematics_plugin_loader::KinematicsPluginLoader::KinematicsLoaderImpl::chooseTipFrames ( const moveit::core::JointModelGroup jmg)
inline

Helper function to decide which, and how many, tip frames a planning group has.

Parameters
jmg- joint model group pointer
Returns
tips - list of valid links in a planning group to plan for

Definition at line 101 of file kinematics_plugin_loader.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ status()

void kinematics_plugin_loader::KinematicsPluginLoader::KinematicsLoaderImpl::status ( ) const
inline

Definition at line 239 of file kinematics_plugin_loader.cpp.


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