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

#include <kinematics_cache_ros.h>

Inheritance diagram for kinematics_cache_ros::KinematicsCacheROS:
Inheritance graph
[legend]
Collaboration diagram for kinematics_cache_ros::KinematicsCacheROS:
Collaboration graph
[legend]

Public Member Functions

 KinematicsCacheROS ()
 
bool init (const kinematics_cache::KinematicsCache::Options &opt, const std::string &kinematics_solver_name, const std::string &group_name, const std::string &base_frame, const std::string &tip_frame, double search_discretization)
 Initialization function. More...
 
- Public Member Functions inherited from kinematics_cache::KinematicsCache
 KinematicsCache ()
 
bool generateCacheMap (double timeout)
 Generate the cache map spending timeout (seconds) on the generation process) More...
 
bool getSolution (const geometry_msgs::Pose &pose, unsigned int solution_index, std::vector< double > &solution) const
 Get a candidate solution for a particular pose. Note that the pose will be projected onto the grid used in the caching process. More...
 
bool getSolutions (const geometry_msgs::Pose &pose, std::vector< std::vector< double > > &solutions) const
 Get all candidate solutions for a particular pose. Note that the pose will be projected onto the grid used in the caching process. The size of the solutions vector MUST be pre-allocated to num_solutions (see getNumSolutions) More...
 
bool getNumSolutions (const geometry_msgs::Pose &pose, unsigned int &num_solutions) const
 Get number of candidate solutions for a particular pose. More...
 
bool initialize (kinematics::KinematicsBaseConstPtr &solver, const planning_models::RobotModelConstPtr &kinematic_model, const KinematicsCache::Options &opt)
 Initialize the cache class. More...
 
const kinematics::KinematicsBaseConstPtr & getSolverInstance () const
 Return the instance of the kinematics solver. More...
 
const planning_models::RobotModelConstPtr & getModelInstance () const
 Return the instance of the kinematics model. More...
 
const OptionsgetCacheParameters () const
 Return the cache parameters used for cache construction. More...
 
const std::string getGroupName ()
 
bool addToCache (const geometry_msgs::Pose &pose, const std::vector< double > &joint_values, bool overwrite=false)
 Add a new solution to the cache at the given location. More...
 
bool writeToFile (const std::string &filename)
 
bool readFromFile (const std::string &filename)
 
std::pair< double, double > getMinMaxSquaredDistance ()
 
 KinematicsCache ()
 
bool generateCacheMap (double timeout)
 Generate the cache map spending timeout (seconds) on the generation process) More...
 
bool getSolution (const geometry_msgs::Pose &pose, unsigned int solution_index, std::vector< double > &solution) const
 Get a candidate solution for a particular pose. Note that the pose will be projected onto the grid used in the caching process. More...
 
bool getSolutions (const geometry_msgs::Pose &pose, std::vector< std::vector< double > > &solutions) const
 Get all candidate solutions for a particular pose. Note that the pose will be projected onto the grid used in the caching process. The size of the solutions vector MUST be pre-allocated to num_solutions (see getNumSolutions) More...
 
bool getNumSolutions (const geometry_msgs::Pose &pose, unsigned int &num_solutions) const
 Get number of candidate solutions for a particular pose. More...
 
bool initialize (kinematics::KinematicsBaseConstPtr &solver, const moveit::core::RobotModelConstPtr &kinematic_model, const KinematicsCache::Options &opt)
 Initialize the cache class. More...
 
const kinematics::KinematicsBaseConstPtr & getSolverInstance () const
 Return the instance of the kinematics solver. More...
 
const moveit::core::RobotModelConstPtr & getModelInstance () const
 Return the instance of the kinematics model. More...
 
const OptionsgetCacheParameters () const
 Return the cache parameters used for cache construction. More...
 
const std::string & getGroupName () const
 
bool addToCache (const geometry_msgs::Pose &pose, const std::vector< double > &joint_values, bool overwrite=false)
 Add a new solution to the cache at the given location. More...
 
bool writeToFile (const std::string &filename)
 
bool readFromFile (const std::string &filename)
 
std::pair< double, double > getMinMaxSquaredDistance ()
 

Detailed Description

Definition at line 46 of file kinematics_cache_ros.h.

Constructor & Destructor Documentation

◆ KinematicsCacheROS()

kinematics_cache_ros::KinematicsCacheROS::KinematicsCacheROS ( )
inline

Definition at line 53 of file kinematics_cache_ros.h.

Member Function Documentation

◆ init()

bool kinematics_cache_ros::KinematicsCacheROS::init ( const kinematics_cache::KinematicsCache::Options opt,
const std::string &  kinematics_solver_name,
const std::string &  group_name,
const std::string &  base_frame,
const std::string &  tip_frame,
double  search_discretization 
)

Initialization function.

Parameters
optA set of options for setting up the cache

Definition at line 52 of file kinematics_cache_ros.cpp.

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

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