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

#include <kinematics_cache.h>

Inheritance diagram for kinematics_cache::KinematicsCache:
Inheritance graph
[legend]

Classes

struct  Options
 

Public Member Functions

 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 48 of file kinematics_cache.h.

Constructor & Destructor Documentation

◆ KinematicsCache() [1/2]

kinematics_cache::KinematicsCache::KinematicsCache ( )

Definition at line 44 of file kinematics_cache.cpp.

◆ KinematicsCache() [2/2]

kinematics_cache::KinematicsCache::KinematicsCache ( )

Member Function Documentation

◆ addToCache() [1/2]

bool kinematics_cache::KinematicsCache::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.

Definition at line 118 of file kinematics_cache.cpp.

Here is the caller graph for this function:

◆ addToCache() [2/2]

bool kinematics_cache::KinematicsCache::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.

◆ generateCacheMap() [1/2]

bool kinematics_cache::KinematicsCache::generateCacheMap ( double  timeout)

Generate the cache map spending timeout (seconds) on the generation process)

Parameters
timeoutTime (in seconds) to be spent on generating the cache
Returns
True if cache map generation was successful

Definition at line 87 of file kinematics_cache.cpp.

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

◆ generateCacheMap() [2/2]

bool kinematics_cache::KinematicsCache::generateCacheMap ( double  timeout)

Generate the cache map spending timeout (seconds) on the generation process)

Parameters
timeoutTime (in seconds) to be spent on generating the cache
Returns
True if cache map generation was successful

◆ getCacheParameters() [1/2]

const Options& kinematics_cache::KinematicsCache::getCacheParameters ( ) const
inline

Return the cache parameters used for cache construction.

Definition at line 121 of file kinematics_cache.h.

◆ getCacheParameters() [2/2]

const Options& kinematics_cache::KinematicsCache::getCacheParameters ( ) const
inline

Return the cache parameters used for cache construction.

Definition at line 121 of file kinematics_cache.h.

◆ getGroupName() [1/2]

const std::string kinematics_cache::KinematicsCache::getGroupName ( )
inline

Definition at line 126 of file kinematics_cache.h.

◆ getGroupName() [2/2]

const std::string& kinematics_cache::KinematicsCache::getGroupName ( ) const
inline

Definition at line 126 of file kinematics_cache.h.

◆ getMinMaxSquaredDistance() [1/2]

std::pair< double, double > kinematics_cache::KinematicsCache::getMinMaxSquaredDistance ( )

Definition at line 362 of file kinematics_cache.cpp.

◆ getMinMaxSquaredDistance() [2/2]

std::pair<double, double> kinematics_cache::KinematicsCache::getMinMaxSquaredDistance ( )

◆ getModelInstance() [1/2]

const planning_models::RobotModelConstPtr& kinematics_cache::KinematicsCache::getModelInstance ( ) const
inline

Return the instance of the kinematics model.

Definition at line 115 of file kinematics_cache.h.

◆ getModelInstance() [2/2]

const moveit::core::RobotModelConstPtr& kinematics_cache::KinematicsCache::getModelInstance ( ) const
inline

Return the instance of the kinematics model.

Definition at line 115 of file kinematics_cache.h.

◆ getNumSolutions() [1/2]

bool kinematics_cache::KinematicsCache::getNumSolutions ( const geometry_msgs::Pose &  pose,
unsigned int &  num_solutions 
) const

Get number of candidate solutions for a particular pose.

Parameters
poseThe desired pose
solution_indexThe solution index
solutionThe actual solution
Returns
False if desired pose lies outside the grid

Definition at line 175 of file kinematics_cache.cpp.

Here is the caller graph for this function:

◆ getNumSolutions() [2/2]

bool kinematics_cache::KinematicsCache::getNumSolutions ( const geometry_msgs::Pose &  pose,
unsigned int &  num_solutions 
) const

Get number of candidate solutions for a particular pose.

Parameters
poseThe desired pose
solution_indexThe solution index
solutionThe actual solution
Returns
False if desired pose lies outside the grid

◆ getSolution() [1/2]

bool kinematics_cache::KinematicsCache::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.

Parameters
poseThe desired pose
solution_indexThe solution index
solutionThe actual solution
Returns
False if desired pose lies outside the grid

Definition at line 192 of file kinematics_cache.cpp.

Here is the caller graph for this function:

◆ getSolution() [2/2]

bool kinematics_cache::KinematicsCache::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.

Parameters
poseThe desired pose
solution_indexThe solution index
solutionThe actual solution
Returns
False if desired pose lies outside the grid

◆ getSolutions() [1/2]

bool kinematics_cache::KinematicsCache::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)

Parameters
poseThe desired pose
solution_indexThe solution index
solutionsThe actual set of solutions
Returns
False if desired pose lies outside the grid or if size(solutions) is not set to num_solutions (see getNumSolutions)

Definition at line 207 of file kinematics_cache.cpp.

Here is the call graph for this function:

◆ getSolutions() [2/2]

bool kinematics_cache::KinematicsCache::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)

Parameters
poseThe desired pose
solution_indexThe solution index
solutionsThe actual set of solutions
Returns
False if desired pose lies outside the grid or if size(solutions) is not set to num_solutions (see getNumSolutions)

◆ getSolverInstance() [1/2]

const kinematics::KinematicsBaseConstPtr& kinematics_cache::KinematicsCache::getSolverInstance ( ) const
inline

Return the instance of the kinematics solver.

Definition at line 109 of file kinematics_cache.h.

◆ getSolverInstance() [2/2]

const kinematics::KinematicsBaseConstPtr& kinematics_cache::KinematicsCache::getSolverInstance ( ) const
inline

Return the instance of the kinematics solver.

Definition at line 109 of file kinematics_cache.h.

◆ initialize() [1/2]

bool kinematics_cache::KinematicsCache::initialize ( kinematics::KinematicsBaseConstPtr &  solver,
const moveit::core::RobotModelConstPtr &  kinematic_model,
const KinematicsCache::Options opt 
)

Initialize the cache class.

Parameters
solverAn instance of a kinematics solver
kinematic_modelAn instance of a kinematic model
optParameters needed for defining the cache workspace
Returns
False if any error occurred during initialization

Definition at line 48 of file kinematics_cache.cpp.

◆ initialize() [2/2]

bool kinematics_cache::KinematicsCache::initialize ( kinematics::KinematicsBaseConstPtr &  solver,
const planning_models::RobotModelConstPtr &  kinematic_model,
const KinematicsCache::Options opt 
)

Initialize the cache class.

Parameters
solverAn instance of a kinematics solver
kinematic_modelAn instance of a kinematic model
optParameters needed for defining the cache workspace
Returns
False if any error occurred during initialization

Definition at line 48 of file kinematics_cache.cpp.

Here is the caller graph for this function:

◆ readFromFile() [1/2]

bool kinematics_cache::KinematicsCache::readFromFile ( const std::string &  filename)

Definition at line 232 of file kinematics_cache.cpp.

◆ readFromFile() [2/2]

bool kinematics_cache::KinematicsCache::readFromFile ( const std::string &  filename)

◆ writeToFile() [1/2]

bool kinematics_cache::KinematicsCache::writeToFile ( const std::string &  filename)

Definition at line 325 of file kinematics_cache.cpp.

◆ writeToFile() [2/2]

bool kinematics_cache::KinematicsCache::writeToFile ( const std::string &  filename)

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