moveit2
The MoveIt Motion Planning Framework for ROS 2.
kinematics_cache.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2012, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Sachin Chitta
36  *********************************************************************/
37 
38 #include <kinematics_cache/kinematics_cache.h>
39 #include <fstream>
40 #include <iostream>
41 
42 namespace kinematics_cache
43 {
44 KinematicsCache::KinematicsCache() : min_squared_distance_(1e6), max_squared_distance_(0.0)
45 {
46 }
47 
48 bool KinematicsCache::initialize(kinematics::KinematicsBaseConstPtr& kinematics_solver,
49  const planning_models::RobotModelConstPtr& kinematic_model,
51 {
52  options_ = opt;
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_);
58 
59  setup(opt);
60  return true;
61 }
62 
63 void KinematicsCache::setup(const KinematicsCache::Options& opt)
64 {
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];
69 
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_);
85 }
86 
88 {
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;
93 
94  fk_names.push_back(kinematics_solver_->getTipFrame());
95  fk_values.resize(kinematics_solver_->getJointNames().size(), 0.0);
96  poses.resize(1);
97 
98  while ((ros::WallTime::now() - start_time).toSec() <= timeout &&
99  kinematics_cache_points_with_solution_ <= kinematics_cache_size_)
100  {
101  joint_state_group_->setToRandomValues();
102  joint_state_group_->getGroupStateValues(fk_values);
103  if (!kinematics_solver_->getPositionFK(fk_names, fk_values, poses))
104  {
105  ROS_ERROR("Fk failed");
106  return false;
107  }
108  if (!addToCache(poses[0], fk_values))
109  {
110  ROS_DEBUG("Adding to cache failed for: %f %f %f", poses[0].position.x, poses[0].position.y, poses[0].position.z);
111  }
112  ROS_DEBUG("Adding: %d", kinematics_cache_points_with_solution_);
113  }
114  ROS_INFO("Cache map generated with %d valid points", kinematics_cache_points_with_solution_);
115  return true;
116 }
117 
118 bool KinematicsCache::addToCache(const geometry_msgs::Pose& pose, const std::vector<double>& joint_values,
119  bool overwrite)
120 {
121  unsigned int grid_index;
122  if (!getGridIndex(pose, grid_index))
123  {
124  ROS_DEBUG("Failed to get grid index");
125  return false;
126  }
127  unsigned int num_solutions = num_solutions_vector_[grid_index];
128  if (!overwrite && num_solutions >= max_solutions_per_grid_location_)
129  {
130  ROS_DEBUG("Pose already has max number of solutions");
131  return true;
132  }
133  if (num_solutions == 0)
134  kinematics_cache_points_with_solution_++;
135  if (overwrite && num_solutions >= max_solutions_per_grid_location_)
136  num_solutions = 0;
137  unsigned int start_index = getSolutionLocation(grid_index, num_solutions);
138  for (unsigned int i = 0; i < joint_values.size(); ++i)
139  {
140  // ROS_INFO("Joint value[%d]: %f, location: %d",i,joint_values[i],start_index+i);
141  kinematics_cache_vector_[start_index + i] = joint_values[i];
142  }
143  if (num_solutions_vector_[grid_index] < max_solutions_per_grid_location_)
144  num_solutions_vector_[grid_index]++;
145  updateDistances(pose);
146  return true;
147 }
148 
149 bool KinematicsCache::getGridIndex(const geometry_msgs::Pose& pose, unsigned int& grid_index) const
150 {
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_);
154 
155  if (x_index >= static_cast<int>(cache_size_x_ || x_index < 0))
156  {
157  ROS_DEBUG("X position %f,%d lies outside grid: %d %d", pose.position.x, x_index, 0, cache_size_x_);
158  return false;
159  }
160  if (y_index >= static_cast<int>(cache_size_y_ || y_index < 0))
161  {
162  ROS_DEBUG("Y position %f,%d lies outside grid: %d %d", pose.position.y, y_index, 0, cache_size_y_);
163  return false;
164  }
165  if (z_index >= static_cast<int>(cache_size_z_ || z_index < 0))
166  {
167  ROS_DEBUG("Z position %f,%d lies outside grid: %d %d", pose.position.z, z_index, 0, cache_size_z_);
168  return false;
169  }
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_);
172  return true;
173 }
174 
175 bool KinematicsCache::getNumSolutions(const geometry_msgs::Pose& pose, unsigned int& num_solutions) const
176 {
177  unsigned int grid_index;
178  if (!getGridIndex(pose, grid_index))
179  return false;
180 
181  num_solutions = num_solutions_vector_[grid_index];
182  return true;
183 }
184 
185 unsigned int KinematicsCache::getSolutionLocation(unsigned int& grid_index, unsigned int& solution_index) const
186 {
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_);
190 }
191 
192 bool KinematicsCache::getSolution(const geometry_msgs::Pose& pose, unsigned int solution_index,
193  std::vector<double>& solution) const
194 {
195  unsigned int grid_index;
196  if (!getGridIndex(pose, grid_index))
197  return false;
198  if (solution_index >= max_solutions_per_grid_location_)
199  return false;
200  if (solution.size() < solution_dimension_)
201  return false;
202 
203  solution = getSolution(grid_index, solution_index);
204  return true;
205 }
206 
207 bool KinematicsCache::getSolutions(const geometry_msgs::Pose& pose, std::vector<std::vector<double> >& solution) const
208 {
209  unsigned int grid_index;
210  if (!getGridIndex(pose, grid_index))
211  return false;
212  if (solution.size() != num_solutions_vector_[grid_index])
213  return false;
214  for (unsigned int i = 0; i < solution.size(); ++i)
215  {
216  if (solution[i].size() != solution_dimension_)
217  return false;
218  solution[i] = getSolution(grid_index, i);
219  }
220  return true;
221 }
222 
223 std::vector<double> KinematicsCache::getSolution(unsigned int grid_index, unsigned int solution_index) const
224 {
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;
230 }
231 
232 bool KinematicsCache::readFromFile(const std::string& filename)
233 {
234  std::ifstream file(filename.c_str());
235  if (!file.is_open())
236  {
237  ROS_WARN("Could not open file: %s", filename.c_str());
238  return false;
239  }
240  std::string group_name;
241  std::getline(file, group_name);
242  if (group_name.empty())
243  {
244  ROS_ERROR("Could not find group_name in file: %s", group_name.c_str());
245  file.close();
246  return false;
247  }
248  if (group_name != kinematics_solver_->getGroupName())
249  {
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());
252  file.close();
253  return false;
254  }
255 
256  std::string line_string;
257  std::getline(file, line_string);
258  std::stringstream line_stream(line_string);
259  line_stream >> options_.origin.x >> options_.origin.y >> options_.origin.z;
260 
261  std::getline(file, line_string);
262  line_stream.clear();
263  line_stream.str("");
264  line_stream << line_string;
265  line_stream >> options_.workspace_size[0] >> options_.workspace_size[1] >> options_.workspace_size[2];
266 
267  std::getline(file, line_string);
268  line_stream.clear();
269  line_stream.str("");
270  line_stream << line_string;
271  line_stream >> options_.resolution[0] >> options_.resolution[1] >> options_.resolution[2];
272 
273  std::getline(file, line_string);
274  line_stream.clear();
275  line_stream.str("");
276  line_stream << line_string;
277  line_stream >> options_.max_solutions_per_grid_location;
278 
279  setup(options_);
280 
281  std::getline(file, line_string);
282  line_stream.clear();
283  line_stream.str("");
284  line_stream << line_string;
285  line_stream >> min_squared_distance_;
286 
287  std::getline(file, line_string);
288  line_stream.clear();
289  line_stream.str("");
290  line_stream << line_string;
291  line_stream >> max_squared_distance_;
292 
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);
297  line_stream.clear();
298  line_stream.str("");
299  line_stream << line_string;
300  double d;
301  while (line_stream >> d)
302  {
303  kinematics_cache_vector.push_back(d);
304  }
305 
306  std::getline(file, line_string);
307  std::getline(file, line_string);
308  line_stream.clear();
309  line_stream.str("");
310  line_stream << line_string;
311  unsigned int index;
312  while (line_stream >> index)
313  {
314  num_solutions_vector.push_back(index);
315  }
316 
317  file.close();
318 
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());
322  return true;
323 }
324 
325 bool KinematicsCache::writeToFile(const std::string& filename)
326 {
327  ROS_DEBUG("Writing %d total points to file: %s", static_cast<int> num_solutions_vector_.size(), filename.c_str());
328  std::ofstream file;
329  file.open(filename.c_str());
330  if (!file.is_open())
331  {
332  ROS_WARN("Could not open file: %s", filename.c_str());
333  return false;
334  }
335  if (file.good())
336  {
337  std::string group_name = kinematics_solver_->getGroupName();
338  file << group_name << '\n';
339 
340  file << options_.origin.x << " " << options_.origin.y << " " << options_.origin.z << '\n';
341  file << options_.workspace_size[0] << " " << options_.workspace_size[1] << " " << options_.workspace_size[2]
342  << '\n';
343  file << options_.resolution[0] << " " << options_.resolution[1] << " " << options_.resolution[2] << '\n';
344  file << options_.max_solutions_per_grid_location << '\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, " "));
350  file << '\n';
351 
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, " "));
355  file << '\n';
356  }
357 
358  file.close();
359  return true;
360 }
361 
362 std::pair<double, double> KinematicsCache::getMinMaxSquaredDistance()
363 {
364  return std::pair<double, double>(min_squared_distance_, max_squared_distance_);
365 }
366 
367 void KinematicsCache::updateDistances(const geometry_msgs::Pose& pose)
368 {
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_);
373 }
374 } // namespace kinematics_cache
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...
Definition: setup.py:1
d
Definition: setup.py:4