00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 
00038 #include <moveit/kinematics_cache/kinematics_cache.h>
00039 #include <fstream>
00040 #include <iostream>
00041 
00042 namespace kinematics_cache
00043 {
00044 KinematicsCache::KinematicsCache() : min_squared_distance_(1e6), max_squared_distance_(0.0)
00045 {
00046 }
00047 
00048 bool KinematicsCache::initialize(kinematics::KinematicsBaseConstPtr& kinematics_solver,
00049                                  const robot_model::RobotModelConstPtr& kinematic_model,
00050                                  const KinematicsCache::Options& opt)
00051 {
00052   options_ = opt;
00053   kinematics_solver_ = kinematics_solver;
00054   kinematic_model_ = kinematic_model;
00055   joint_model_group_ = kinematic_model_->getJointModelGroup(kinematics_solver_->getGroupName());
00056   kinematic_state_.reset(new robot_state::RobotState(kinematic_model));
00057   joint_state_group_.reset(new robot_state::JointStateGroup(kinematic_state_.get(), joint_model_group_));
00058 
00059   setup(opt);
00060   return true;
00061 }
00062 
00063 void KinematicsCache::setup(const KinematicsCache::Options& opt)
00064 {
00065   cache_origin_ = opt.origin;
00066   cache_resolution_x_ = opt.resolution[0];
00067   cache_resolution_y_ = opt.resolution[1];
00068   cache_resolution_z_ = opt.resolution[2];
00069 
00070   cache_size_x_ = (unsigned int)(opt.workspace_size[0] / opt.resolution[0]);
00071   cache_size_y_ = (unsigned int)(opt.workspace_size[1] / opt.resolution[1]);
00072   cache_size_z_ = (unsigned int)(opt.workspace_size[2] / opt.resolution[2]);
00073   max_solutions_per_grid_location_ = std::max((unsigned int)1, opt.max_solutions_per_grid_location);
00074   solution_dimension_ = joint_model_group_->getVariableCount();
00075   size_grid_node_ = max_solutions_per_grid_location_ * solution_dimension_;
00076   kinematics_cache_size_ = cache_size_x_ * cache_size_y_ * cache_size_z_;
00077   kinematics_cache_points_with_solution_ = 0;
00078   kinematics_cache_vector_.resize(kinematics_cache_size_ * size_grid_node_, 0.0);
00079   num_solutions_vector_.resize(kinematics_cache_size_, 0);
00080   logDebug("Origin: %f %f %f", cache_origin_.x, cache_origin_.y, cache_origin_.z);
00081   logDebug("Cache size (num points x,y,z): %d %d %d", cache_size_x_, cache_size_y_, cache_size_z_);
00082   logDebug("Cache resolution: %f %f %f", cache_resolution_x_, cache_resolution_y_, cache_resolution_z_);
00083   logDebug("Solutions per grid location: %d", (int)max_solutions_per_grid_location_);
00084   logDebug("Solution dimension: %d", (int)solution_dimension_);
00085 }
00086 
00087 bool KinematicsCache::generateCacheMap(double timeout)
00088 {
00089   ros::WallTime start_time = ros::WallTime::now();
00090   std::vector<std::string> fk_names;
00091   std::vector<double> fk_values;
00092   std::vector<geometry_msgs::Pose> poses;
00093 
00094   fk_names.push_back(kinematics_solver_->getTipFrame());
00095   fk_values.resize(kinematics_solver_->getJointNames().size(), 0.0);
00096   poses.resize(1);
00097 
00098   while ((ros::WallTime::now() - start_time).toSec() <= timeout &&
00099          kinematics_cache_points_with_solution_ <= kinematics_cache_size_)
00100   {
00101     joint_state_group_->setToRandomValues();
00102     joint_state_group_->getVariableValues(fk_values);
00103     if (!kinematics_solver_->getPositionFK(fk_names, fk_values, poses))
00104     {
00105       logError("Fk failed");
00106       return false;
00107     }
00108     if (!addToCache(poses[0], fk_values))
00109     {
00110       logDebug("Adding to cache failed for: %f %f %f", poses[0].position.x, poses[0].position.y, poses[0].position.z);
00111     }
00112     logDebug("Adding: %d", kinematics_cache_points_with_solution_);
00113   }
00114   logDebug("Cache map generated with %d valid points", kinematics_cache_points_with_solution_);
00115   return true;
00116 }
00117 
00118 bool KinematicsCache::addToCache(const geometry_msgs::Pose& pose, const std::vector<double>& joint_values,
00119                                  bool overwrite)
00120 {
00121   unsigned int grid_index;
00122   if (!getGridIndex(pose, grid_index))
00123   {
00124     logDebug("Failed to get grid index");
00125     return false;
00126   }
00127   unsigned int num_solutions = num_solutions_vector_[grid_index];
00128   if (!overwrite && num_solutions >= max_solutions_per_grid_location_)
00129   {
00130     logDebug("Pose already has max number of solutions");
00131     return true;
00132   }
00133   if (num_solutions == 0)
00134     kinematics_cache_points_with_solution_++;
00135   if (overwrite && num_solutions >= max_solutions_per_grid_location_)
00136     num_solutions = 0;
00137   unsigned int start_index = getSolutionLocation(grid_index, num_solutions);
00138   for (unsigned int i = 0; i < joint_values.size(); ++i)
00139   {
00140     
00141     kinematics_cache_vector_[start_index + i] = joint_values[i];
00142   }
00143   if (num_solutions_vector_[grid_index] < max_solutions_per_grid_location_)
00144     num_solutions_vector_[grid_index]++;
00145   updateDistances(pose);
00146   return true;
00147 }
00148 
00149 bool KinematicsCache::getGridIndex(const geometry_msgs::Pose& pose, unsigned int& grid_index) const
00150 {
00151   int x_index = (int)((pose.position.x - cache_origin_.x) / cache_resolution_x_);
00152   int y_index = (int)((pose.position.y - cache_origin_.y) / cache_resolution_y_);
00153   int z_index = (int)((pose.position.z - cache_origin_.z) / cache_resolution_z_);
00154 
00155   if (x_index >= (int)cache_size_x_ || x_index < 0)
00156   {
00157     logDebug("X position %f,%d lies outside grid: %d %d", pose.position.x, x_index, 0, cache_size_x_);
00158     return false;
00159   }
00160   if (y_index >= (int)cache_size_y_ || y_index < 0)
00161   {
00162     logDebug("Y position %f,%d lies outside grid: %d %d", pose.position.y, y_index, 0, cache_size_y_);
00163     return false;
00164   }
00165   if (z_index >= (int)cache_size_z_ || z_index < 0)
00166   {
00167     logDebug("Z position %f,%d lies outside grid: %d %d", pose.position.z, z_index, 0, cache_size_z_);
00168     return false;
00169   }
00170   logDebug("Grid indices: %d %d %d", x_index, y_index, z_index);
00171   grid_index = (x_index + y_index * cache_size_x_ + z_index * cache_size_x_ * cache_size_y_);
00172   return true;
00173 }
00174 
00175 bool KinematicsCache::getNumSolutions(const geometry_msgs::Pose& pose, unsigned int& num_solutions) const
00176 {
00177   unsigned int grid_index;
00178   if (!getGridIndex(pose, grid_index))
00179     return false;
00180 
00181   num_solutions = num_solutions_vector_[grid_index];
00182   return true;
00183 }
00184 
00185 unsigned int KinematicsCache::getSolutionLocation(unsigned int& grid_index, unsigned int& solution_index) const
00186 {
00187   logDebug("[Grid Index, Solution number location]: %d, %d", grid_index,
00188            grid_index * size_grid_node_ + solution_index * solution_dimension_);
00189   return (grid_index * size_grid_node_ + solution_index * solution_dimension_);
00190 }
00191 
00192 bool KinematicsCache::getSolution(const geometry_msgs::Pose& pose, unsigned int solution_index,
00193                                   std::vector<double>& solution) const
00194 {
00195   unsigned int grid_index;
00196   if (!getGridIndex(pose, grid_index))
00197     return false;
00198   if (solution_index >= max_solutions_per_grid_location_)
00199     return false;
00200   if (solution.size() < solution_dimension_)
00201     return false;
00202 
00203   solution = getSolution(grid_index, solution_index);
00204   return true;
00205 }
00206 
00207 bool KinematicsCache::getSolutions(const geometry_msgs::Pose& pose, std::vector<std::vector<double> >& solution) const
00208 {
00209   unsigned int grid_index;
00210   if (!getGridIndex(pose, grid_index))
00211     return false;
00212   if (solution.size() != num_solutions_vector_[grid_index])
00213     return false;
00214   for (unsigned int i = 0; i < solution.size(); i++)
00215   {
00216     if (solution[i].size() != solution_dimension_)
00217       return false;
00218     solution[i] = getSolution(grid_index, i);
00219   }
00220   return true;
00221 }
00222 
00223 std::vector<double> KinematicsCache::getSolution(unsigned int grid_index, unsigned int solution_index) const
00224 {
00225   std::vector<double> solution_local(solution_dimension_);
00226   unsigned int solution_location = getSolutionLocation(grid_index, solution_index);
00227   for (unsigned int i = 0; i < solution_dimension_; ++i)
00228     solution_local[i] = kinematics_cache_vector_[solution_location + i];
00229   return solution_local;
00230 }
00231 
00232 bool KinematicsCache::readFromFile(const std::string& filename)
00233 {
00234   std::ifstream file(filename.c_str());
00235   if (!file.is_open())
00236   {
00237     logDebug("Could not open file: %s", filename.c_str());
00238     return false;
00239   }
00240   std::string group_name;
00241   std::getline(file, group_name);
00242   if (group_name.empty())
00243   {
00244     logError("Could not find group_name in file: %s", group_name.c_str());
00245     file.close();
00246     return false;
00247   }
00248   if (group_name != kinematics_solver_->getGroupName())
00249   {
00250     logError("Input file group name %s does not match solver group name %s", group_name.c_str(),
00251              kinematics_solver_->getGroupName().c_str());
00252     file.close();
00253     return false;
00254   }
00255 
00256   std::string line_string;
00257   std::getline(file, line_string);
00258   std::stringstream line_stream(line_string);
00259   line_stream >> options_.origin.x >> options_.origin.y >> options_.origin.z;
00260 
00261   std::getline(file, line_string);
00262   line_stream.clear();
00263   line_stream.str("");
00264   line_stream << line_string;
00265   line_stream >> options_.workspace_size[0] >> options_.workspace_size[1] >> options_.workspace_size[2];
00266 
00267   std::getline(file, line_string);
00268   line_stream.clear();
00269   line_stream.str("");
00270   line_stream << line_string;
00271   line_stream >> options_.resolution[0] >> options_.resolution[1] >> options_.resolution[2];
00272 
00273   std::getline(file, line_string);
00274   line_stream.clear();
00275   line_stream.str("");
00276   line_stream << line_string;
00277   line_stream >> options_.max_solutions_per_grid_location;
00278 
00279   setup(options_);
00280 
00281   std::getline(file, line_string);
00282   line_stream.clear();
00283   line_stream.str("");
00284   line_stream << line_string;
00285   line_stream >> min_squared_distance_;
00286 
00287   std::getline(file, line_string);
00288   line_stream.clear();
00289   line_stream.str("");
00290   line_stream << line_string;
00291   line_stream >> max_squared_distance_;
00292 
00293   std::vector<double> kinematics_cache_vector;
00294   std::vector<unsigned int> num_solutions_vector;
00295   std::getline(file, line_string);
00296   std::getline(file, line_string);
00297   line_stream.clear();
00298   line_stream.str("");
00299   line_stream << line_string;
00300   double d;
00301   while (line_stream >> d)
00302   {
00303     kinematics_cache_vector.push_back(d);
00304   }
00305 
00306   std::getline(file, line_string);
00307   std::getline(file, line_string);
00308   line_stream.clear();
00309   line_stream.str("");
00310   line_stream << line_string;
00311   unsigned int index;
00312   while (line_stream >> index)
00313   {
00314     num_solutions_vector.push_back(index);
00315   }
00316 
00317   file.close();
00318 
00319   kinematics_cache_vector_ = kinematics_cache_vector;
00320   num_solutions_vector_ = num_solutions_vector;
00321   logDebug("Read %d total points from file: %s", (int)num_solutions_vector_.size(), filename.c_str());
00322   return true;
00323 }
00324 
00325 bool KinematicsCache::writeToFile(const std::string& filename)
00326 {
00327   logDebug("Writing %d total points to file: %s", (int)num_solutions_vector_.size(), filename.c_str());
00328   std::ofstream file;
00329   file.open(filename.c_str());
00330   if (!file.is_open())
00331   {
00332     logDebug("Could not open file: %s", filename.c_str());
00333     return false;
00334   }
00335   if (file.good())
00336   {
00337     std::string group_name = kinematics_solver_->getGroupName();
00338     file << group_name << std::endl;
00339 
00340     file << options_.origin.x << " " << options_.origin.y << " " << options_.origin.z << std::endl;
00341     file << options_.workspace_size[0] << " " << options_.workspace_size[1] << " " << options_.workspace_size[2]
00342          << std::endl;
00343     file << options_.resolution[0] << " " << options_.resolution[1] << " " << options_.resolution[2] << std::endl;
00344     file << options_.max_solutions_per_grid_location << std::endl;
00345     file << min_squared_distance_ << std::endl;
00346     file << max_squared_distance_ << std::endl;
00347     file << kinematics_cache_vector_.size() << std::endl;
00348     std::copy(kinematics_cache_vector_.begin(), kinematics_cache_vector_.end(),
00349               std::ostream_iterator<double>(file, " "));
00350     file << std::endl;
00351 
00352     file << num_solutions_vector_.size() << std::endl;
00353     std::copy(num_solutions_vector_.begin(), num_solutions_vector_.end(),
00354               std::ostream_iterator<unsigned int>(file, " "));
00355     file << std::endl;
00356   }
00357 
00358   file.close();
00359   return true;
00360 }
00361 
00362 std::pair<double, double> KinematicsCache::getMinMaxSquaredDistance()
00363 {
00364   return std::pair<double, double>(min_squared_distance_, max_squared_distance_);
00365 }
00366 
00367 void KinematicsCache::updateDistances(const geometry_msgs::Pose& pose)
00368 {
00369   double distance_squared =
00370       (pose.position.x * pose.position.x + pose.position.y * pose.position.y + pose.position.z * pose.position.z);
00371   min_squared_distance_ = std::min<double>(distance_squared, min_squared_distance_);
00372   max_squared_distance_ = std::max<double>(distance_squared, max_squared_distance_);
00373 }
00374 }