41 #include <planning_models/robot_model.h>
42 #include <planning_models/kinematic_state.h>
78 bool getSolution(
const geometry_msgs::Pose& pose,
unsigned int solution_index, std::vector<double>& solution)
const;
89 bool getSolutions(
const geometry_msgs::Pose& pose, std::vector<std::vector<double> >& solutions)
const;
97 bool getNumSolutions(
const geometry_msgs::Pose& pose,
unsigned int& num_solutions)
const;
105 bool initialize(kinematics::KinematicsBaseConstPtr& solver,
111 return kinematics_solver_;
117 return kinematic_model_;
128 return kinematics_solver_->getGroupName();
133 bool addToCache(
const geometry_msgs::Pose& pose,
const std::vector<double>& joint_values,
bool overwrite =
false);
143 unsigned int getSolutionLocation(
unsigned int& grid_index,
unsigned int& solution_index)
const;
146 std::vector<double>
getSolution(
unsigned int grid_index,
unsigned int solution_index)
const;
149 bool getGridIndex(
const geometry_msgs::Pose& pose,
unsigned int& grid_index)
const;
154 void updateDistances(
const geometry_msgs::Pose& pose);
157 geometry_msgs::Point cache_origin_;
158 double cache_resolution_x_, cache_resolution_y_, cache_resolution_z_;
159 unsigned int cache_size_x_, cache_size_y_, cache_size_z_;
160 unsigned int max_solutions_per_grid_location_;
161 unsigned int solution_dimension_;
162 unsigned int size_grid_node_;
163 unsigned int kinematics_cache_points_with_solution_;
164 unsigned int kinematics_cache_size_;
166 std::vector<double> kinematics_cache_vector_;
167 std::vector<unsigned int> num_solutions_vector_;
169 kinematics::KinematicsBaseConstPtr kinematics_solver_;
171 planning_models::RobotModelConstPtr kinematic_model_;
172 planning_models::RobotState* Ptr kinematic_state_;
174 const planning_models::RobotModel::JointModelGroup* joint_model_group_;
176 std::shared_ptr<planning_models::RobotState* ::JointStateGroup> joint_state_group_;
181 double min_squared_distance_, max_squared_distance_;
const planning_models::RobotModelConstPtr & getModelInstance() const
Return the instance of the kinematics model.
bool readFromFile(const std::string &filename)
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 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.
bool writeToFile(const std::string &filename)
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.
const std::string getGroupName()
bool getNumSolutions(const geometry_msgs::Pose &pose, unsigned int &num_solutions) const
Get number of candidate solutions for a particular pose.
std::pair< double, double > getMinMaxSquaredDistance()
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 us...
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...
std::shared_ptr< KinematicsCache > KinematicsCachePtr
unsigned int max_solutions_per_grid_location
geometry_msgs::Point origin
std::array< double, 3 > workspace_size
std::array< double, 3 > resolution