Public Member Functions | Private Attributes | 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]

Public Member Functions

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...
 
 KinematicsCacheROS ()
 
- Public Member Functions inherited from kinematics_cache::KinematicsCache
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 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 generateCacheMap (double timeout)
 Generate the cache map spending timeout (seconds) on the generation process) More...
 
bool generateCacheMap (double timeout)
 Generate the cache map spending timeout (seconds) on the generation process) More...
 
const OptionsgetCacheParameters () const
 Return the cache parameters used for cache construction. More...
 
const OptionsgetCacheParameters () const
 Return the cache parameters used for cache construction. More...
 
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. More...
 
const robot_model::RobotModelConstPtr & getModelInstance () const
 Return the instance of the kinematics model. More...
 
bool getNumSolutions (const geometry_msgs::Pose &pose, unsigned int &num_solutions) const
 Get number of candidate solutions for a particular pose. More...
 
bool getNumSolutions (const geometry_msgs::Pose &pose, unsigned int &num_solutions) const
 Get number of candidate solutions for a particular pose. 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 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 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...
 
const kinematics::KinematicsBaseConstPtr & getSolverInstance () const
 Return the instance of the kinematics solver. More...
 
const kinematics::KinematicsBaseConstPtr & getSolverInstance () const
 Return the instance of the kinematics solver. More...
 
bool initialize (kinematics::KinematicsBaseConstPtr &solver, const planning_models::RobotModelConstPtr &kinematic_model, const KinematicsCache::Options &opt)
 Initialize the cache class. More...
 
bool initialize (kinematics::KinematicsBaseConstPtr &solver, const robot_model::RobotModelConstPtr &kinematic_model, const KinematicsCache::Options &opt)
 Initialize the cache class. More...
 
 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 Attributes

planning_models::RobotModelPtr kinematic_model_
 
boost::shared_ptr< pluginlib::ClassLoader< kinematics::KinematicsBase > > kinematics_loader_
 
kinematics::KinematicsBase * kinematics_solver_
 

Detailed Description

Definition at line 47 of file kinematics_cache_ros.h.

Constructor & Destructor Documentation

kinematics_cache_ros::KinematicsCacheROS::KinematicsCacheROS ( )
inline

Definition at line 54 of file kinematics_cache_ros.h.

Member Function Documentation

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.

Member Data Documentation

planning_models::RobotModelPtr kinematics_cache_ros::KinematicsCacheROS::kinematic_model_
private

A loader needed to load the instance of a kinematics solver

Definition at line 69 of file kinematics_cache_ros.h.

boost::shared_ptr<pluginlib::ClassLoader<kinematics::KinematicsBase> > kinematics_cache_ros::KinematicsCacheROS::kinematics_loader_
private

An instance of a kinematics solver needed by this class

Definition at line 67 of file kinematics_cache_ros.h.

kinematics::KinematicsBase* kinematics_cache_ros::KinematicsCacheROS::kinematics_solver_
private

Definition at line 64 of file kinematics_cache_ros.h.


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


moveit_experimental
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley , Jorge Nicho
autogenerated on Wed Jul 10 2019 04:03:02