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 #include <moveit/utils/logger.hpp>
43 
44 #include <ompl/tools/config/SelfConfig.h>
45 #include <utility>
46 
47 namespace ompl_interface
48 {
49 namespace
50 {
51 rclcpp::Logger getLogger()
52 {
53  return moveit::getLogger("ompl_constraints_library");
54 }
55 
56 template <typename T>
57 void msgToHex(const T& msg, std::string& hex)
58 {
59  static const char SYMBOL[] = { '0', '1', '2', '3', '4', '5', '6', '7', '8', '9', 'A', 'B', 'C', 'D', 'E', 'F' };
60  auto type_support = rosidl_typesupport_cpp::get_message_type_support_handle<T>();
61  rmw_serialized_message_t serialized_msg = { nullptr, 0, 0, rcutils_get_default_allocator() };
62  rmw_ret_t result = rmw_serialize(&msg, type_support, &serialized_msg);
63  if (result != RMW_RET_OK)
64  {
65  // TODO(henningkayser): handle error
66  RCLCPP_ERROR(getLogger(), "Failed to serialize message!");
67  return;
68  }
69  const size_t serial_size_arg = serialized_msg.buffer_length;
70 
71  hex.resize(serial_size_arg * 2);
72  for (std::size_t i = 0; i < serial_size_arg; ++i)
73  {
74  hex[i * 2] = SYMBOL[serialized_msg.buffer[i] / 16];
75  hex[i * 2 + 1] = SYMBOL[serialized_msg.buffer[i] % 16];
76  }
77 }
78 
79 template <typename T>
80 void hexToMsg(const std::string& hex, T& msg)
81 {
82  const size_t serial_size_arg = hex.length() / 2;
83  rmw_serialized_message_t serialized_msg = rcutils_get_zero_initialized_uint8_array();
84  rcutils_ret_t rcutils_result = rcutils_uint8_array_resize(&serialized_msg, serial_size_arg);
85  if (rcutils_result != RCUTILS_RET_OK)
86  {
87  // TODO(henningkayser): handle error
88  RCLCPP_ERROR(getLogger(), "Failed to allocate message buffer!");
89  return;
90  }
91 
92  for (std::size_t i = 0; i < serial_size_arg; ++i)
93  {
94  serialized_msg.buffer[i] = (hex[i * 2] <= '9' ? (hex[i * 2] - '0') : (hex[i * 2] - 'A' + 10)) * 16 +
95  (hex[i * 2 + 1] <= '9' ? (hex[i * 2 + 1] - '0') : (hex[i * 2 + 1] - 'A' + 10));
96  }
97  auto type_support = rosidl_typesupport_cpp::get_message_type_support_handle<T>();
98  rmw_ret_t result = rmw_deserialize(&serialized_msg, type_support, &msg);
99  if (result != RMW_RET_OK)
100  {
101  // TODO(henningkayser): handle error
102  RCLCPP_ERROR(getLogger(), "Failed to deserialize message!");
103  return;
104  }
105 }
106 } // namespace
107 
108 class ConstraintApproximationStateSampler : public ob::StateSampler
109 {
110 public:
111  ConstraintApproximationStateSampler(const ob::StateSpace* space,
112  const ConstraintApproximationStateStorage* state_storage, std::size_t milestones)
113  : ob::StateSampler(space), state_storage_(state_storage)
114  {
115  max_index_ = milestones - 1;
116  inv_dim_ = space->getDimension() > 0 ? 1.0 / static_cast<double>(space->getDimension()) : 1.0;
117  }
118 
119  void sampleUniform(ob::State* state) override
120  {
121  space_->copyState(state, state_storage_->getState(rng_.uniformInt(0, max_index_)));
122  }
123 
124  void sampleUniformNear(ob::State* state, const ob::State* near, const double distance) override
125  {
126  int index = -1;
127  int tag = near->as<ModelBasedStateSpace::StateType>()->tag;
128 
129  if (tag >= 0)
130  {
131  const ConstrainedStateMetadata& md = state_storage_->getMetadata(tag);
132  if (!md.first.empty())
133  {
134  std::size_t matt = md.first.size() / 3;
135  std::size_t att = 0;
136  do
137  {
138  index = md.first[rng_.uniformInt(0, md.first.size() - 1)];
139  } while (dirty_.find(index) != dirty_.end() && ++att < matt);
140  if (att >= matt)
141  {
142  index = -1;
143  }
144  else
145  {
146  dirty_.insert(index);
147  }
148  }
149  }
150  if (index < 0)
151  index = rng_.uniformInt(0, max_index_);
152 
153  double dist = space_->distance(near, state_storage_->getState(index));
154 
155  if (dist > distance)
156  {
157  double d = pow(rng_.uniform01(), inv_dim_) * distance;
158  space_->interpolate(near, state_storage_->getState(index), d / dist, state);
159  }
160  else
161  space_->copyState(state, state_storage_->getState(index));
162  }
163 
164  void sampleGaussian(ob::State* state, const ob::State* mean, const double stdDev) override
165  {
166  sampleUniformNear(state, mean, rng_.gaussian(0.0, stdDev));
167  }
168 
169 protected:
172  std::set<std::size_t> dirty_;
173  unsigned int max_index_;
174  double inv_dim_;
175 };
176 
177 bool interpolateUsingStoredStates(const ConstraintApproximationStateStorage* state_storage, const ob::State* from,
178  const ob::State* to, const double t, ob::State* state)
179 {
180  int tag_from = from->as<ModelBasedStateSpace::StateType>()->tag;
181  int tag_to = to->as<ModelBasedStateSpace::StateType>()->tag;
182 
183  if (tag_from < 0 || tag_to < 0)
184  return false;
185 
186  if (tag_from == tag_to)
187  {
188  state_storage->getStateSpace()->copyState(state, to);
189  }
190  else
191  {
192  const ConstrainedStateMetadata& md = state_storage->getMetadata(tag_from);
193 
194  auto it = md.second.find(tag_to);
195  if (it == md.second.end())
196  return false;
197  const std::pair<std::size_t, std::size_t>& istates = it->second;
198  std::size_t index = static_cast<std::size_t>((istates.second - istates.first + 2) * t + 0.5);
199 
200  if (index == 0)
201  {
202  state_storage->getStateSpace()->copyState(state, from);
203  }
204  else
205  {
206  --index;
207  if (index >= istates.second - istates.first)
208  {
209  state_storage->getStateSpace()->copyState(state, to);
210  }
211  else
212  {
213  state_storage->getStateSpace()->copyState(state, state_storage->getState(istates.first + index));
214  }
215  }
216  }
217  return true;
218 }
219 
221 {
222  if (explicit_motions_ && milestones_ > 0 && milestones_ < state_storage_->size())
223  {
224  return
225  [this](const ompl::base::State* from, const ompl::base::State* to, const double t, ompl::base::State* state) {
226  return interpolateUsingStoredStates(state_storage_, from, to, t, state);
227  };
228  }
229  return InterpolationFunction();
230 }
231 
232 ompl::base::StateSamplerPtr
233 allocConstraintApproximationStateSampler(const ob::StateSpace* space, const std::vector<int>& expected_signature,
234  const ConstraintApproximationStateStorage* state_storage,
235  std::size_t milestones)
236 {
237  std::vector<int> sig;
238  space->computeSignature(sig);
239  if (sig != expected_signature)
240  {
241  return ompl::base::StateSamplerPtr();
242  }
243  else
244  {
245  return std::make_shared<ConstraintApproximationStateSampler>(space, state_storage, milestones);
246  }
247 }
248 
249 ConstraintApproximation::ConstraintApproximation(std::string group, std::string state_space_parameterization,
250  bool explicit_motions, moveit_msgs::msg::Constraints msg,
251  std::string filename, ompl::base::StateStoragePtr storage,
252  std::size_t milestones)
253  : group_(std::move(group))
254  , state_space_parameterization_(std::move(state_space_parameterization))
255  , explicit_motions_(explicit_motions)
256  , constraint_msg_(std::move(msg))
257  , ompldb_filename_(std::move(filename))
258  , state_storage_ptr_(std::move(storage))
259  , milestones_(milestones)
260 {
262  state_storage_->getStateSpace()->computeSignature(space_signature_);
263  if (milestones_ == 0)
264  milestones_ = state_storage_->size();
265 }
266 
267 ompl::base::StateSamplerAllocator
268 ConstraintApproximation::getStateSamplerAllocator(const moveit_msgs::msg::Constraints& /*unused*/) const
269 {
270  if (state_storage_->size() == 0)
271  return ompl::base::StateSamplerAllocator();
272  return [this](const ompl::base::StateSpace* ss) {
274  };
275 }
276 
278 {
279  constraint_approximations_.clear();
280  std::ifstream fin((path + "/manifest").c_str());
281  if (!fin.good())
282  {
283  RCLCPP_WARN(getLogger(),
284  "Manifest not found in folder '%s'. Not loading "
285  "constraint approximations.",
286  path.c_str());
287  return;
288  }
289 
290  RCLCPP_INFO(getLogger(), "Loading constrained space approximations from '%s'...", path.c_str());
291 
292  while (fin.good() && !fin.eof())
293  {
294  std::string group, state_space_parameterization, serialization, filename;
295  bool explicit_motions;
296  unsigned int milestones;
297  fin >> group;
298  if (fin.eof())
299  break;
300  fin >> state_space_parameterization;
301  if (fin.eof())
302  break;
303  fin >> explicit_motions;
304  if (fin.eof())
305  break;
306  fin >> milestones;
307  if (fin.eof())
308  break;
309  fin >> serialization;
310  if (fin.eof())
311  break;
312  fin >> filename;
313 
314  if (context_->getGroupName() != group &&
315  context_->getOMPLStateSpace()->getParameterizationType() != state_space_parameterization)
316  {
317  RCLCPP_INFO(getLogger(), "Ignoring constraint approximation of type '%s' for group '%s' from '%s'...",
318  state_space_parameterization.c_str(), group.c_str(), filename.c_str());
319  continue;
320  }
321 
322  RCLCPP_INFO(getLogger(), "Loading constraint approximation of type '%s' for group '%s' from '%s'...",
323  state_space_parameterization.c_str(), group.c_str(), filename.c_str());
324  moveit_msgs::msg::Constraints msg;
325  hexToMsg(serialization, msg);
326  auto* cass = new ConstraintApproximationStateStorage(context_->getOMPLSimpleSetup()->getStateSpace());
327  cass->load((std::string{ path }.append("/").append(filename)).c_str());
328  auto cap = std::make_shared<ConstraintApproximation>(group, state_space_parameterization, explicit_motions, msg,
329  filename, ompl::base::StateStoragePtr(cass), milestones);
330  if (constraint_approximations_.find(cap->getName()) != constraint_approximations_.end())
331  RCLCPP_WARN(getLogger(), "Overwriting constraint approximation named '%s'", cap->getName().c_str());
332  constraint_approximations_[cap->getName()] = cap;
333  std::size_t sum = 0;
334  for (std::size_t i = 0; i < cass->size(); ++i)
335  sum += cass->getMetadata(i).first.size();
336  RCLCPP_INFO(getLogger(),
337  "Loaded %lu states (%lu milestones) and %lu connections (%0.1lf per state) "
338  "for constraint named '%s'%s",
339  cass->size(), cap->getMilestoneCount(), sum,
340  static_cast<double>(sum) / static_cast<double>(cap->getMilestoneCount()), msg.name.c_str(),
341  explicit_motions ? ". Explicit motions included." : "");
342  }
343  RCLCPP_INFO(getLogger(), "Done loading constrained space approximations.");
344 }
345 
347 {
348  RCLCPP_INFO(getLogger(), "Saving %u constrained space approximations to '%s'",
349  static_cast<unsigned int>(constraint_approximations_.size()), path.c_str());
350  try
351  {
352  std::filesystem::create_directory(path);
353  }
354  catch (...)
355  {
356  }
357 
358  std::ofstream fout((path + "/manifest").c_str());
359  if (fout.good())
360  {
361  for (std::map<std::string, ConstraintApproximationPtr>::const_iterator it = constraint_approximations_.begin();
362  it != constraint_approximations_.end(); ++it)
363  {
364  fout << it->second->getGroup() << '\n';
365  fout << it->second->getStateSpaceParameterization() << '\n';
366  fout << it->second->hasExplicitMotions() << '\n';
367  fout << it->second->getMilestoneCount() << '\n';
368  std::string serialization;
369  msgToHex(it->second->getConstraintsMsg(), serialization);
370  fout << serialization << '\n';
371  fout << it->second->getFilename() << '\n';
372  if (it->second->getStateStorage())
373  it->second->getStateStorage()->store((path + "/" + it->second->getFilename()).c_str());
374  }
375  }
376  else
377  {
378  RCLCPP_ERROR(getLogger(), "Unable to save constraint approximation to '%s'", path.c_str());
379  }
380  fout.close();
381 }
382 
384 {
385  constraint_approximations_.clear();
386 }
387 
389 {
390  for (const std::pair<const std::string, ConstraintApproximationPtr>& constraint_approximation :
391  constraint_approximations_)
392  {
393  out << constraint_approximation.second->getGroup() << '\n';
394  out << constraint_approximation.second->getStateSpaceParameterization() << '\n';
395  out << constraint_approximation.second->hasExplicitMotions() << '\n';
396  out << constraint_approximation.second->getMilestoneCount() << '\n';
397  out << constraint_approximation.second->getFilename() << '\n';
398  // TODO(henningkayser): format print constraint message
399  // out << constraint_approximation.second->getConstraintsMsg() << '\n';
400  }
401 }
402 
403 const ConstraintApproximationPtr&
404 ConstraintsLibrary::getConstraintApproximation(const moveit_msgs::msg::Constraints& msg) const
405 {
406  auto it = constraint_approximations_.find(msg.name);
407  if (it != constraint_approximations_.end())
408  return it->second;
409 
410  static ConstraintApproximationPtr empty;
411  return empty;
412 }
413 
415 ConstraintsLibrary::addConstraintApproximation(const moveit_msgs::msg::Constraints& constr, const std::string& group,
416  const planning_scene::PlanningSceneConstPtr& scene,
418 {
419  return addConstraintApproximation(constr, constr, group, scene, options);
420 }
421 
423  const moveit_msgs::msg::Constraints& constr_sampling, const moveit_msgs::msg::Constraints& constr_hard,
424  const std::string& group, const planning_scene::PlanningSceneConstPtr& scene,
426 {
428  if (context_->getGroupName() != group &&
429  context_->getOMPLStateSpace()->getParameterizationType() != options.state_space_parameterization)
430  {
431  RCLCPP_INFO(getLogger(), "Ignoring constraint approximation of type '%s' for group '%s'...",
432  options.state_space_parameterization.c_str(), group.c_str());
433  return res;
434  }
435 
436  context_->clear();
437  context_->setPlanningScene(scene);
438  context_->setCompleteInitialState(scene->getCurrentState());
439 
440  rclcpp::Clock clock;
441  auto start = clock.now();
442  ompl::base::StateStoragePtr state_storage =
443  constructConstraintApproximation(context_, constr_sampling, constr_hard, options, res);
444  RCLCPP_INFO(getLogger(), "Spent %lf seconds constructing the database", (clock.now() - start).seconds());
445  if (state_storage)
446  {
447  auto constraint_approx = std::make_shared<ConstraintApproximation>(
448  group, options.state_space_parameterization, options.explicit_motions, constr_hard,
449  group + "_" + boost::posix_time::to_iso_extended_string(boost::posix_time::microsec_clock::universal_time()) +
450  ".ompldb",
451  state_storage, res.milestones);
452  if (constraint_approximations_.find(constraint_approx->getName()) != constraint_approximations_.end())
453  RCLCPP_WARN(getLogger(), "Overwriting constraint approximation named '%s'", constraint_approx->getName().c_str());
454  constraint_approximations_[constraint_approx->getName()] = constraint_approx;
455  res.approx = constraint_approx;
456  }
457  else
458  RCLCPP_ERROR(getLogger(), "Unable to construct constraint approximation for group '%s'", group.c_str());
459  return res;
460 }
461 
462 ompl::base::StateStoragePtr ConstraintsLibrary::constructConstraintApproximation(
463  ModelBasedPlanningContext* pcontext, const moveit_msgs::msg::Constraints& constr_sampling,
464  const moveit_msgs::msg::Constraints& constr_hard, const ConstraintApproximationConstructionOptions& options,
466 {
467  // state storage structure
469  ob::StateStoragePtr state_storage(cass);
470 
471  // construct a sampler for the sampling constraints
473  moveit::core::Transforms no_transforms(pcontext->getRobotModel()->getModelFrame());
474  kset.add(constr_hard, no_transforms);
475 
476  const moveit::core::RobotState& default_state = pcontext->getCompleteInitialRobotState();
477 
478  unsigned int attempts = 0;
479 
480  double bounds_val = std::numeric_limits<double>::max() / 2.0 - 1.0;
481  pcontext->getOMPLStateSpace()->setPlanningVolume(-bounds_val, bounds_val, -bounds_val, bounds_val, -bounds_val,
482  bounds_val);
483  pcontext->getOMPLStateSpace()->setup();
484 
485  // construct the constrained states
486 
487  moveit::core::RobotState robot_state(default_state);
488  const constraint_samplers::ConstraintSamplerManagerPtr& csmng = pcontext->getConstraintSamplerManager();
489  ConstrainedSampler* constrained_sampler = nullptr;
490  if (csmng)
491  {
492  constraint_samplers::ConstraintSamplerPtr constraint_sampler =
493  csmng->selectSampler(pcontext->getPlanningScene(), pcontext->getJointModelGroup()->getName(), constr_sampling);
494  if (constraint_sampler)
495  constrained_sampler = new ConstrainedSampler(pcontext, constraint_sampler);
496  }
497 
498  ob::StateSamplerPtr ss(constrained_sampler ? ob::StateSamplerPtr(constrained_sampler) :
499  pcontext->getOMPLStateSpace()->allocDefaultStateSampler());
500 
501  ompl::base::ScopedState<> temp(pcontext->getOMPLStateSpace());
502  int done = -1;
503  bool slow_warn = false;
504  ompl::time::point start = ompl::time::now();
505  while (state_storage->size() < options.samples)
506  {
507  ++attempts;
508  int done_now = 100 * state_storage->size() / options.samples;
509  if (done != done_now)
510  {
511  done = done_now;
512  RCLCPP_INFO(getLogger(), "%d%% complete (kept %0.1lf%% sampled states)", done,
513  100.0 * static_cast<double>(state_storage->size()) / static_cast<double>(attempts));
514  }
515 
516  if (!slow_warn && attempts > 10 && attempts > state_storage->size() * 100)
517  {
518  slow_warn = true;
519  RCLCPP_WARN(getLogger(), "Computation of valid state database is very slow...");
520  }
521 
522  if (attempts > options.samples && state_storage->size() == 0)
523  {
524  RCLCPP_ERROR(getLogger(), "Unable to generate any samples");
525  break;
526  }
527 
528  ss->sampleUniform(temp.get());
529  pcontext->getOMPLStateSpace()->copyToRobotState(robot_state, temp.get());
530  if (kset.decide(robot_state).satisfied)
531  {
532  if (state_storage->size() < options.samples)
533  {
534  temp->as<ModelBasedStateSpace::StateType>()->tag = state_storage->size();
535  state_storage->addState(temp.get());
536  }
537  }
538  }
539 
540  result.state_sampling_time = ompl::time::seconds(ompl::time::now() - start);
541  RCLCPP_INFO(getLogger(), "Generated %u states in %lf seconds", static_cast<unsigned int>(state_storage->size()),
542  result.state_sampling_time);
543  if (constrained_sampler)
544  {
545  result.sampling_success_rate = constrained_sampler->getConstrainedSamplingRate();
546  RCLCPP_INFO(getLogger(), "Constrained sampling rate: %lf", result.sampling_success_rate);
547  }
548 
549  result.milestones = state_storage->size();
550  if (options.edges_per_sample > 0)
551  {
552  RCLCPP_INFO(getLogger(), "Computing graph connections (max %u edges per sample) ...", options.edges_per_sample);
553 
554  // construct connections
555  const ob::StateSpacePtr& space = pcontext->getOMPLSimpleSetup()->getStateSpace();
556  unsigned int milestones = state_storage->size();
557  std::vector<ob::State*> int_states(options.max_explicit_points, nullptr);
558  pcontext->getOMPLSimpleSetup()->getSpaceInformation()->allocStates(int_states);
559 
560  ompl::time::point start = ompl::time::now();
561  int good = 0;
562  int done = -1;
563 
564  for (std::size_t j = 0; j < milestones; ++j)
565  {
566  int done_now = 100 * j / milestones;
567  if (done != done_now)
568  {
569  done = done_now;
570  RCLCPP_INFO(getLogger(), "%d%% complete", done);
571  }
572  if (cass->getMetadata(j).first.size() >= options.edges_per_sample)
573  continue;
574 
575  const ob::State* sj = state_storage->getState(j);
576 
577  for (std::size_t i = j + 1; i < milestones; ++i)
578  {
579  if (cass->getMetadata(i).first.size() >= options.edges_per_sample)
580  continue;
581  double d = space->distance(state_storage->getState(i), sj);
582  if (d >= options.max_edge_length)
583  continue;
584  unsigned int isteps =
585  std::min<unsigned int>(options.max_explicit_points, d / options.explicit_points_resolution);
586  double step = 1.0 / static_cast<double>(isteps);
587  bool ok = true;
588  space->interpolate(state_storage->getState(i), sj, step, int_states[0]);
589  for (unsigned int k = 1; k < isteps; ++k)
590  {
591  double this_step = step / (1.0 - (k - 1) * step);
592  space->interpolate(int_states[k - 1], sj, this_step, int_states[k]);
593  pcontext->getOMPLStateSpace()->copyToRobotState(robot_state, int_states[k]);
594  if (!kset.decide(robot_state).satisfied)
595  {
596  ok = false;
597  break;
598  }
599  }
600 
601  if (ok)
602  {
603  cass->getMetadata(i).first.push_back(j);
604  cass->getMetadata(j).first.push_back(i);
605 
606  if (options.explicit_motions)
607  {
608  cass->getMetadata(i).second[j].first = state_storage->size();
609  for (unsigned int k = 0; k < isteps; ++k)
610  {
611  int_states[k]->as<ModelBasedStateSpace::StateType>()->tag = -1;
612  state_storage->addState(int_states[k]);
613  }
614  cass->getMetadata(i).second[j].second = state_storage->size();
615  cass->getMetadata(j).second[i] = cass->getMetadata(i).second[j];
616  }
617 
618  good++;
619  if (cass->getMetadata(j).first.size() >= options.edges_per_sample)
620  break;
621  }
622  }
623  }
624 
625  result.state_connection_time = ompl::time::seconds(ompl::time::now() - start);
626  RCLCPP_INFO(getLogger(), "Computed possible connexions in %lf seconds. Added %d connexions",
627  result.state_connection_time, good);
628  pcontext->getOMPLSimpleSetup()->getSpaceInformation()->freeStates(int_states);
629 
630  return state_storage;
631  }
632 
633  // TODO(davetcoleman): this function did not originally return a value,
634  // causing compiler warnings in ROS Melodic
635  // Update with more intelligent logic as needed
636  RCLCPP_ERROR(getLogger(), "No StateStoragePtr found - implement better solution here.");
637  return state_storage;
638 }
639 
640 } // namespace ompl_interface
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.
void printConstraintApproximations(std::ostream &out=std::cout) 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 saveConstraintApproximations(const std::string &path)
void loadConstraintApproximations(const std::string &path)
const ConstraintApproximationPtr & getConstraintApproximation(const moveit_msgs::msg::Constraints &msg) const
const moveit::core::RobotModelConstPtr & getRobotModel() const
void clear() override
Clear the data structures used by the planner.
const moveit::core::RobotState & getCompleteInitialRobotState() const
const moveit::core::JointModelGroup * getJointModelGroup() const
const constraint_samplers::ConstraintSamplerManagerPtr & getConstraintSamplerManager()
void setCompleteInitialState(const moveit::core::RobotState &complete_initial_robot_state)
const ModelBasedStateSpacePtr & getOMPLStateSpace() const
const og::SimpleSetupPtr & getOMPLSimpleSetup() const
void setPlanningScene(const planning_scene::PlanningSceneConstPtr &planning_scene)
Set the planning scene for this context.
const std::string & getGroupName() const
Get the name of the group this planning context is for.
const planning_scene::PlanningSceneConstPtr & getPlanningScene() const
Get the planning scene associated to this planning context.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79
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)
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)
InterpolationFunction getInterpolationFunction() const
ompl::base::StateSamplerAllocator getStateSamplerAllocator(const moveit_msgs::msg::Constraints &msg) const