48 bool KinematicsCache::initialize(kinematics::KinematicsBaseConstPtr& kinematics_solver,
49 const moveit::core::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<moveit::core::RobotState>(kinematic_model);
57 joint_state_group_ = std::make_shared<moveit::core::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_NAMED(
"kinematics_cache",
"Origin: %f %f %f", cache_origin_.x, cache_origin_.y, cache_origin_.z);
81 ROS_DEBUG_NAMED(
"kinematics_cache",
"Cache size (num points x,y,z): %d %d %d", cache_size_x_, cache_size_y_,
83 ROS_DEBUG_NAMED(
"kinematics_cache",
"Cache resolution: %f %f %f", cache_resolution_x_, cache_resolution_y_,
85 ROS_DEBUG_NAMED(
"kinematics_cache",
"Solutions per grid location: %d",
86 static_cast<int> max_solutions_per_grid_location_);
87 ROS_DEBUG_NAMED(
"kinematics_cache",
"Solution dimension: %d",
static_cast<int> solution_dimension_);
90 bool KinematicsCache::generateCacheMap(
double timeout)
92 ros::WallTime start_time = ros::WallTime::now();
93 std::vector<std::string> fk_names;
94 std::vector<double> fk_values;
95 std::vector<geometry_msgs::Pose> poses;
97 fk_names.push_back(kinematics_solver_->getTipFrame());
98 fk_values.resize(kinematics_solver_->getJointNames().size(), 0.0);
101 while ((ros::WallTime::now() - start_time).toSec() <= timeout &&
102 kinematics_cache_points_with_solution_ <= kinematics_cache_size_)
104 joint_state_group_->setToRandomValues();
105 joint_state_group_->getVariableValues(fk_values);
106 if (!kinematics_solver_->getPositionFK(fk_names, fk_values, poses))
108 ROS_ERROR_NAMED(
"kinematics_cache",
"Fk failed");
111 if (!addToCache(poses[0], fk_values))
113 ROS_DEBUG_NAMED(
"kinematics_cache",
"Adding to cache failed for: %f %f %f", poses[0].position.x,
114 poses[0].position.y, poses[0].position.z);
116 ROS_DEBUG_NAMED(
"kinematics_cache",
"Adding: %d", kinematics_cache_points_with_solution_);
118 ROS_DEBUG_NAMED(
"kinematics_cache",
"Cache map generated with %d valid points",
119 kinematics_cache_points_with_solution_);
123 bool KinematicsCache::addToCache(
const geometry_msgs::Pose& pose,
const std::vector<double>& joint_values,
126 unsigned int grid_index;
127 if (!getGridIndex(pose, grid_index))
129 ROS_DEBUG_NAMED(
"kinematics_cache",
"Failed to get grid index");
132 unsigned int num_solutions = num_solutions_vector_[grid_index];
133 if (!overwrite && num_solutions >= max_solutions_per_grid_location_)
135 ROS_DEBUG_NAMED(
"kinematics_cache",
"Pose already has max number of solutions");
138 if (num_solutions == 0)
139 kinematics_cache_points_with_solution_++;
140 if (overwrite && num_solutions >= max_solutions_per_grid_location_)
142 unsigned int start_index = getSolutionLocation(grid_index, num_solutions);
143 for (
unsigned int i = 0; i < joint_values.size(); ++i)
146 kinematics_cache_vector_[start_index + i] = joint_values[i];
148 if (num_solutions_vector_[grid_index] < max_solutions_per_grid_location_)
149 num_solutions_vector_[grid_index]++;
150 updateDistances(pose);
154 bool KinematicsCache::getGridIndex(
const geometry_msgs::Pose& pose,
unsigned int& grid_index)
const
156 int x_index =
static_cast<int>((pose.position.x - cache_origin_.x) / cache_resolution_x_);
157 int y_index =
static_cast<int>((pose.position.y - cache_origin_.y) / cache_resolution_y_);
158 int z_index =
static_cast<int>((pose.position.z - cache_origin_.z) / cache_resolution_z_);
160 if (x_index >=
static_cast<int>(cache_size_x_ || x_index < 0))
162 ROS_DEBUG_NAMED(
"kinematics_cache",
"X position %f,%d lies outside grid: %d %d", pose.position.x, x_index, 0,
166 if (y_index >=
static_cast<int>(cache_size_y_) || y_index < 0)
168 ROS_DEBUG_NAMED(
"kinematics_cache",
"Y position %f,%d lies outside grid: %d %d", pose.position.y, y_index, 0,
172 if (z_index >=
static_cast<int>(cache_size_z_) || z_index < 0)
174 ROS_DEBUG_NAMED(
"kinematics_cache",
"Z position %f,%d lies outside grid: %d %d", pose.position.z, z_index, 0,
178 ROS_DEBUG_NAMED(
"kinematics_cache",
"Grid indices: %d %d %d", x_index, y_index, z_index);
179 grid_index = (x_index + y_index * cache_size_x_ + z_index * cache_size_x_ * cache_size_y_);
183 bool KinematicsCache::getNumSolutions(
const geometry_msgs::Pose& pose,
unsigned int& num_solutions)
const
185 unsigned int grid_index;
186 if (!getGridIndex(pose, grid_index))
189 num_solutions = num_solutions_vector_[grid_index];
193 unsigned int KinematicsCache::getSolutionLocation(
unsigned int& grid_index,
unsigned int& solution_index)
const
195 ROS_DEBUG_NAMED(
"kinematics_cache",
"[Grid Index, Solution number location]: %d, %d", grid_index,
196 grid_index * size_grid_node_ + solution_index * solution_dimension_);
197 return (grid_index * size_grid_node_ + solution_index * solution_dimension_);
200 bool KinematicsCache::getSolution(
const geometry_msgs::Pose& pose,
unsigned int solution_index,
201 std::vector<double>& solution)
const
203 unsigned int grid_index;
204 if (!getGridIndex(pose, grid_index))
206 if (solution_index >= max_solutions_per_grid_location_)
208 if (solution.size() < solution_dimension_)
211 solution = getSolution(grid_index, solution_index);
215 bool KinematicsCache::getSolutions(
const geometry_msgs::Pose& pose, std::vector<std::vector<double> >& solution)
const
217 unsigned int grid_index;
218 if (!getGridIndex(pose, grid_index))
220 if (solution.size() != num_solutions_vector_[grid_index])
222 for (
unsigned int i = 0; i < solution.size(); ++i)
224 if (solution[i].size() != solution_dimension_)
226 solution[i] = getSolution(grid_index, i);
231 std::vector<double> KinematicsCache::getSolution(
unsigned int grid_index,
unsigned int solution_index)
const
233 std::vector<double> solution_local(solution_dimension_);
234 unsigned int solution_location = getSolutionLocation(grid_index, solution_index);
235 for (
unsigned int i = 0; i < solution_dimension_; ++i)
236 solution_local[i] = kinematics_cache_vector_[solution_location + i];
237 return solution_local;
240 bool KinematicsCache::readFromFile(
const std::string& filename)
242 std::ifstream file(filename.c_str());
245 ROS_DEBUG_NAMED(
"kinematics_cache",
"Could not open file: %s", filename.c_str());
248 std::string group_name;
249 std::getline(file, group_name);
250 if (group_name.empty())
252 ROS_ERROR_NAMED(
"kinematics_cache",
"Could not find group_name in file: %s", group_name.c_str());
256 if (group_name != kinematics_solver_->getGroupName())
258 ROS_ERROR_NAMED(
"kinematics_cache",
"Input file group name %s does not match solver group name %s",
259 group_name.c_str(), kinematics_solver_->getGroupName().c_str());
264 std::string line_string;
265 std::getline(file, line_string);
266 std::stringstream line_stream(line_string);
267 line_stream >> options_.origin.x >> options_.origin.y >> options_.origin.z;
269 std::getline(file, line_string);
272 line_stream << line_string;
273 line_stream >> options_.workspace_size[0] >> options_.workspace_size[1] >> options_.workspace_size[2];
275 std::getline(file, line_string);
278 line_stream << line_string;
279 line_stream >> options_.resolution[0] >> options_.resolution[1] >> options_.resolution[2];
281 std::getline(file, line_string);
284 line_stream << line_string;
285 line_stream >> options_.max_solutions_per_grid_location;
289 std::getline(file, line_string);
292 line_stream << line_string;
293 line_stream >> min_squared_distance_;
295 std::getline(file, line_string);
298 line_stream << line_string;
299 line_stream >> max_squared_distance_;
301 std::vector<double> kinematics_cache_vector;
302 std::vector<unsigned int> num_solutions_vector;
303 std::getline(file, line_string);
304 std::getline(file, line_string);
307 line_stream << line_string;
309 while (line_stream >>
d)
311 kinematics_cache_vector.push_back(
d);
314 std::getline(file, line_string);
315 std::getline(file, line_string);
318 line_stream << line_string;
320 while (line_stream >> index)
322 num_solutions_vector.push_back(index);
327 kinematics_cache_vector_ = kinematics_cache_vector;
328 num_solutions_vector_ = num_solutions_vector;
329 ROS_DEBUG_NAMED(
"kinematics_cache",
"Read %d total points from file: %s",
330 static_cast<int>(num_solutions_vector_.size()), filename.c_str());
334 bool KinematicsCache::writeToFile(
const std::string& filename)
336 ROS_DEBUG_NAMED(
"kinematics_cache",
"Writing %d total points to file: %s",
337 static_cast<int>(num_solutions_vector_.size()), filename.c_str());
339 file.open(filename.c_str());
342 ROS_DEBUG_NAMED(
"kinematics_cache",
"Could not open file: %s", filename.c_str());
347 std::string group_name = kinematics_solver_->getGroupName();
348 file << group_name <<
'\n';
350 file << options_.origin.x <<
" " << options_.origin.y <<
" " << options_.origin.z <<
'\n';
351 file << options_.workspace_size[0] <<
" " << options_.workspace_size[1] <<
" " << options_.workspace_size[2]
353 file << options_.resolution[0] <<
" " << options_.resolution[1] <<
" " << options_.resolution[2] <<
'\n';
354 file << options_.max_solutions_per_grid_location <<
'\n';
355 file << min_squared_distance_ <<
'\n';
356 file << max_squared_distance_ <<
'\n';
357 file << kinematics_cache_vector_.size() <<
'\n';
358 std::copy(kinematics_cache_vector_.begin(), kinematics_cache_vector_.end(),
359 std::ostream_iterator<double>(file,
" "));
362 file << num_solutions_vector_.size() <<
'\n';
363 std::copy(num_solutions_vector_.begin(), num_solutions_vector_.end(),
364 std::ostream_iterator<unsigned int>(file,
" "));
372 std::pair<double, double> KinematicsCache::getMinMaxSquaredDistance()
374 return std::pair<double, double>(min_squared_distance_, max_squared_distance_);
377 void KinematicsCache::updateDistances(
const geometry_msgs::Pose& pose)
379 double distance_squared =
380 (pose.position.x * pose.position.x + pose.position.y * pose.position.y + pose.position.z * pose.position.z);
381 min_squared_distance_ = std::min<double>(distance_squared, min_squared_distance_);
382 max_squared_distance_ = std::max<double>(distance_squared, max_squared_distance_);