38 #include <kinematics_cache/kinematics_cache.h>
49 const planning_models::RobotModelConstPtr& kinematic_model,
53 kinematics_solver_ = kinematics_solver;
54 kinematic_model_ = kinematic_model;
55 joint_model_group_ = kinematic_model_->getJointModelGroup(kinematics_solver_->getGroupName());
56 kinematic_state_ = std::make_shared<planning_models::RobotState>(kinematic_model);
57 joint_state_group_ = std::make_shared<planning_models::JointStateGroup>(kinematic_state_.get(), joint_model_group_);
65 cache_origin_ =
opt.origin;
66 cache_resolution_x_ =
opt.resolution[0];
67 cache_resolution_y_ =
opt.resolution[1];
68 cache_resolution_z_ =
opt.resolution[2];
70 cache_size_x_ = (
unsigned int)(
opt.workspace_size[0] /
opt.resolution[0]);
71 cache_size_y_ = (
unsigned int)(
opt.workspace_size[1] /
opt.resolution[1]);
72 cache_size_z_ = (
unsigned int)(
opt.workspace_size[2] /
opt.resolution[2]);
73 max_solutions_per_grid_location_ = std::max((
unsigned int)1,
opt.max_solutions_per_grid_location);
74 solution_dimension_ = joint_model_group_->getVariableCount();
75 size_grid_node_ = max_solutions_per_grid_location_ * solution_dimension_;
76 kinematics_cache_size_ = cache_size_x_ * cache_size_y_ * cache_size_z_;
77 kinematics_cache_points_with_solution_ = 0;
78 kinematics_cache_vector_.resize(kinematics_cache_size_ * size_grid_node_, 0.0);
79 num_solutions_vector_.resize(kinematics_cache_size_, 0);
80 ROS_DEBUG(
"Origin: %f %f %f", cache_origin_.x, cache_origin_.y, cache_origin_.z);
81 ROS_DEBUG(
"Cache size (num points x,y,z): %d %d %d", cache_size_x_, cache_size_y_, cache_size_z_);
82 ROS_DEBUG(
"Cache resolution: %f %f %f", cache_resolution_x_, cache_resolution_y_, cache_resolution_z_);
83 ROS_DEBUG(
"Solutions per grid location: %d",
static_cast<int> max_solutions_per_grid_location_);
84 ROS_DEBUG(
"Solution dimension: %d",
static_cast<int> solution_dimension_);
89 ros::WallTime start_time = ros::WallTime::now();
90 std::vector<std::string> fk_names;
91 std::vector<double> fk_values;
92 std::vector<geometry_msgs::Pose> poses;
94 fk_names.push_back(kinematics_solver_->getTipFrame());
95 fk_values.resize(kinematics_solver_->getJointNames().size(), 0.0);
98 while ((ros::WallTime::now() - start_time).toSec() <= timeout &&
99 kinematics_cache_points_with_solution_ <= kinematics_cache_size_)
101 joint_state_group_->setToRandomValues();
102 joint_state_group_->getGroupStateValues(fk_values);
103 if (!kinematics_solver_->getPositionFK(fk_names, fk_values, poses))
105 ROS_ERROR(
"Fk failed");
110 ROS_DEBUG(
"Adding to cache failed for: %f %f %f", poses[0].position.x, poses[0].position.y, poses[0].position.z);
112 ROS_DEBUG(
"Adding: %d", kinematics_cache_points_with_solution_);
114 ROS_INFO(
"Cache map generated with %d valid points", kinematics_cache_points_with_solution_);
121 unsigned int grid_index;
122 if (!getGridIndex(pose, grid_index))
124 ROS_DEBUG(
"Failed to get grid index");
127 unsigned int num_solutions = num_solutions_vector_[grid_index];
128 if (!overwrite && num_solutions >= max_solutions_per_grid_location_)
130 ROS_DEBUG(
"Pose already has max number of solutions");
133 if (num_solutions == 0)
134 kinematics_cache_points_with_solution_++;
135 if (overwrite && num_solutions >= max_solutions_per_grid_location_)
137 unsigned int start_index = getSolutionLocation(grid_index, num_solutions);
138 for (
unsigned int i = 0; i < joint_values.size(); ++i)
141 kinematics_cache_vector_[start_index + i] = joint_values[i];
143 if (num_solutions_vector_[grid_index] < max_solutions_per_grid_location_)
144 num_solutions_vector_[grid_index]++;
145 updateDistances(pose);
149 bool KinematicsCache::getGridIndex(
const geometry_msgs::Pose& pose,
unsigned int& grid_index)
const
151 int x_index =
static_cast<int>((pose.position.x - cache_origin_.x) / cache_resolution_x_);
152 int y_index =
static_cast<int>((pose.position.y - cache_origin_.y) / cache_resolution_y_);
153 int z_index =
static_cast<int>((pose.position.z - cache_origin_.z) / cache_resolution_z_);
155 if (x_index >=
static_cast<int>(cache_size_x_ || x_index < 0))
157 ROS_DEBUG(
"X position %f,%d lies outside grid: %d %d", pose.position.x, x_index, 0, cache_size_x_);
160 if (y_index >=
static_cast<int>(cache_size_y_ || y_index < 0))
162 ROS_DEBUG(
"Y position %f,%d lies outside grid: %d %d", pose.position.y, y_index, 0, cache_size_y_);
165 if (z_index >=
static_cast<int>(cache_size_z_ || z_index < 0))
167 ROS_DEBUG(
"Z position %f,%d lies outside grid: %d %d", pose.position.z, z_index, 0, cache_size_z_);
170 ROS_DEBUG(
"Grid indices: %d %d %d", x_index, y_index, z_index);
171 grid_index = (x_index + y_index * cache_size_x_ + z_index * cache_size_x_ * cache_size_y_);
177 unsigned int grid_index;
178 if (!getGridIndex(pose, grid_index))
181 num_solutions = num_solutions_vector_[grid_index];
185 unsigned int KinematicsCache::getSolutionLocation(
unsigned int& grid_index,
unsigned int& solution_index)
const
187 ROS_DEBUG(
"[Grid Index, Solution number location]: %d, %d", grid_index,
188 grid_index * size_grid_node_ + solution_index * solution_dimension_);
189 return (grid_index * size_grid_node_ + solution_index * solution_dimension_);
193 std::vector<double>& solution)
const
195 unsigned int grid_index;
196 if (!getGridIndex(pose, grid_index))
198 if (solution_index >= max_solutions_per_grid_location_)
200 if (solution.size() < solution_dimension_)
203 solution =
getSolution(grid_index, solution_index);
209 unsigned int grid_index;
210 if (!getGridIndex(pose, grid_index))
212 if (solution.size() != num_solutions_vector_[grid_index])
214 for (
unsigned int i = 0; i < solution.size(); ++i)
216 if (solution[i].size() != solution_dimension_)
225 std::vector<double> solution_local(solution_dimension_);
226 unsigned int solution_location = getSolutionLocation(grid_index, solution_index);
227 for (
unsigned int i = 0; i < solution_dimension_; ++i)
228 solution_local[i] = kinematics_cache_vector_[solution_location + i];
229 return solution_local;
234 std::ifstream file(filename.c_str());
237 ROS_WARN(
"Could not open file: %s", filename.c_str());
240 std::string group_name;
241 std::getline(file, group_name);
242 if (group_name.empty())
244 ROS_ERROR(
"Could not find group_name in file: %s", group_name.c_str());
248 if (group_name != kinematics_solver_->getGroupName())
250 ROS_ERROR(
"Input file group name %s does not match solver group name %s", group_name.c_str(),
251 kinematics_solver_->getGroupName().c_str());
256 std::string line_string;
257 std::getline(file, line_string);
258 std::stringstream line_stream(line_string);
261 std::getline(file, line_string);
264 line_stream << line_string;
267 std::getline(file, line_string);
270 line_stream << line_string;
273 std::getline(file, line_string);
276 line_stream << line_string;
281 std::getline(file, line_string);
284 line_stream << line_string;
285 line_stream >> min_squared_distance_;
287 std::getline(file, line_string);
290 line_stream << line_string;
291 line_stream >> max_squared_distance_;
293 std::vector<double> kinematics_cache_vector;
294 std::vector<unsigned int> num_solutions_vector;
295 std::getline(file, line_string);
296 std::getline(file, line_string);
299 line_stream << line_string;
301 while (line_stream >>
d)
303 kinematics_cache_vector.push_back(
d);
306 std::getline(file, line_string);
307 std::getline(file, line_string);
310 line_stream << line_string;
312 while (line_stream >> index)
314 num_solutions_vector.push_back(index);
319 kinematics_cache_vector_ = kinematics_cache_vector;
320 num_solutions_vector_ = num_solutions_vector;
321 ROS_DEBUG(
"Read %d total points from file: %s",
static_cast<int> num_solutions_vector_.size(), filename.c_str());
327 ROS_DEBUG(
"Writing %d total points to file: %s",
static_cast<int> num_solutions_vector_.size(), filename.c_str());
329 file.open(filename.c_str());
332 ROS_WARN(
"Could not open file: %s", filename.c_str());
337 std::string group_name = kinematics_solver_->getGroupName();
338 file << group_name <<
'\n';
340 file << options_.
origin.x <<
" " << options_.
origin.y <<
" " << options_.
origin.z <<
'\n';
345 file << min_squared_distance_ <<
'\n';
346 file << max_squared_distance_ <<
'\n';
347 file << kinematics_cache_vector_.size() <<
'\n';
348 std::copy(kinematics_cache_vector_.begin(), kinematics_cache_vector_.end(),
349 std::ostream_iterator<double>(file,
" "));
352 file << num_solutions_vector_.size() <<
'\n';
353 std::copy(num_solutions_vector_.begin(), num_solutions_vector_.end(),
354 std::ostream_iterator<unsigned int>(file,
" "));
364 return std::pair<double, double>(min_squared_distance_, max_squared_distance_);
367 void KinematicsCache::updateDistances(
const geometry_msgs::Pose& pose)
369 double distance_squared =
370 (pose.position.x * pose.position.x + pose.position.y * pose.position.y + pose.position.z * pose.position.z);
371 min_squared_distance_ = std::min<double>(distance_squared, min_squared_distance_);
372 max_squared_distance_ = std::max<double>(distance_squared, max_squared_distance_);
bool readFromFile(const std::string &filename)
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)
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.
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...
unsigned int max_solutions_per_grid_location
geometry_msgs::Point origin
std::array< double, 3 > workspace_size
std::array< double, 3 > resolution