#include <kinematics_cache.h>
Classes | |
struct | Options |
Public Member Functions | |
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. | |
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. | |
bool | generateCacheMap (double timeout) |
Generate the cache map spending timeout (seconds) on the generation process) | |
bool | generateCacheMap (double timeout) |
Generate the cache map spending timeout (seconds) on the generation process) | |
const Options & | getCacheParameters () const |
Return the cache parameters used for cache construction. | |
const Options & | getCacheParameters () const |
Return the cache parameters used for cache construction. | |
const std::string | getGroupName () |
const std::string & | getGroupName () const |
std::pair< double, double > | getMinMaxSquaredDistance () |
std::pair< double, double > | getMinMaxSquaredDistance () |
const planning_models::RobotModelConstPtr & | getModelInstance () const |
Return the instance of the kinematics model. | |
const robot_model::RobotModelConstPtr & | getModelInstance () const |
Return the instance of the kinematics model. | |
bool | getNumSolutions (const geometry_msgs::Pose &pose, unsigned int &num_solutions) const |
Get number of candidate solutions for a particular pose. | |
bool | getNumSolutions (const geometry_msgs::Pose &pose, unsigned int &num_solutions) const |
Get number of candidate solutions for a particular pose. | |
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. | |
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. | |
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) | |
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) | |
const kinematics::KinematicsBaseConstPtr & | getSolverInstance () const |
Return the instance of the kinematics solver. | |
const kinematics::KinematicsBaseConstPtr & | getSolverInstance () const |
Return the instance of the kinematics solver. | |
bool | initialize (kinematics::KinematicsBaseConstPtr &solver, const planning_models::RobotModelConstPtr &kinematic_model, const KinematicsCache::Options &opt) |
Initialize the cache class. | |
bool | initialize (kinematics::KinematicsBaseConstPtr &solver, const robot_model::RobotModelConstPtr &kinematic_model, const KinematicsCache::Options &opt) |
Initialize the cache class. | |
KinematicsCache () | |
KinematicsCache () | |
bool | readFromFile (const std::string &filename) |
bool | readFromFile (const std::string &filename) |
bool | writeToFile (const std::string &filename) |
bool | writeToFile (const std::string &filename) |
Private Member Functions | |
bool | getGridIndex (const geometry_msgs::Pose &pose, unsigned int &grid_index) const |
Get the grid index for a given pose. | |
bool | getGridIndex (const geometry_msgs::Pose &pose, unsigned int &grid_index) const |
Get the grid index for a given pose. | |
std::vector< double > | getSolution (unsigned int grid_index, unsigned int solution_index) const |
Get a solution for the grid index given the solution index. | |
std::vector< double > | getSolution (unsigned int grid_index, unsigned int solution_index) const |
Get a solution for the grid index given the solution index. | |
unsigned int | getSolutionLocation (unsigned int &grid_index, unsigned int &solution_index) const |
Get the location of a solution given the grid index and solution index. | |
unsigned int | getSolutionLocation (unsigned int &grid_index, unsigned int &solution_index) const |
Get the location of a solution given the grid index and solution index. | |
void | setup (const KinematicsCache::Options &opt) |
Setup the cache. | |
void | setup (const KinematicsCache::Options &opt) |
Setup the cache. | |
void | updateDistances (const geometry_msgs::Pose &pose) |
void | updateDistances (const geometry_msgs::Pose &pose) |
Private Attributes | |
geometry_msgs::Point | cache_origin_ |
double | cache_resolution_x_ |
double | cache_resolution_y_ |
double | cache_resolution_z_ |
unsigned int | cache_size_x_ |
unsigned int | cache_size_y_ |
unsigned int | cache_size_z_ |
const planning_models::RobotModel::JointModelGroup * | joint_model_group_ |
const robot_model::JointModelGroup * | joint_model_group_ |
boost::shared_ptr < robot_state::JointStateGroup > | joint_state_group_ |
boost::shared_ptr < planning_models::RobotState *::JointStateGroup > | joint_state_group_ |
planning_models::RobotModelConstPtr | kinematic_model_ |
robot_model::RobotModelConstPtr | kinematic_model_ |
planning_models::RobotState *Ptr | kinematic_state_ |
robot_state::RobotStatePtr | kinematic_state_ |
unsigned int | kinematics_cache_points_with_solution_ |
unsigned int | kinematics_cache_size_ |
std::vector< double > | kinematics_cache_vector_ |
kinematics::KinematicsBaseConstPtr | kinematics_solver_ |
unsigned int | max_solutions_per_grid_location_ |
double | max_squared_distance_ |
double | min_squared_distance_ |
std::vector< unsigned int > | num_solutions_vector_ |
KinematicsCache::Options | options_ |
unsigned int | size_grid_node_ |
unsigned int | solution_dimension_ |
Definition at line 49 of file v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h.
Definition at line 44 of file v1/kinematics_cache/src/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.
Definition at line 119 of file v1/kinematics_cache/src/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 88 of file v1/kinematics_cache/src/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 |
const Options& kinematics_cache::KinematicsCache::getCacheParameters | ( | ) | const [inline] |
Return the cache parameters used for cache construction.
Definition at line 122 of file v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h.
const Options& kinematics_cache::KinematicsCache::getCacheParameters | ( | ) | const [inline] |
Return the cache parameters used for cache construction.
Definition at line 122 of file v2/kinematics_cache/include/moveit/kinematics_cache/kinematics_cache.h.
bool kinematics_cache::KinematicsCache::getGridIndex | ( | const geometry_msgs::Pose & | pose, |
unsigned int & | grid_index | ||
) | const [private] |
Get the grid index for a given pose.
bool kinematics_cache::KinematicsCache::getGridIndex | ( | const geometry_msgs::Pose & | pose, |
unsigned int & | grid_index | ||
) | const [private] |
Get the grid index for a given pose.
Definition at line 150 of file v1/kinematics_cache/src/kinematics_cache.cpp.
const std::string kinematics_cache::KinematicsCache::getGroupName | ( | ) | [inline] |
Definition at line 127 of file v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h.
const std::string& kinematics_cache::KinematicsCache::getGroupName | ( | ) | const [inline] |
Definition at line 127 of file v2/kinematics_cache/include/moveit/kinematics_cache/kinematics_cache.h.
std::pair< double, double > kinematics_cache::KinematicsCache::getMinMaxSquaredDistance | ( | ) |
Definition at line 363 of file v1/kinematics_cache/src/kinematics_cache.cpp.
std::pair<double, double> kinematics_cache::KinematicsCache::getMinMaxSquaredDistance | ( | ) |
const robot_model::RobotModelConstPtr& kinematics_cache::KinematicsCache::getModelInstance | ( | ) | const [inline] |
Return the instance of the kinematics model.
Definition at line 116 of file v2/kinematics_cache/include/moveit/kinematics_cache/kinematics_cache.h.
const planning_models::RobotModelConstPtr& kinematics_cache::KinematicsCache::getModelInstance | ( | ) | const [inline] |
Return the instance of the kinematics model.
Definition at line 116 of file v1/kinematics_cache/include/kinematics_cache/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 176 of file v1/kinematics_cache/src/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 193 of file v1/kinematics_cache/src/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 |
std::vector<double> kinematics_cache::KinematicsCache::getSolution | ( | unsigned int | grid_index, |
unsigned int | solution_index | ||
) | const [private] |
Get a solution for the grid index given the solution index.
std::vector< double > kinematics_cache::KinematicsCache::getSolution | ( | unsigned int | grid_index, |
unsigned int | solution_index | ||
) | const [private] |
Get a solution for the grid index given the solution index.
Definition at line 224 of file v1/kinematics_cache/src/kinematics_cache.cpp.
unsigned int kinematics_cache::KinematicsCache::getSolutionLocation | ( | unsigned int & | grid_index, |
unsigned int & | solution_index | ||
) | const [private] |
Get the location of a solution given the grid index and solution index.
unsigned int kinematics_cache::KinematicsCache::getSolutionLocation | ( | unsigned int & | grid_index, |
unsigned int & | solution_index | ||
) | const [private] |
Get the location of a solution given the grid index and solution index.
Definition at line 186 of file v1/kinematics_cache/src/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 |
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 208 of file v1/kinematics_cache/src/kinematics_cache.cpp.
const kinematics::KinematicsBaseConstPtr& kinematics_cache::KinematicsCache::getSolverInstance | ( | ) | const [inline] |
Return the instance of the kinematics solver.
Definition at line 110 of file v2/kinematics_cache/include/moveit/kinematics_cache/kinematics_cache.h.
const kinematics::KinematicsBaseConstPtr& kinematics_cache::KinematicsCache::getSolverInstance | ( | ) | const [inline] |
Return the instance of the kinematics solver.
Definition at line 110 of file v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h.
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 v1/kinematics_cache/src/kinematics_cache.cpp.
bool kinematics_cache::KinematicsCache::initialize | ( | kinematics::KinematicsBaseConstPtr & | solver, |
const robot_model::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 v2/kinematics_cache/src/kinematics_cache.cpp.
bool kinematics_cache::KinematicsCache::readFromFile | ( | const std::string & | filename | ) |
bool kinematics_cache::KinematicsCache::readFromFile | ( | const std::string & | filename | ) |
Definition at line 233 of file v1/kinematics_cache/src/kinematics_cache.cpp.
void kinematics_cache::KinematicsCache::setup | ( | const KinematicsCache::Options & | opt | ) | [private] |
Setup the cache.
Definition at line 64 of file v1/kinematics_cache/src/kinematics_cache.cpp.
void kinematics_cache::KinematicsCache::setup | ( | const KinematicsCache::Options & | opt | ) | [private] |
Setup the cache.
void kinematics_cache::KinematicsCache::updateDistances | ( | const geometry_msgs::Pose & | pose | ) | [private] |
Definition at line 368 of file v1/kinematics_cache/src/kinematics_cache.cpp.
void kinematics_cache::KinematicsCache::updateDistances | ( | const geometry_msgs::Pose & | pose | ) | [private] |
bool kinematics_cache::KinematicsCache::writeToFile | ( | const std::string & | filename | ) |
bool kinematics_cache::KinematicsCache::writeToFile | ( | const std::string & | filename | ) |
Definition at line 326 of file v1/kinematics_cache/src/kinematics_cache.cpp.
geometry_msgs::Point kinematics_cache::KinematicsCache::cache_origin_ [private] |
Internal copy of cache parameters
Definition at line 158 of file v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h.
double kinematics_cache::KinematicsCache::cache_resolution_x_ [private] |
Origin for cache workspace
Definition at line 159 of file v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h.
double kinematics_cache::KinematicsCache::cache_resolution_y_ [private] |
Definition at line 159 of file v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h.
double kinematics_cache::KinematicsCache::cache_resolution_z_ [private] |
Definition at line 159 of file v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h.
unsigned int kinematics_cache::KinematicsCache::cache_size_x_ [private] |
Resolution for grid (in m)
Definition at line 160 of file v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h.
unsigned int kinematics_cache::KinematicsCache::cache_size_y_ [private] |
Definition at line 160 of file v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h.
unsigned int kinematics_cache::KinematicsCache::cache_size_z_ [private] |
Definition at line 160 of file v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h.
const planning_models::RobotModel::JointModelGroup* kinematics_cache::KinematicsCache::joint_model_group_ [private] |
An instance of the kinematic state
Definition at line 175 of file v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h.
const robot_model::JointModelGroup* kinematics_cache::KinematicsCache::joint_model_group_ [private] |
An instance of the kinematic state
Definition at line 175 of file v2/kinematics_cache/include/moveit/kinematics_cache/kinematics_cache.h.
boost::shared_ptr<robot_state::JointStateGroup> kinematics_cache::KinematicsCache::joint_state_group_ [private] |
Joint model group associated with this cache
Definition at line 176 of file v2/kinematics_cache/include/moveit/kinematics_cache/kinematics_cache.h.
boost::shared_ptr<planning_models::RobotState* ::JointStateGroup> kinematics_cache::KinematicsCache::joint_state_group_ [private] |
Joint model group associated with this cache
Definition at line 177 of file v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h.
planning_models::RobotModelConstPtr kinematics_cache::KinematicsCache::kinematic_model_ [private] |
An instance of the kinematics solver
Reimplemented in kinematics_cache_ros::KinematicsCacheROS.
Definition at line 172 of file v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h.
robot_model::RobotModelConstPtr kinematics_cache::KinematicsCache::kinematic_model_ [private] |
An instance of the kinematics solver
Reimplemented in kinematics_cache_ros::KinematicsCacheROS.
Definition at line 172 of file v2/kinematics_cache/include/moveit/kinematics_cache/kinematics_cache.h.
planning_models::RobotState* Ptr kinematics_cache::KinematicsCache::kinematic_state_ [private] |
An instance of the kinematic model
Definition at line 173 of file v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h.
robot_state::RobotStatePtr kinematics_cache::KinematicsCache::kinematic_state_ [private] |
An instance of the kinematic model
Definition at line 173 of file v2/kinematics_cache/include/moveit/kinematics_cache/kinematics_cache.h.
unsigned int kinematics_cache::KinematicsCache::kinematics_cache_points_with_solution_ [private] |
Size of storage location (in number of doubles) for each grid node
Definition at line 164 of file v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h.
unsigned int kinematics_cache::KinematicsCache::kinematics_cache_size_ [private] |
Number of grid points that have solutions
Definition at line 165 of file v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h.
std::vector< double > kinematics_cache::KinematicsCache::kinematics_cache_vector_ [private] |
Total number of grid points
Definition at line 167 of file v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h.
kinematics::KinematicsBaseConstPtr kinematics_cache::KinematicsCache::kinematics_solver_ [private] |
Storage for number of solutions for each grid location
Reimplemented in kinematics_cache_ros::KinematicsCacheROS.
Definition at line 170 of file v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h.
unsigned int kinematics_cache::KinematicsCache::max_solutions_per_grid_location_ [private] |
Number of elements in XYZ grid
Definition at line 161 of file v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h.
double kinematics_cache::KinematicsCache::max_squared_distance_ [private] |
Definition at line 182 of file v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h.
double kinematics_cache::KinematicsCache::min_squared_distance_ [private] |
Joint state corresponding to cache
Definition at line 182 of file v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h.
std::vector< unsigned int > kinematics_cache::KinematicsCache::num_solutions_vector_ [private] |
Storage for the solutions
Definition at line 168 of file v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h.
Definition at line 157 of file v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h.
unsigned int kinematics_cache::KinematicsCache::size_grid_node_ [private] |
Dimension of each solution
Definition at line 163 of file v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h.
unsigned int kinematics_cache::KinematicsCache::solution_dimension_ [private] |
Max number of solutions per grid location
Definition at line 162 of file v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h.