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 / (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  index = -1;
138  else
139  dirty_.insert(index);
140  }
141  }
142  if (index < 0)
143  index = rng_.uniformInt(0, max_index_);
144 
145  double dist = space_->distance(near, state_storage_->getState(index));
146 
147  if (dist > distance)
148  {
149  double d = pow(rng_.uniform01(), inv_dim_) * distance;
150  space_->interpolate(near, state_storage_->getState(index), d / dist, state);
151  }
152  else
153  space_->copyState(state, state_storage_->getState(index));
154  }
155 
156  void sampleGaussian(ob::State* state, const ob::State* mean, const double stdDev) override
157  {
158  sampleUniformNear(state, mean, rng_.gaussian(0.0, stdDev));
159  }
160 
161 protected:
164  std::set<std::size_t> dirty_;
165  unsigned int max_index_;
166  double inv_dim_;
167 };
168 
169 bool interpolateUsingStoredStates(const ConstraintApproximationStateStorage* state_storage, const ob::State* from,
170  const ob::State* to, const double t, ob::State* state)
171 {
172  int tag_from = from->as<ModelBasedStateSpace::StateType>()->tag;
173  int tag_to = to->as<ModelBasedStateSpace::StateType>()->tag;
174 
175  if (tag_from < 0 || tag_to < 0)
176  return false;
177 
178  if (tag_from == tag_to)
179  state_storage->getStateSpace()->copyState(state, to);
180  else
181  {
182  const ConstrainedStateMetadata& md = state_storage->getMetadata(tag_from);
183 
184  auto it = md.second.find(tag_to);
185  if (it == md.second.end())
186  return false;
187  const std::pair<std::size_t, std::size_t>& istates = it->second;
188  std::size_t index = (std::size_t)((istates.second - istates.first + 2) * t + 0.5);
189 
190  if (index == 0)
191  state_storage->getStateSpace()->copyState(state, from);
192  else
193  {
194  --index;
195  if (index >= istates.second - istates.first)
196  state_storage->getStateSpace()->copyState(state, to);
197  else
198  state_storage->getStateSpace()->copyState(state, state_storage->getState(istates.first + index));
199  }
200  }
201  return true;
202 }
203 
205 {
206  if (explicit_motions_ && milestones_ > 0 && milestones_ < state_storage_->size())
207  return
208  [this](const ompl::base::State* from, const ompl::base::State* to, const double t, ompl::base::State* state) {
209  return interpolateUsingStoredStates(state_storage_, from, to, t, state);
210  };
211  return InterpolationFunction();
212 }
213 
214 ompl::base::StateSamplerPtr
215 allocConstraintApproximationStateSampler(const ob::StateSpace* space, const std::vector<int>& expected_signature,
216  const ConstraintApproximationStateStorage* state_storage,
217  std::size_t milestones)
218 {
219  std::vector<int> sig;
220  space->computeSignature(sig);
221  if (sig != expected_signature)
222  return ompl::base::StateSamplerPtr();
223  else
224  return std::make_shared<ConstraintApproximationStateSampler>(space, state_storage, milestones);
225 }
226 } // namespace ompl_interface
227 
229  std::string group, std::string state_space_parameterization, bool explicit_motions,
230  moveit_msgs::msg::Constraints msg, std::string filename, ompl::base::StateStoragePtr storage,
231  std::size_t milestones)
232  : group_(std::move(group))
233  , state_space_parameterization_(std::move(state_space_parameterization))
234  , explicit_motions_(explicit_motions)
235  , constraint_msg_(std::move(msg))
236  , ompldb_filename_(std::move(filename))
237  , state_storage_ptr_(std::move(storage))
238  , milestones_(milestones)
239 {
241  state_storage_->getStateSpace()->computeSignature(space_signature_);
242  if (milestones_ == 0)
243  milestones_ = state_storage_->size();
244 }
245 
246 ompl::base::StateSamplerAllocator
247 ompl_interface::ConstraintApproximation::getStateSamplerAllocator(const moveit_msgs::msg::Constraints& /*unused*/) const
248 {
249  if (state_storage_->size() == 0)
250  return ompl::base::StateSamplerAllocator();
251  return [this](const ompl::base::StateSpace* ss) {
252  return allocConstraintApproximationStateSampler(ss, space_signature_, state_storage_, milestones_);
253  };
254 }
255 /*
256 void ompl_interface::ConstraintApproximation::visualizeDistribution(const
257 std::string &link_name, unsigned int count,
258 visualization_msgs::MarkerArray &arr) const
259 {
260  moveit::core::RobotState robot_state(robot_model_);
261  robot_state.setToDefaultValues();
262 
263  ompl::RNG rng;
264  std_msgs::ColorRGBA color;
265  color.r = 0.0f;
266  color.g = 1.0f;
267  color.b = 1.0f;
268  color.a = 1.0f;
269  if (state_storage_->size() < count)
270  count = state_storage_->size();
271 
272  for (std::size_t i = 0 ; i < count ; ++i)
273  {
274  state_storage_->getStateSpace()->as<ModelBasedStateSpace>()->copyToRobotState(robot_state,
275 state_storage_->getState(rng.uniformInt(0, state_storage_->size() - 1)));
276  const Eigen::Vector3d &pos =
277 robot_state.getLinkState(link_name)->getGlobalLinkTransform().translation();
278 
279  visualization_msgs::Marker mk;
280  mk.header.stamp = ros::Time::now();
281  mk.header.frame_id = robot_model_->getModelFrame();
282  mk.ns = "stored_constraint_data";
283  mk.id = i;
284  mk.type = visualization_msgs::Marker::SPHERE;
285  mk.action = visualization_msgs::Marker::ADD;
286  mk.pose.position.x = pos.x();
287  mk.pose.position.y = pos.y();
288  mk.pose.position.z = pos.z();
289  mk.pose.orientation.w = 1.0;
290  mk.scale.x = mk.scale.y = mk.scale.z = 0.035;
291  mk.color = color;
292  mk.lifetime = ros::Duration(30.0);
293  arr.markers.push_back(mk);
294  }
295  }
296 */
297 
299 {
300  constraint_approximations_.clear();
301  std::ifstream fin((path + "/manifest").c_str());
302  if (!fin.good())
303  {
304  RCLCPP_WARN(LOGGER,
305  "Manifest not found in folder '%s'. Not loading "
306  "constraint approximations.",
307  path.c_str());
308  return;
309  }
310 
311  RCLCPP_INFO(LOGGER, "Loading constrained space approximations from '%s'...", path.c_str());
312 
313  while (fin.good() && !fin.eof())
314  {
315  std::string group, state_space_parameterization, serialization, filename;
316  bool explicit_motions;
317  unsigned int milestones;
318  fin >> group;
319  if (fin.eof())
320  break;
321  fin >> state_space_parameterization;
322  if (fin.eof())
323  break;
324  fin >> explicit_motions;
325  if (fin.eof())
326  break;
327  fin >> milestones;
328  if (fin.eof())
329  break;
330  fin >> serialization;
331  if (fin.eof())
332  break;
333  fin >> filename;
334 
335  if (context_->getGroupName() != group &&
336  context_->getOMPLStateSpace()->getParameterizationType() != state_space_parameterization)
337  {
338  RCLCPP_INFO(LOGGER, "Ignoring constraint approximation of type '%s' for group '%s' from '%s'...",
339  state_space_parameterization.c_str(), group.c_str(), filename.c_str());
340  continue;
341  }
342 
343  RCLCPP_INFO(LOGGER, "Loading constraint approximation of type '%s' for group '%s' from '%s'...",
344  state_space_parameterization.c_str(), group.c_str(), filename.c_str());
345  moveit_msgs::msg::Constraints msg;
346  hexToMsg(serialization, msg);
347  auto* cass = new ConstraintApproximationStateStorage(context_->getOMPLSimpleSetup()->getStateSpace());
348  cass->load((std::string{ path }.append("/").append(filename)).c_str());
349  auto cap = std::make_shared<ConstraintApproximation>(group, state_space_parameterization, explicit_motions, msg,
350  filename, ompl::base::StateStoragePtr(cass), milestones);
351  if (constraint_approximations_.find(cap->getName()) != constraint_approximations_.end())
352  RCLCPP_WARN(LOGGER, "Overwriting constraint approximation named '%s'", cap->getName().c_str());
353  constraint_approximations_[cap->getName()] = cap;
354  std::size_t sum = 0;
355  for (std::size_t i = 0; i < cass->size(); ++i)
356  sum += cass->getMetadata(i).first.size();
357  RCLCPP_INFO(LOGGER,
358  "Loaded %lu states (%lu milestones) and %lu connections (%0.1lf per state) "
359  "for constraint named '%s'%s",
360  cass->size(), cap->getMilestoneCount(), sum, (double)sum / (double)cap->getMilestoneCount(),
361  msg.name.c_str(), explicit_motions ? ". Explicit motions included." : "");
362  }
363  RCLCPP_INFO(LOGGER, "Done loading constrained space approximations.");
364 }
365 
367 {
368  RCLCPP_INFO(LOGGER, "Saving %u constrained space approximations to '%s'",
369  (unsigned int)constraint_approximations_.size(), path.c_str());
370  try
371  {
372  std::filesystem::create_directory(path);
373  }
374  catch (...)
375  {
376  }
377 
378  std::ofstream fout((path + "/manifest").c_str());
379  if (fout.good())
380  for (std::map<std::string, ConstraintApproximationPtr>::const_iterator it = constraint_approximations_.begin();
381  it != constraint_approximations_.end(); ++it)
382  {
383  fout << it->second->getGroup() << '\n';
384  fout << it->second->getStateSpaceParameterization() << '\n';
385  fout << it->second->hasExplicitMotions() << '\n';
386  fout << it->second->getMilestoneCount() << '\n';
387  std::string serialization;
388  msgToHex(it->second->getConstraintsMsg(), serialization);
389  fout << serialization << '\n';
390  fout << it->second->getFilename() << '\n';
391  if (it->second->getStateStorage())
392  it->second->getStateStorage()->store((path + "/" + it->second->getFilename()).c_str());
393  }
394  else
395  RCLCPP_ERROR(LOGGER, "Unable to save constraint approximation to '%s'", path.c_str());
396  fout.close();
397 }
398 
400 {
401  constraint_approximations_.clear();
402 }
403 
405 {
406  for (const std::pair<const std::string, ConstraintApproximationPtr>& constraint_approximation :
407  constraint_approximations_)
408  {
409  out << constraint_approximation.second->getGroup() << '\n';
410  out << constraint_approximation.second->getStateSpaceParameterization() << '\n';
411  out << constraint_approximation.second->hasExplicitMotions() << '\n';
412  out << constraint_approximation.second->getMilestoneCount() << '\n';
413  out << constraint_approximation.second->getFilename() << '\n';
414  // TODO(henningkayser): format print constraint message
415  // out << constraint_approximation.second->getConstraintsMsg() << '\n';
416  }
417 }
418 
419 const ompl_interface::ConstraintApproximationPtr&
420 ompl_interface::ConstraintsLibrary::getConstraintApproximation(const moveit_msgs::msg::Constraints& msg) const
421 {
422  auto it = constraint_approximations_.find(msg.name);
423  if (it != constraint_approximations_.end())
424  return it->second;
425 
426  static ConstraintApproximationPtr empty;
427  return empty;
428 }
429 
431 ompl_interface::ConstraintsLibrary::addConstraintApproximation(const moveit_msgs::msg::Constraints& constr,
432  const std::string& group,
433  const planning_scene::PlanningSceneConstPtr& scene,
435 {
436  return addConstraintApproximation(constr, constr, group, scene, options);
437 }
438 
440 ompl_interface::ConstraintsLibrary::addConstraintApproximation(const moveit_msgs::msg::Constraints& constr_sampling,
441  const moveit_msgs::msg::Constraints& constr_hard,
442  const std::string& group,
443  const planning_scene::PlanningSceneConstPtr& scene,
445 {
447  if (context_->getGroupName() != group &&
448  context_->getOMPLStateSpace()->getParameterizationType() != options.state_space_parameterization)
449  {
450  RCLCPP_INFO(LOGGER, "Ignoring constraint approximation of type '%s' for group '%s'...",
451  options.state_space_parameterization.c_str(), group.c_str());
452  return res;
453  }
454 
455  context_->clear();
456  context_->setPlanningScene(scene);
457  context_->setCompleteInitialState(scene->getCurrentState());
458 
459  rclcpp::Clock clock;
460  auto start = clock.now();
461  ompl::base::StateStoragePtr state_storage =
462  constructConstraintApproximation(context_, constr_sampling, constr_hard, options, res);
463  RCLCPP_INFO(LOGGER, "Spent %lf seconds constructing the database", (clock.now() - start).seconds());
464  if (state_storage)
465  {
466  auto constraint_approx = std::make_shared<ConstraintApproximation>(
467  group, options.state_space_parameterization, options.explicit_motions, constr_hard,
468  group + "_" + boost::posix_time::to_iso_extended_string(boost::posix_time::microsec_clock::universal_time()) +
469  ".ompldb",
470  state_storage, res.milestones);
471  if (constraint_approximations_.find(constraint_approx->getName()) != constraint_approximations_.end())
472  RCLCPP_WARN(LOGGER, "Overwriting constraint approximation named '%s'", constraint_approx->getName().c_str());
473  constraint_approximations_[constraint_approx->getName()] = constraint_approx;
474  res.approx = constraint_approx;
475  }
476  else
477  RCLCPP_ERROR(LOGGER, "Unable to construct constraint approximation for group '%s'", group.c_str());
478  return res;
479 }
480 
481 ompl::base::StateStoragePtr ompl_interface::ConstraintsLibrary::constructConstraintApproximation(
482  ModelBasedPlanningContext* pcontext, const moveit_msgs::msg::Constraints& constr_sampling,
483  const moveit_msgs::msg::Constraints& constr_hard, const ConstraintApproximationConstructionOptions& options,
485 {
486  // state storage structure
488  ob::StateStoragePtr state_storage(cass);
489 
490  // construct a sampler for the sampling constraints
492  moveit::core::Transforms no_transforms(pcontext->getRobotModel()->getModelFrame());
493  kset.add(constr_hard, no_transforms);
494 
495  const moveit::core::RobotState& default_state = pcontext->getCompleteInitialRobotState();
496 
497  unsigned int attempts = 0;
498 
499  double bounds_val = std::numeric_limits<double>::max() / 2.0 - 1.0;
500  pcontext->getOMPLStateSpace()->setPlanningVolume(-bounds_val, bounds_val, -bounds_val, bounds_val, -bounds_val,
501  bounds_val);
502  pcontext->getOMPLStateSpace()->setup();
503 
504  // construct the constrained states
505 
506  moveit::core::RobotState robot_state(default_state);
507  const constraint_samplers::ConstraintSamplerManagerPtr& csmng = pcontext->getConstraintSamplerManager();
508  ConstrainedSampler* constrained_sampler = nullptr;
509  if (csmng)
510  {
511  constraint_samplers::ConstraintSamplerPtr constraint_sampler =
512  csmng->selectSampler(pcontext->getPlanningScene(), pcontext->getJointModelGroup()->getName(), constr_sampling);
513  if (constraint_sampler)
514  constrained_sampler = new ConstrainedSampler(pcontext, constraint_sampler);
515  }
516 
517  ob::StateSamplerPtr ss(constrained_sampler ? ob::StateSamplerPtr(constrained_sampler) :
518  pcontext->getOMPLStateSpace()->allocDefaultStateSampler());
519 
520  ompl::base::ScopedState<> temp(pcontext->getOMPLStateSpace());
521  int done = -1;
522  bool slow_warn = false;
523  ompl::time::point start = ompl::time::now();
524  while (state_storage->size() < options.samples)
525  {
526  ++attempts;
527  int done_now = 100 * state_storage->size() / options.samples;
528  if (done != done_now)
529  {
530  done = done_now;
531  RCLCPP_INFO(LOGGER, "%d%% complete (kept %0.1lf%% sampled states)", done,
532  100.0 * (double)state_storage->size() / (double)attempts);
533  }
534 
535  if (!slow_warn && attempts > 10 && attempts > state_storage->size() * 100)
536  {
537  slow_warn = true;
538  RCLCPP_WARN(LOGGER, "Computation of valid state database is very slow...");
539  }
540 
541  if (attempts > options.samples && state_storage->size() == 0)
542  {
543  RCLCPP_ERROR(LOGGER, "Unable to generate any samples");
544  break;
545  }
546 
547  ss->sampleUniform(temp.get());
548  pcontext->getOMPLStateSpace()->copyToRobotState(robot_state, temp.get());
549  if (kset.decide(robot_state).satisfied)
550  {
551  if (state_storage->size() < options.samples)
552  {
553  temp->as<ModelBasedStateSpace::StateType>()->tag = state_storage->size();
554  state_storage->addState(temp.get());
555  }
556  }
557  }
558 
559  result.state_sampling_time = ompl::time::seconds(ompl::time::now() - start);
560  RCLCPP_INFO(LOGGER, "Generated %u states in %lf seconds", (unsigned int)state_storage->size(),
561  result.state_sampling_time);
562  if (constrained_sampler)
563  {
564  result.sampling_success_rate = constrained_sampler->getConstrainedSamplingRate();
565  RCLCPP_INFO(LOGGER, "Constrained sampling rate: %lf", result.sampling_success_rate);
566  }
567 
568  result.milestones = state_storage->size();
569  if (options.edges_per_sample > 0)
570  {
571  RCLCPP_INFO(LOGGER, "Computing graph connections (max %u edges per sample) ...", options.edges_per_sample);
572 
573  // construct connections
574  const ob::StateSpacePtr& space = pcontext->getOMPLSimpleSetup()->getStateSpace();
575  unsigned int milestones = state_storage->size();
576  std::vector<ob::State*> int_states(options.max_explicit_points, nullptr);
577  pcontext->getOMPLSimpleSetup()->getSpaceInformation()->allocStates(int_states);
578 
579  ompl::time::point start = ompl::time::now();
580  int good = 0;
581  int done = -1;
582 
583  for (std::size_t j = 0; j < milestones; ++j)
584  {
585  int done_now = 100 * j / milestones;
586  if (done != done_now)
587  {
588  done = done_now;
589  RCLCPP_INFO(LOGGER, "%d%% complete", done);
590  }
591  if (cass->getMetadata(j).first.size() >= options.edges_per_sample)
592  continue;
593 
594  const ob::State* sj = state_storage->getState(j);
595 
596  for (std::size_t i = j + 1; i < milestones; ++i)
597  {
598  if (cass->getMetadata(i).first.size() >= options.edges_per_sample)
599  continue;
600  double d = space->distance(state_storage->getState(i), sj);
601  if (d >= options.max_edge_length)
602  continue;
603  unsigned int isteps =
604  std::min<unsigned int>(options.max_explicit_points, d / options.explicit_points_resolution);
605  double step = 1.0 / (double)isteps;
606  bool ok = true;
607  space->interpolate(state_storage->getState(i), sj, step, int_states[0]);
608  for (unsigned int k = 1; k < isteps; ++k)
609  {
610  double this_step = step / (1.0 - (k - 1) * step);
611  space->interpolate(int_states[k - 1], sj, this_step, int_states[k]);
612  pcontext->getOMPLStateSpace()->copyToRobotState(robot_state, int_states[k]);
613  if (!kset.decide(robot_state).satisfied)
614  {
615  ok = false;
616  break;
617  }
618  }
619 
620  if (ok)
621  {
622  cass->getMetadata(i).first.push_back(j);
623  cass->getMetadata(j).first.push_back(i);
624 
625  if (options.explicit_motions)
626  {
627  cass->getMetadata(i).second[j].first = state_storage->size();
628  for (unsigned int k = 0; k < isteps; ++k)
629  {
630  int_states[k]->as<ModelBasedStateSpace::StateType>()->tag = -1;
631  state_storage->addState(int_states[k]);
632  }
633  cass->getMetadata(i).second[j].second = state_storage->size();
634  cass->getMetadata(j).second[i] = cass->getMetadata(i).second[j];
635  }
636 
637  good++;
638  if (cass->getMetadata(j).first.size() >= options.edges_per_sample)
639  break;
640  }
641  }
642  }
643 
644  result.state_connection_time = ompl::time::seconds(ompl::time::now() - start);
645  RCLCPP_INFO(LOGGER, "Computed possible connexions in %lf seconds. Added %d connexions",
646  result.state_connection_time, good);
647  pcontext->getOMPLSimpleSetup()->getSpaceInformation()->freeStates(int_states);
648 
649  return state_storage;
650  }
651 
652  // TODO(davetcoleman): this function did not originally return a value,
653  // causing compiler warnings in ROS Melodic
654  // Update with more intelligent logic as needed
655  RCLCPP_ERROR(LOGGER, "No StateStoragePtr found - implement better solution here.");
656  return state_storage;
657 }
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
scene
Definition: pick.py:52
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
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