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 
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 moveit::core::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<moveit::core::RobotState>(kinematic_model);
57  joint_state_group_ = std::make_shared<moveit::core::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_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_,
82  cache_size_z_);
83  ROS_DEBUG_NAMED("kinematics_cache", "Cache resolution: %f %f %f", cache_resolution_x_, cache_resolution_y_,
84  cache_resolution_z_);
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_);
88 }
89 
90 bool KinematicsCache::generateCacheMap(double timeout)
91 {
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;
96 
97  fk_names.push_back(kinematics_solver_->getTipFrame());
98  fk_values.resize(kinematics_solver_->getJointNames().size(), 0.0);
99  poses.resize(1);
100 
101  while ((ros::WallTime::now() - start_time).toSec() <= timeout &&
102  kinematics_cache_points_with_solution_ <= kinematics_cache_size_)
103  {
104  joint_state_group_->setToRandomValues();
105  joint_state_group_->getVariableValues(fk_values);
106  if (!kinematics_solver_->getPositionFK(fk_names, fk_values, poses))
107  {
108  ROS_ERROR_NAMED("kinematics_cache", "Fk failed");
109  return false;
110  }
111  if (!addToCache(poses[0], fk_values))
112  {
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);
115  }
116  ROS_DEBUG_NAMED("kinematics_cache", "Adding: %d", kinematics_cache_points_with_solution_);
117  }
118  ROS_DEBUG_NAMED("kinematics_cache", "Cache map generated with %d valid points",
119  kinematics_cache_points_with_solution_);
120  return true;
121 }
122 
123 bool KinematicsCache::addToCache(const geometry_msgs::Pose& pose, const std::vector<double>& joint_values,
124  bool overwrite)
125 {
126  unsigned int grid_index;
127  if (!getGridIndex(pose, grid_index))
128  {
129  ROS_DEBUG_NAMED("kinematics_cache", "Failed to get grid index");
130  return false;
131  }
132  unsigned int num_solutions = num_solutions_vector_[grid_index];
133  if (!overwrite && num_solutions >= max_solutions_per_grid_location_)
134  {
135  ROS_DEBUG_NAMED("kinematics_cache", "Pose already has max number of solutions");
136  return true;
137  }
138  if (num_solutions == 0)
139  kinematics_cache_points_with_solution_++;
140  if (overwrite && num_solutions >= max_solutions_per_grid_location_)
141  num_solutions = 0;
142  unsigned int start_index = getSolutionLocation(grid_index, num_solutions);
143  for (unsigned int i = 0; i < joint_values.size(); ++i)
144  {
145  // ROS_INFO("Joint value[%d]: %f, location: %d",i,joint_values[i],start_index+i);
146  kinematics_cache_vector_[start_index + i] = joint_values[i];
147  }
148  if (num_solutions_vector_[grid_index] < max_solutions_per_grid_location_)
149  num_solutions_vector_[grid_index]++;
150  updateDistances(pose);
151  return true;
152 }
153 
154 bool KinematicsCache::getGridIndex(const geometry_msgs::Pose& pose, unsigned int& grid_index) const
155 {
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_);
159 
160  if (x_index >= static_cast<int>(cache_size_x_ || x_index < 0))
161  {
162  ROS_DEBUG_NAMED("kinematics_cache", "X position %f,%d lies outside grid: %d %d", pose.position.x, x_index, 0,
163  cache_size_x_);
164  return false;
165  }
166  if (y_index >= static_cast<int>(cache_size_y_) || y_index < 0)
167  {
168  ROS_DEBUG_NAMED("kinematics_cache", "Y position %f,%d lies outside grid: %d %d", pose.position.y, y_index, 0,
169  cache_size_y_);
170  return false;
171  }
172  if (z_index >= static_cast<int>(cache_size_z_) || z_index < 0)
173  {
174  ROS_DEBUG_NAMED("kinematics_cache", "Z position %f,%d lies outside grid: %d %d", pose.position.z, z_index, 0,
175  cache_size_z_);
176  return false;
177  }
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_);
180  return true;
181 }
182 
183 bool KinematicsCache::getNumSolutions(const geometry_msgs::Pose& pose, unsigned int& num_solutions) const
184 {
185  unsigned int grid_index;
186  if (!getGridIndex(pose, grid_index))
187  return false;
188 
189  num_solutions = num_solutions_vector_[grid_index];
190  return true;
191 }
192 
193 unsigned int KinematicsCache::getSolutionLocation(unsigned int& grid_index, unsigned int& solution_index) const
194 {
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_);
198 }
199 
200 bool KinematicsCache::getSolution(const geometry_msgs::Pose& pose, unsigned int solution_index,
201  std::vector<double>& solution) const
202 {
203  unsigned int grid_index;
204  if (!getGridIndex(pose, grid_index))
205  return false;
206  if (solution_index >= max_solutions_per_grid_location_)
207  return false;
208  if (solution.size() < solution_dimension_)
209  return false;
210 
211  solution = getSolution(grid_index, solution_index);
212  return true;
213 }
214 
215 bool KinematicsCache::getSolutions(const geometry_msgs::Pose& pose, std::vector<std::vector<double> >& solution) const
216 {
217  unsigned int grid_index;
218  if (!getGridIndex(pose, grid_index))
219  return false;
220  if (solution.size() != num_solutions_vector_[grid_index])
221  return false;
222  for (unsigned int i = 0; i < solution.size(); ++i)
223  {
224  if (solution[i].size() != solution_dimension_)
225  return false;
226  solution[i] = getSolution(grid_index, i);
227  }
228  return true;
229 }
230 
231 std::vector<double> KinematicsCache::getSolution(unsigned int grid_index, unsigned int solution_index) const
232 {
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;
238 }
239 
240 bool KinematicsCache::readFromFile(const std::string& filename)
241 {
242  std::ifstream file(filename.c_str());
243  if (!file.is_open())
244  {
245  ROS_DEBUG_NAMED("kinematics_cache", "Could not open file: %s", filename.c_str());
246  return false;
247  }
248  std::string group_name;
249  std::getline(file, group_name);
250  if (group_name.empty())
251  {
252  ROS_ERROR_NAMED("kinematics_cache", "Could not find group_name in file: %s", group_name.c_str());
253  file.close();
254  return false;
255  }
256  if (group_name != kinematics_solver_->getGroupName())
257  {
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());
260  file.close();
261  return false;
262  }
263 
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;
268 
269  std::getline(file, line_string);
270  line_stream.clear();
271  line_stream.str("");
272  line_stream << line_string;
273  line_stream >> options_.workspace_size[0] >> options_.workspace_size[1] >> options_.workspace_size[2];
274 
275  std::getline(file, line_string);
276  line_stream.clear();
277  line_stream.str("");
278  line_stream << line_string;
279  line_stream >> options_.resolution[0] >> options_.resolution[1] >> options_.resolution[2];
280 
281  std::getline(file, line_string);
282  line_stream.clear();
283  line_stream.str("");
284  line_stream << line_string;
285  line_stream >> options_.max_solutions_per_grid_location;
286 
287  setup(options_);
288 
289  std::getline(file, line_string);
290  line_stream.clear();
291  line_stream.str("");
292  line_stream << line_string;
293  line_stream >> min_squared_distance_;
294 
295  std::getline(file, line_string);
296  line_stream.clear();
297  line_stream.str("");
298  line_stream << line_string;
299  line_stream >> max_squared_distance_;
300 
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);
305  line_stream.clear();
306  line_stream.str("");
307  line_stream << line_string;
308  double d;
309  while (line_stream >> d)
310  {
311  kinematics_cache_vector.push_back(d);
312  }
313 
314  std::getline(file, line_string);
315  std::getline(file, line_string);
316  line_stream.clear();
317  line_stream.str("");
318  line_stream << line_string;
319  unsigned int index;
320  while (line_stream >> index)
321  {
322  num_solutions_vector.push_back(index);
323  }
324 
325  file.close();
326 
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());
331  return true;
332 }
333 
334 bool KinematicsCache::writeToFile(const std::string& filename)
335 {
336  ROS_DEBUG_NAMED("kinematics_cache", "Writing %d total points to file: %s",
337  static_cast<int>(num_solutions_vector_.size()), filename.c_str());
338  std::ofstream file;
339  file.open(filename.c_str());
340  if (!file.is_open())
341  {
342  ROS_DEBUG_NAMED("kinematics_cache", "Could not open file: %s", filename.c_str());
343  return false;
344  }
345  if (file.good())
346  {
347  std::string group_name = kinematics_solver_->getGroupName();
348  file << group_name << '\n';
349 
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]
352  << '\n';
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, " "));
360  file << '\n';
361 
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, " "));
365  file << '\n';
366  }
367 
368  file.close();
369  return true;
370 }
371 
372 std::pair<double, double> KinematicsCache::getMinMaxSquaredDistance()
373 {
374  return std::pair<double, double>(min_squared_distance_, max_squared_distance_);
375 }
376 
377 void KinematicsCache::updateDistances(const geometry_msgs::Pose& pose)
378 {
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_);
383 }
384 } // namespace kinematics_cache
Definition: setup.py:1
d
Definition: setup.py:4