moveit2
The MoveIt Motion Planning Framework for ROS 2.
constraints_library.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
37 #include <boost/date_time/posix_time/posix_time.hpp>
38 #include <filesystem>
39 #include <fstream>
42 
43 #include <ompl/tools/config/SelfConfig.h>
44 #include <utility>
45 
46 namespace ompl_interface
47 {
48 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ompl_planning.constraints_library");
49 
50 namespace
51 {
52 template <typename T>
53 void msgToHex(const T& msg, std::string& hex)
54 {
55  static const char SYMBOL[] = { '0', '1', '2', '3', '4', '5', '6', '7', '8', '9', 'A', 'B', 'C', 'D', 'E', 'F' };
56  auto type_support = rosidl_typesupport_cpp::get_message_type_support_handle<T>();
57  rmw_serialized_message_t serialized_msg = { nullptr, 0, 0, rcutils_get_default_allocator() };
58  rmw_ret_t result = rmw_serialize(&msg, type_support, &serialized_msg);
59  if (result != RMW_RET_OK)
60  {
61  // TODO(henningkayser): handle error
62  RCLCPP_ERROR(LOGGER, "Failed to serialize message!");
63  return;
64  }
65  const size_t serial_size_arg = serialized_msg.buffer_length;
66 
67  hex.resize(serial_size_arg * 2);
68  for (std::size_t i = 0; i < serial_size_arg; ++i)
69  {
70  hex[i * 2] = SYMBOL[serialized_msg.buffer[i] / 16];
71  hex[i * 2 + 1] = SYMBOL[serialized_msg.buffer[i] % 16];
72  }
73 }
74 
75 template <typename T>
76 void hexToMsg(const std::string& hex, T& msg)
77 {
78  const size_t serial_size_arg = hex.length() / 2;
79  rmw_serialized_message_t serialized_msg = rcutils_get_zero_initialized_uint8_array();
80  rcutils_ret_t rcutils_result = rcutils_uint8_array_resize(&serialized_msg, serial_size_arg);
81  if (rcutils_result != RCUTILS_RET_OK)
82  {
83  // TODO(henningkayser): handle error
84  RCLCPP_ERROR(LOGGER, "Failed to allocate message buffer!");
85  return;
86  }
87 
88  for (std::size_t i = 0; i < serial_size_arg; ++i)
89  {
90  serialized_msg.buffer[i] = (hex[i * 2] <= '9' ? (hex[i * 2] - '0') : (hex[i * 2] - 'A' + 10)) * 16 +
91  (hex[i * 2 + 1] <= '9' ? (hex[i * 2 + 1] - '0') : (hex[i * 2 + 1] - 'A' + 10));
92  }
93  auto type_support = rosidl_typesupport_cpp::get_message_type_support_handle<T>();
94  rmw_ret_t result = rmw_deserialize(&serialized_msg, type_support, &msg);
95  if (result != RMW_RET_OK)
96  {
97  // TODO(henningkayser): handle error
98  RCLCPP_ERROR(LOGGER, "Failed to deserialize message!");
99  return;
100  }
101 }
102 } // namespace
103 
104 class ConstraintApproximationStateSampler : public ob::StateSampler
105 {
106 public:
107  ConstraintApproximationStateSampler(const ob::StateSpace* space,
108  const ConstraintApproximationStateStorage* state_storage, std::size_t milestones)
109  : ob::StateSampler(space), state_storage_(state_storage)
110  {
111  max_index_ = milestones - 1;
112  inv_dim_ = space->getDimension() > 0 ? 1.0 / static_cast<double>(space->getDimension()) : 1.0;
113  }
114 
115  void sampleUniform(ob::State* state) override
116  {
117  space_->copyState(state, state_storage_->getState(rng_.uniformInt(0, max_index_)));
118  }
119 
120  void sampleUniformNear(ob::State* state, const ob::State* near, const double distance) override
121  {
122  int index = -1;
123  int tag = near->as<ModelBasedStateSpace::StateType>()->tag;
124 
125  if (tag >= 0)
126  {
127  const ConstrainedStateMetadata& md = state_storage_->getMetadata(tag);
128  if (!md.first.empty())
129  {
130  std::size_t matt = md.first.size() / 3;
131  std::size_t att = 0;
132  do
133  {
134  index = md.first[rng_.uniformInt(0, md.first.size() - 1)];
135  } while (dirty_.find(index) != dirty_.end() && ++att < matt);
136  if (att >= matt)
137  {
138  index = -1;
139  }
140  else
141  {
142  dirty_.insert(index);
143  }
144  }
145  }
146  if (index < 0)
147  index = rng_.uniformInt(0, max_index_);
148 
149  double dist = space_->distance(near, state_storage_->getState(index));
150 
151  if (dist > distance)
152  {
153  double d = pow(rng_.uniform01(), inv_dim_) * distance;
154  space_->interpolate(near, state_storage_->getState(index), d / dist, state);
155  }
156  else
157  space_->copyState(state, state_storage_->getState(index));
158  }
159 
160  void sampleGaussian(ob::State* state, const ob::State* mean, const double stdDev) override
161  {
162  sampleUniformNear(state, mean, rng_.gaussian(0.0, stdDev));
163  }
164 
165 protected:
168  std::set<std::size_t> dirty_;
169  unsigned int max_index_;
170  double inv_dim_;
171 };
172 
173 bool interpolateUsingStoredStates(const ConstraintApproximationStateStorage* state_storage, const ob::State* from,
174  const ob::State* to, const double t, ob::State* state)
175 {
176  int tag_from = from->as<ModelBasedStateSpace::StateType>()->tag;
177  int tag_to = to->as<ModelBasedStateSpace::StateType>()->tag;
178 
179  if (tag_from < 0 || tag_to < 0)
180  return false;
181 
182  if (tag_from == tag_to)
183  {
184  state_storage->getStateSpace()->copyState(state, to);
185  }
186  else
187  {
188  const ConstrainedStateMetadata& md = state_storage->getMetadata(tag_from);
189 
190  auto it = md.second.find(tag_to);
191  if (it == md.second.end())
192  return false;
193  const std::pair<std::size_t, std::size_t>& istates = it->second;
194  std::size_t index = static_cast<std::size_t>((istates.second - istates.first + 2) * t + 0.5);
195 
196  if (index == 0)
197  {
198  state_storage->getStateSpace()->copyState(state, from);
199  }
200  else
201  {
202  --index;
203  if (index >= istates.second - istates.first)
204  {
205  state_storage->getStateSpace()->copyState(state, to);
206  }
207  else
208  {
209  state_storage->getStateSpace()->copyState(state, state_storage->getState(istates.first + index));
210  }
211  }
212  }
213  return true;
214 }
215 
217 {
218  if (explicit_motions_ && milestones_ > 0 && milestones_ < state_storage_->size())
219  {
220  return
221  [this](const ompl::base::State* from, const ompl::base::State* to, const double t, ompl::base::State* state) {
222  return interpolateUsingStoredStates(state_storage_, from, to, t, state);
223  };
224  }
225  return InterpolationFunction();
226 }
227 
228 ompl::base::StateSamplerPtr
229 allocConstraintApproximationStateSampler(const ob::StateSpace* space, const std::vector<int>& expected_signature,
230  const ConstraintApproximationStateStorage* state_storage,
231  std::size_t milestones)
232 {
233  std::vector<int> sig;
234  space->computeSignature(sig);
235  if (sig != expected_signature)
236  {
237  return ompl::base::StateSamplerPtr();
238  }
239  else
240  {
241  return std::make_shared<ConstraintApproximationStateSampler>(space, state_storage, milestones);
242  }
243 }
244 } // namespace ompl_interface
245 
247  std::string group, std::string state_space_parameterization, bool explicit_motions,
248  moveit_msgs::msg::Constraints msg, std::string filename, ompl::base::StateStoragePtr storage,
249  std::size_t milestones)
250  : group_(std::move(group))
251  , state_space_parameterization_(std::move(state_space_parameterization))
252  , explicit_motions_(explicit_motions)
253  , constraint_msg_(std::move(msg))
254  , ompldb_filename_(std::move(filename))
255  , state_storage_ptr_(std::move(storage))
256  , milestones_(milestones)
257 {
259  state_storage_->getStateSpace()->computeSignature(space_signature_);
260  if (milestones_ == 0)
261  milestones_ = state_storage_->size();
262 }
263 
264 ompl::base::StateSamplerAllocator
265 ompl_interface::ConstraintApproximation::getStateSamplerAllocator(const moveit_msgs::msg::Constraints& /*unused*/) const
266 {
267  if (state_storage_->size() == 0)
268  return ompl::base::StateSamplerAllocator();
269  return [this](const ompl::base::StateSpace* ss) {
270  return allocConstraintApproximationStateSampler(ss, space_signature_, state_storage_, milestones_);
271  };
272 }
273 /*
274 void ompl_interface::ConstraintApproximation::visualizeDistribution(const
275 std::string &link_name, unsigned int count,
276 visualization_msgs::MarkerArray &arr) const
277 {
278  moveit::core::RobotState robot_state(robot_model_);
279  robot_state.setToDefaultValues();
280 
281  ompl::RNG rng;
282  std_msgs::ColorRGBA color;
283  color.r = 0.0f;
284  color.g = 1.0f;
285  color.b = 1.0f;
286  color.a = 1.0f;
287  if (state_storage_->size() < count)
288  count = state_storage_->size();
289 
290  for (std::size_t i = 0 ; i < count ; ++i)
291  {
292  state_storage_->getStateSpace()->as<ModelBasedStateSpace>()->copyToRobotState(robot_state,
293 state_storage_->getState(rng.uniformInt(0, state_storage_->size() - 1)));
294  const Eigen::Vector3d &pos =
295 robot_state.getLinkState(link_name)->getGlobalLinkTransform().translation();
296 
297  visualization_msgs::Marker mk;
298  mk.header.stamp = ros::Time::now();
299  mk.header.frame_id = robot_model_->getModelFrame();
300  mk.ns = "stored_constraint_data";
301  mk.id = i;
302  mk.type = visualization_msgs::Marker::SPHERE;
303  mk.action = visualization_msgs::Marker::ADD;
304  mk.pose.position.x = pos.x();
305  mk.pose.position.y = pos.y();
306  mk.pose.position.z = pos.z();
307  mk.pose.orientation.w = 1.0;
308  mk.scale.x = mk.scale.y = mk.scale.z = 0.035;
309  mk.color = color;
310  mk.lifetime = ros::Duration(30.0);
311  arr.markers.push_back(mk);
312  }
313  }
314 */
315 
317 {
318  constraint_approximations_.clear();
319  std::ifstream fin((path + "/manifest").c_str());
320  if (!fin.good())
321  {
322  RCLCPP_WARN(LOGGER,
323  "Manifest not found in folder '%s'. Not loading "
324  "constraint approximations.",
325  path.c_str());
326  return;
327  }
328 
329  RCLCPP_INFO(LOGGER, "Loading constrained space approximations from '%s'...", path.c_str());
330 
331  while (fin.good() && !fin.eof())
332  {
333  std::string group, state_space_parameterization, serialization, filename;
334  bool explicit_motions;
335  unsigned int milestones;
336  fin >> group;
337  if (fin.eof())
338  break;
339  fin >> state_space_parameterization;
340  if (fin.eof())
341  break;
342  fin >> explicit_motions;
343  if (fin.eof())
344  break;
345  fin >> milestones;
346  if (fin.eof())
347  break;
348  fin >> serialization;
349  if (fin.eof())
350  break;
351  fin >> filename;
352 
353  if (context_->getGroupName() != group &&
354  context_->getOMPLStateSpace()->getParameterizationType() != state_space_parameterization)
355  {
356  RCLCPP_INFO(LOGGER, "Ignoring constraint approximation of type '%s' for group '%s' from '%s'...",
357  state_space_parameterization.c_str(), group.c_str(), filename.c_str());
358  continue;
359  }
360 
361  RCLCPP_INFO(LOGGER, "Loading constraint approximation of type '%s' for group '%s' from '%s'...",
362  state_space_parameterization.c_str(), group.c_str(), filename.c_str());
363  moveit_msgs::msg::Constraints msg;
364  hexToMsg(serialization, msg);
365  auto* cass = new ConstraintApproximationStateStorage(context_->getOMPLSimpleSetup()->getStateSpace());
366  cass->load((std::string{ path }.append("/").append(filename)).c_str());
367  auto cap = std::make_shared<ConstraintApproximation>(group, state_space_parameterization, explicit_motions, msg,
368  filename, ompl::base::StateStoragePtr(cass), milestones);
369  if (constraint_approximations_.find(cap->getName()) != constraint_approximations_.end())
370  RCLCPP_WARN(LOGGER, "Overwriting constraint approximation named '%s'", cap->getName().c_str());
371  constraint_approximations_[cap->getName()] = cap;
372  std::size_t sum = 0;
373  for (std::size_t i = 0; i < cass->size(); ++i)
374  sum += cass->getMetadata(i).first.size();
375  RCLCPP_INFO(LOGGER,
376  "Loaded %lu states (%lu milestones) and %lu connections (%0.1lf per state) "
377  "for constraint named '%s'%s",
378  cass->size(), cap->getMilestoneCount(), sum,
379  static_cast<double>(sum) / static_cast<double>(cap->getMilestoneCount()), msg.name.c_str(),
380  explicit_motions ? ". Explicit motions included." : "");
381  }
382  RCLCPP_INFO(LOGGER, "Done loading constrained space approximations.");
383 }
384 
386 {
387  RCLCPP_INFO(LOGGER, "Saving %u constrained space approximations to '%s'",
388  static_cast<unsigned int>(constraint_approximations_.size()), path.c_str());
389  try
390  {
391  std::filesystem::create_directory(path);
392  }
393  catch (...)
394  {
395  }
396 
397  std::ofstream fout((path + "/manifest").c_str());
398  if (fout.good())
399  {
400  for (std::map<std::string, ConstraintApproximationPtr>::const_iterator it = constraint_approximations_.begin();
401  it != constraint_approximations_.end(); ++it)
402  {
403  fout << it->second->getGroup() << '\n';
404  fout << it->second->getStateSpaceParameterization() << '\n';
405  fout << it->second->hasExplicitMotions() << '\n';
406  fout << it->second->getMilestoneCount() << '\n';
407  std::string serialization;
408  msgToHex(it->second->getConstraintsMsg(), serialization);
409  fout << serialization << '\n';
410  fout << it->second->getFilename() << '\n';
411  if (it->second->getStateStorage())
412  it->second->getStateStorage()->store((path + "/" + it->second->getFilename()).c_str());
413  }
414  }
415  else
416  {
417  RCLCPP_ERROR(LOGGER, "Unable to save constraint approximation to '%s'", path.c_str());
418  }
419  fout.close();
420 }
421 
423 {
424  constraint_approximations_.clear();
425 }
426 
428 {
429  for (const std::pair<const std::string, ConstraintApproximationPtr>& constraint_approximation :
430  constraint_approximations_)
431  {
432  out << constraint_approximation.second->getGroup() << '\n';
433  out << constraint_approximation.second->getStateSpaceParameterization() << '\n';
434  out << constraint_approximation.second->hasExplicitMotions() << '\n';
435  out << constraint_approximation.second->getMilestoneCount() << '\n';
436  out << constraint_approximation.second->getFilename() << '\n';
437  // TODO(henningkayser): format print constraint message
438  // out << constraint_approximation.second->getConstraintsMsg() << '\n';
439  }
440 }
441 
442 const ompl_interface::ConstraintApproximationPtr&
443 ompl_interface::ConstraintsLibrary::getConstraintApproximation(const moveit_msgs::msg::Constraints& msg) const
444 {
445  auto it = constraint_approximations_.find(msg.name);
446  if (it != constraint_approximations_.end())
447  return it->second;
448 
449  static ConstraintApproximationPtr empty;
450  return empty;
451 }
452 
454 ompl_interface::ConstraintsLibrary::addConstraintApproximation(const moveit_msgs::msg::Constraints& constr,
455  const std::string& group,
456  const planning_scene::PlanningSceneConstPtr& scene,
458 {
459  return addConstraintApproximation(constr, constr, group, scene, options);
460 }
461 
463 ompl_interface::ConstraintsLibrary::addConstraintApproximation(const moveit_msgs::msg::Constraints& constr_sampling,
464  const moveit_msgs::msg::Constraints& constr_hard,
465  const std::string& group,
466  const planning_scene::PlanningSceneConstPtr& scene,
468 {
470  if (context_->getGroupName() != group &&
471  context_->getOMPLStateSpace()->getParameterizationType() != options.state_space_parameterization)
472  {
473  RCLCPP_INFO(LOGGER, "Ignoring constraint approximation of type '%s' for group '%s'...",
474  options.state_space_parameterization.c_str(), group.c_str());
475  return res;
476  }
477 
478  context_->clear();
479  context_->setPlanningScene(scene);
480  context_->setCompleteInitialState(scene->getCurrentState());
481 
482  rclcpp::Clock clock;
483  auto start = clock.now();
484  ompl::base::StateStoragePtr state_storage =
485  constructConstraintApproximation(context_, constr_sampling, constr_hard, options, res);
486  RCLCPP_INFO(LOGGER, "Spent %lf seconds constructing the database", (clock.now() - start).seconds());
487  if (state_storage)
488  {
489  auto constraint_approx = std::make_shared<ConstraintApproximation>(
490  group, options.state_space_parameterization, options.explicit_motions, constr_hard,
491  group + "_" + boost::posix_time::to_iso_extended_string(boost::posix_time::microsec_clock::universal_time()) +
492  ".ompldb",
493  state_storage, res.milestones);
494  if (constraint_approximations_.find(constraint_approx->getName()) != constraint_approximations_.end())
495  RCLCPP_WARN(LOGGER, "Overwriting constraint approximation named '%s'", constraint_approx->getName().c_str());
496  constraint_approximations_[constraint_approx->getName()] = constraint_approx;
497  res.approx = constraint_approx;
498  }
499  else
500  RCLCPP_ERROR(LOGGER, "Unable to construct constraint approximation for group '%s'", group.c_str());
501  return res;
502 }
503 
504 ompl::base::StateStoragePtr ompl_interface::ConstraintsLibrary::constructConstraintApproximation(
505  ModelBasedPlanningContext* pcontext, const moveit_msgs::msg::Constraints& constr_sampling,
506  const moveit_msgs::msg::Constraints& constr_hard, const ConstraintApproximationConstructionOptions& options,
508 {
509  // state storage structure
511  ob::StateStoragePtr state_storage(cass);
512 
513  // construct a sampler for the sampling constraints
515  moveit::core::Transforms no_transforms(pcontext->getRobotModel()->getModelFrame());
516  kset.add(constr_hard, no_transforms);
517 
518  const moveit::core::RobotState& default_state = pcontext->getCompleteInitialRobotState();
519 
520  unsigned int attempts = 0;
521 
522  double bounds_val = std::numeric_limits<double>::max() / 2.0 - 1.0;
523  pcontext->getOMPLStateSpace()->setPlanningVolume(-bounds_val, bounds_val, -bounds_val, bounds_val, -bounds_val,
524  bounds_val);
525  pcontext->getOMPLStateSpace()->setup();
526 
527  // construct the constrained states
528 
529  moveit::core::RobotState robot_state(default_state);
530  const constraint_samplers::ConstraintSamplerManagerPtr& csmng = pcontext->getConstraintSamplerManager();
531  ConstrainedSampler* constrained_sampler = nullptr;
532  if (csmng)
533  {
534  constraint_samplers::ConstraintSamplerPtr constraint_sampler =
535  csmng->selectSampler(pcontext->getPlanningScene(), pcontext->getJointModelGroup()->getName(), constr_sampling);
536  if (constraint_sampler)
537  constrained_sampler = new ConstrainedSampler(pcontext, constraint_sampler);
538  }
539 
540  ob::StateSamplerPtr ss(constrained_sampler ? ob::StateSamplerPtr(constrained_sampler) :
541  pcontext->getOMPLStateSpace()->allocDefaultStateSampler());
542 
543  ompl::base::ScopedState<> temp(pcontext->getOMPLStateSpace());
544  int done = -1;
545  bool slow_warn = false;
546  ompl::time::point start = ompl::time::now();
547  while (state_storage->size() < options.samples)
548  {
549  ++attempts;
550  int done_now = 100 * state_storage->size() / options.samples;
551  if (done != done_now)
552  {
553  done = done_now;
554  RCLCPP_INFO(LOGGER, "%d%% complete (kept %0.1lf%% sampled states)", done,
555  100.0 * static_cast<double>(state_storage->size()) / static_cast<double>(attempts));
556  }
557 
558  if (!slow_warn && attempts > 10 && attempts > state_storage->size() * 100)
559  {
560  slow_warn = true;
561  RCLCPP_WARN(LOGGER, "Computation of valid state database is very slow...");
562  }
563 
564  if (attempts > options.samples && state_storage->size() == 0)
565  {
566  RCLCPP_ERROR(LOGGER, "Unable to generate any samples");
567  break;
568  }
569 
570  ss->sampleUniform(temp.get());
571  pcontext->getOMPLStateSpace()->copyToRobotState(robot_state, temp.get());
572  if (kset.decide(robot_state).satisfied)
573  {
574  if (state_storage->size() < options.samples)
575  {
576  temp->as<ModelBasedStateSpace::StateType>()->tag = state_storage->size();
577  state_storage->addState(temp.get());
578  }
579  }
580  }
581 
582  result.state_sampling_time = ompl::time::seconds(ompl::time::now() - start);
583  RCLCPP_INFO(LOGGER, "Generated %u states in %lf seconds", static_cast<unsigned int>(state_storage->size()),
584  result.state_sampling_time);
585  if (constrained_sampler)
586  {
587  result.sampling_success_rate = constrained_sampler->getConstrainedSamplingRate();
588  RCLCPP_INFO(LOGGER, "Constrained sampling rate: %lf", result.sampling_success_rate);
589  }
590 
591  result.milestones = state_storage->size();
592  if (options.edges_per_sample > 0)
593  {
594  RCLCPP_INFO(LOGGER, "Computing graph connections (max %u edges per sample) ...", options.edges_per_sample);
595 
596  // construct connections
597  const ob::StateSpacePtr& space = pcontext->getOMPLSimpleSetup()->getStateSpace();
598  unsigned int milestones = state_storage->size();
599  std::vector<ob::State*> int_states(options.max_explicit_points, nullptr);
600  pcontext->getOMPLSimpleSetup()->getSpaceInformation()->allocStates(int_states);
601 
602  ompl::time::point start = ompl::time::now();
603  int good = 0;
604  int done = -1;
605 
606  for (std::size_t j = 0; j < milestones; ++j)
607  {
608  int done_now = 100 * j / milestones;
609  if (done != done_now)
610  {
611  done = done_now;
612  RCLCPP_INFO(LOGGER, "%d%% complete", done);
613  }
614  if (cass->getMetadata(j).first.size() >= options.edges_per_sample)
615  continue;
616 
617  const ob::State* sj = state_storage->getState(j);
618 
619  for (std::size_t i = j + 1; i < milestones; ++i)
620  {
621  if (cass->getMetadata(i).first.size() >= options.edges_per_sample)
622  continue;
623  double d = space->distance(state_storage->getState(i), sj);
624  if (d >= options.max_edge_length)
625  continue;
626  unsigned int isteps =
627  std::min<unsigned int>(options.max_explicit_points, d / options.explicit_points_resolution);
628  double step = 1.0 / static_cast<double>(isteps);
629  bool ok = true;
630  space->interpolate(state_storage->getState(i), sj, step, int_states[0]);
631  for (unsigned int k = 1; k < isteps; ++k)
632  {
633  double this_step = step / (1.0 - (k - 1) * step);
634  space->interpolate(int_states[k - 1], sj, this_step, int_states[k]);
635  pcontext->getOMPLStateSpace()->copyToRobotState(robot_state, int_states[k]);
636  if (!kset.decide(robot_state).satisfied)
637  {
638  ok = false;
639  break;
640  }
641  }
642 
643  if (ok)
644  {
645  cass->getMetadata(i).first.push_back(j);
646  cass->getMetadata(j).first.push_back(i);
647 
648  if (options.explicit_motions)
649  {
650  cass->getMetadata(i).second[j].first = state_storage->size();
651  for (unsigned int k = 0; k < isteps; ++k)
652  {
653  int_states[k]->as<ModelBasedStateSpace::StateType>()->tag = -1;
654  state_storage->addState(int_states[k]);
655  }
656  cass->getMetadata(i).second[j].second = state_storage->size();
657  cass->getMetadata(j).second[i] = cass->getMetadata(i).second[j];
658  }
659 
660  good++;
661  if (cass->getMetadata(j).first.size() >= options.edges_per_sample)
662  break;
663  }
664  }
665  }
666 
667  result.state_connection_time = ompl::time::seconds(ompl::time::now() - start);
668  RCLCPP_INFO(LOGGER, "Computed possible connexions in %lf seconds. Added %d connexions",
669  result.state_connection_time, good);
670  pcontext->getOMPLSimpleSetup()->getSpaceInformation()->freeStates(int_states);
671 
672  return state_storage;
673  }
674 
675  // TODO(davetcoleman): this function did not originally return a value,
676  // causing compiler warnings in ROS Melodic
677  // Update with more intelligent logic as needed
678  RCLCPP_ERROR(LOGGER, "No StateStoragePtr found - implement better solution here.");
679  return state_storage;
680 }
A class that contains many different constraints, and can check RobotState *versus the full set....
const std::string & getName() const
Get the name of the joint group.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
Provides an implementation of a snapshot of a transform tree that can be easily queried for transform...
Definition: transforms.h:59
void sampleGaussian(ob::State *state, const ob::State *mean, const double stdDev) override
void sampleUniformNear(ob::State *state, const ob::State *near, const double distance) override
ConstraintApproximationStateSampler(const ob::StateSpace *space, const ConstraintApproximationStateStorage *state_storage, std::size_t milestones)
const ConstraintApproximationStateStorage * state_storage_
The states to sample from.
const ConstraintApproximationPtr & getConstraintApproximation(const moveit_msgs::msg::Constraints &msg) const
ConstraintApproximationConstructionResults addConstraintApproximation(const moveit_msgs::msg::Constraints &constr_sampling, const moveit_msgs::msg::Constraints &constr_hard, const std::string &group, const planning_scene::PlanningSceneConstPtr &scene, const ConstraintApproximationConstructionOptions &options)
void printConstraintApproximations(std::ostream &out=std::cout) const
void saveConstraintApproximations(const std::string &path)
void loadConstraintApproximations(const std::string &path)
const moveit::core::RobotModelConstPtr & getRobotModel() const
const moveit::core::RobotState & getCompleteInitialRobotState() const
const moveit::core::JointModelGroup * getJointModelGroup() const
const constraint_samplers::ConstraintSamplerManagerPtr & getConstraintSamplerManager()
const ModelBasedStateSpacePtr & getOMPLStateSpace() const
const og::SimpleSetupPtr & getOMPLSimpleSetup() const
const planning_scene::PlanningSceneConstPtr & getPlanningScene() const
Get the planning scene associated to this planning context.
The MoveIt interface to OMPL.
bool interpolateUsingStoredStates(const ConstraintApproximationStateStorage *state_storage, const ob::State *from, const ob::State *to, const double t, ob::State *state)
std::pair< std::vector< std::size_t >, std::map< std::size_t, std::pair< std::size_t, std::size_t > > > ConstrainedStateMetadata
ompl::base::StateSamplerPtr allocConstraintApproximationStateSampler(const ob::StateSpace *space, const std::vector< int > &expected_signature, const ConstraintApproximationStateStorage *state_storage, std::size_t milestones)
std::function< bool(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state)> InterpolationFunction
ompl::base::StateStorageWithMetadata< std::vector< std::size_t > > ConstraintApproximationStateStorage
double distance(const urdf::Pose &transform)
Definition: pr2_arm_ik.h:55
std::string append(const std::string &left, const std::string &right)
d
Definition: setup.py:4
CostFn sum(const std::vector< CostFn > &cost_functions)
ConstraintApproximationStateStorage * state_storage_
ConstraintApproximation(const planning_models::RobotModelConstPtr &kinematic_model, const std::string &group, const std::string &factory, const std::string &serialization, const std::string &filename, const ompl::base::StateStoragePtr &storage)
ompl::base::StateSamplerAllocator getStateSamplerAllocator(const moveit_msgs::msg::Constraints &msg) const
InterpolationFunction getInterpolationFunction() const