|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <kinematics_cache.h>

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 Options & | getCacheParameters () 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 Options & | getCacheParameters () 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 () |
Definition at line 48 of file kinematics_cache.h.
| kinematics_cache::KinematicsCache::KinematicsCache | ( | ) |
Definition at line 44 of file kinematics_cache.cpp.
| kinematics_cache::KinematicsCache::KinematicsCache | ( | ) |
| 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.

| 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.
| bool kinematics_cache::KinematicsCache::generateCacheMap | ( | double | timeout | ) |
Generate the cache map spending timeout (seconds) on the generation process)
| timeout | Time (in seconds) to be spent on generating the cache |
Definition at line 87 of file kinematics_cache.cpp.


| bool kinematics_cache::KinematicsCache::generateCacheMap | ( | double | timeout | ) |
Generate the cache map spending timeout (seconds) on the generation process)
| timeout | Time (in seconds) to be spent on generating the cache |
|
inline |
Return the cache parameters used for cache construction.
Definition at line 121 of file kinematics_cache.h.
|
inline |
Return the cache parameters used for cache construction.
Definition at line 121 of file kinematics_cache.h.
|
inline |
Definition at line 126 of file kinematics_cache.h.
|
inline |
Definition at line 126 of file kinematics_cache.h.
| std::pair< double, double > kinematics_cache::KinematicsCache::getMinMaxSquaredDistance | ( | ) |
Definition at line 362 of file kinematics_cache.cpp.
| std::pair<double, double> kinematics_cache::KinematicsCache::getMinMaxSquaredDistance | ( | ) |
|
inline |
Return the instance of the kinematics model.
Definition at line 115 of file kinematics_cache.h.
|
inline |
Return the instance of the kinematics model.
Definition at line 115 of file kinematics_cache.h.
| bool kinematics_cache::KinematicsCache::getNumSolutions | ( | const geometry_msgs::Pose & | pose, |
| unsigned int & | num_solutions | ||
| ) | const |
Get number of candidate solutions for a particular pose.
| pose | The desired pose |
| solution_index | The solution index |
| solution | The actual solution |
Definition at line 175 of file kinematics_cache.cpp.

| bool kinematics_cache::KinematicsCache::getNumSolutions | ( | const geometry_msgs::Pose & | pose, |
| unsigned int & | num_solutions | ||
| ) | const |
Get number of candidate solutions for a particular pose.
| pose | The desired pose |
| solution_index | The solution index |
| solution | The actual solution |
| 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.
| pose | The desired pose |
| solution_index | The solution index |
| solution | The actual solution |
Definition at line 192 of file kinematics_cache.cpp.

| 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.
| pose | The desired pose |
| solution_index | The solution index |
| solution | The actual solution |
| 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)
| pose | The desired pose |
| solution_index | The solution index |
| solutions | The actual set of solutions |
Definition at line 207 of file kinematics_cache.cpp.

| 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)
| pose | The desired pose |
| solution_index | The solution index |
| solutions | The actual set of solutions |
|
inline |
Return the instance of the kinematics solver.
Definition at line 109 of file kinematics_cache.h.
|
inline |
Return the instance of the kinematics solver.
Definition at line 109 of file kinematics_cache.h.
| bool kinematics_cache::KinematicsCache::initialize | ( | kinematics::KinematicsBaseConstPtr & | solver, |
| const moveit::core::RobotModelConstPtr & | kinematic_model, | ||
| const KinematicsCache::Options & | opt | ||
| ) |
Initialize the cache class.
| solver | An instance of a kinematics solver |
| kinematic_model | An instance of a kinematic model |
| opt | Parameters needed for defining the cache workspace |
Definition at line 48 of file kinematics_cache.cpp.
| bool kinematics_cache::KinematicsCache::initialize | ( | kinematics::KinematicsBaseConstPtr & | solver, |
| const planning_models::RobotModelConstPtr & | kinematic_model, | ||
| const KinematicsCache::Options & | opt | ||
| ) |
Initialize the cache class.
| solver | An instance of a kinematics solver |
| kinematic_model | An instance of a kinematic model |
| opt | Parameters needed for defining the cache workspace |
Definition at line 48 of file kinematics_cache.cpp.

| bool kinematics_cache::KinematicsCache::readFromFile | ( | const std::string & | filename | ) |
Definition at line 232 of file kinematics_cache.cpp.
| bool kinematics_cache::KinematicsCache::readFromFile | ( | const std::string & | filename | ) |
| bool kinematics_cache::KinematicsCache::writeToFile | ( | const std::string & | filename | ) |
Definition at line 325 of file kinematics_cache.cpp.
| bool kinematics_cache::KinematicsCache::writeToFile | ( | const std::string & | filename | ) |