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 <boost/filesystem.hpp>
39 #include <fstream>
43 #include <ompl/tools/config/SelfConfig.h>
44 #include <utility>
45 
46 namespace ompl_interface
47 {
48 constexpr char LOGNAME[] = "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  const size_t serial_size_arg = ros::serialization::serializationLength(msg);
57 
58  boost::shared_array<uint8_t> buffer_arg(new uint8_t[serial_size_arg]);
59  ros::serialization::OStream stream_arg(buffer_arg.get(), serial_size_arg);
60  ros::serialization::serialize(stream_arg, msg);
61  hex.resize(serial_size_arg * 2);
62  for (std::size_t i = 0; i < serial_size_arg; ++i)
63  {
64  hex[i * 2] = SYMBOL[buffer_arg[i] / 16];
65  hex[i * 2 + 1] = SYMBOL[buffer_arg[i] % 16];
66  }
67 }
68 
69 template <typename T>
70 void hexToMsg(const std::string& hex, T& msg)
71 {
72  const size_t serial_size_arg = hex.length() / 2;
73  boost::shared_array<uint8_t> buffer_arg(new uint8_t[serial_size_arg]);
74  for (std::size_t i = 0; i < serial_size_arg; ++i)
75  {
76  buffer_arg[i] = (hex[i * 2] <= '9' ? (hex[i * 2] - '0') : (hex[i * 2] - 'A' + 10)) * 16 +
77  (hex[i * 2 + 1] <= '9' ? (hex[i * 2 + 1] - '0') : (hex[i * 2 + 1] - 'A' + 10));
78  }
79  ros::serialization::IStream stream_arg(buffer_arg.get(), serial_size_arg);
80  ros::serialization::deserialize(stream_arg, msg);
81 }
82 } // namespace
83 
84 class ConstraintApproximationStateSampler : public ob::StateSampler
85 {
86 public:
87  ConstraintApproximationStateSampler(const ob::StateSpace* space,
88  const ConstraintApproximationStateStorage* state_storage, std::size_t milestones)
89  : ob::StateSampler(space), state_storage_(state_storage)
90  {
91  max_index_ = milestones - 1;
92  inv_dim_ = space->getDimension() > 0 ? 1.0 / (double)space->getDimension() : 1.0;
93  }
94 
95  void sampleUniform(ob::State* state) override
96  {
97  space_->copyState(state, state_storage_->getState(rng_.uniformInt(0, max_index_)));
98  }
99 
100  void sampleUniformNear(ob::State* state, const ob::State* near, const double distance) override
101  {
102  int index = -1;
103  int tag = near->as<ModelBasedStateSpace::StateType>()->tag;
104 
105  if (tag >= 0)
106  {
107  const ConstrainedStateMetadata& md = state_storage_->getMetadata(tag);
108  if (!md.first.empty())
109  {
110  std::size_t matt = md.first.size() / 3;
111  std::size_t att = 0;
112  do
113  {
114  index = md.first[rng_.uniformInt(0, md.first.size() - 1)];
115  } while (dirty_.find(index) != dirty_.end() && ++att < matt);
116  if (att >= matt)
117  index = -1;
118  else
119  dirty_.insert(index);
120  }
121  }
122  if (index < 0)
123  index = rng_.uniformInt(0, max_index_);
124 
125  double dist = space_->distance(near, state_storage_->getState(index));
126 
127  if (dist > distance)
128  {
129  double d = pow(rng_.uniform01(), inv_dim_) * distance;
130  space_->interpolate(near, state_storage_->getState(index), d / dist, state);
131  }
132  else
133  space_->copyState(state, state_storage_->getState(index));
134  }
135 
136  void sampleGaussian(ob::State* state, const ob::State* mean, const double stdDev) override
137  {
138  sampleUniformNear(state, mean, rng_.gaussian(0.0, stdDev));
139  }
140 
141 protected:
144  std::set<std::size_t> dirty_;
145  unsigned int max_index_;
146  double inv_dim_;
147 };
148 
149 bool interpolateUsingStoredStates(const ConstraintApproximationStateStorage* state_storage, const ob::State* from,
150  const ob::State* to, const double t, ob::State* state)
151 {
152  int tag_from = from->as<ModelBasedStateSpace::StateType>()->tag;
153  int tag_to = to->as<ModelBasedStateSpace::StateType>()->tag;
154 
155  if (tag_from < 0 || tag_to < 0)
156  return false;
157 
158  if (tag_from == tag_to)
159  state_storage->getStateSpace()->copyState(state, to);
160  else
161  {
162  const ConstrainedStateMetadata& md = state_storage->getMetadata(tag_from);
163 
164  auto it = md.second.find(tag_to);
165  if (it == md.second.end())
166  return false;
167  const std::pair<std::size_t, std::size_t>& istates = it->second;
168  std::size_t index = (std::size_t)((istates.second - istates.first + 2) * t + 0.5);
169 
170  if (index == 0)
171  state_storage->getStateSpace()->copyState(state, from);
172  else
173  {
174  --index;
175  if (index >= istates.second - istates.first)
176  state_storage->getStateSpace()->copyState(state, to);
177  else
178  state_storage->getStateSpace()->copyState(state, state_storage->getState(istates.first + index));
179  }
180  }
181  return true;
182 }
183 
185 {
186  if (explicit_motions_ && milestones_ > 0 && milestones_ < state_storage_->size())
187  return
188  [this](const ompl::base::State* from, const ompl::base::State* to, const double t, ompl::base::State* state) {
189  return interpolateUsingStoredStates(state_storage_, from, to, t, state);
190  };
191  return InterpolationFunction();
192 }
193 
194 ompl::base::StateSamplerPtr
195 allocConstraintApproximationStateSampler(const ob::StateSpace* space, const std::vector<int>& expected_signature,
196  const ConstraintApproximationStateStorage* state_storage,
197  std::size_t milestones)
198 {
199  std::vector<int> sig;
200  space->computeSignature(sig);
201  if (sig != expected_signature)
202  return ompl::base::StateSamplerPtr();
203  else
204  return ompl::base::StateSamplerPtr(new ConstraintApproximationStateSampler(space, state_storage, milestones));
205 }
206 } // namespace ompl_interface
207 
209  std::string group, std::string state_space_parameterization, bool explicit_motions, moveit_msgs::Constraints msg,
210  std::string filename, ompl::base::StateStoragePtr storage, std::size_t milestones)
211  : group_(std::move(group))
212  , state_space_parameterization_(std::move(state_space_parameterization))
213  , explicit_motions_(explicit_motions)
214  , constraint_msg_(std::move(msg))
215  , ompldb_filename_(std::move(filename))
216  , state_storage_ptr_(std::move(storage))
217  , milestones_(milestones)
218 {
219  state_storage_ = static_cast<ConstraintApproximationStateStorage*>(state_storage_ptr_.get());
220  state_storage_->getStateSpace()->computeSignature(space_signature_);
221  if (milestones_ == 0)
222  milestones_ = state_storage_->size();
223 }
224 
225 ompl::base::StateSamplerAllocator
226 ompl_interface::ConstraintApproximation::getStateSamplerAllocator(const moveit_msgs::Constraints& /*unused*/) const
227 {
228  if (state_storage_->size() == 0)
229  return ompl::base::StateSamplerAllocator();
230  return [this](const ompl::base::StateSpace* ss) {
232  };
233 }
234 /*
235 void ompl_interface::ConstraintApproximation::visualizeDistribution(const
236 std::string &link_name, unsigned int count,
237 visualization_msgs::MarkerArray &arr) const
238 {
239  moveit::core::RobotState robot_state(robot_model_);
240  robot_state.setToDefaultValues();
241 
242  ompl::RNG rng;
243  std_msgs::ColorRGBA color;
244  color.r = 0.0f;
245  color.g = 1.0f;
246  color.b = 1.0f;
247  color.a = 1.0f;
248  if (state_storage_->size() < count)
249  count = state_storage_->size();
250 
251  for (std::size_t i = 0 ; i < count ; ++i)
252  {
253  state_storage_->getStateSpace()->as<ModelBasedStateSpace>()->copyToRobotState(robot_state,
254 state_storage_->getState(rng.uniformInt(0, state_storage_->size() - 1)));
255  const Eigen::Vector3d &pos =
256 robot_state.getLinkState(link_name)->getGlobalLinkTransform().translation();
257 
258  visualization_msgs::Marker mk;
259  mk.header.stamp = ros::Time::now();
260  mk.header.frame_id = robot_model_->getModelFrame();
261  mk.ns = "stored_constraint_data";
262  mk.id = i;
263  mk.type = visualization_msgs::Marker::SPHERE;
264  mk.action = visualization_msgs::Marker::ADD;
265  mk.pose.position.x = pos.x();
266  mk.pose.position.y = pos.y();
267  mk.pose.position.z = pos.z();
268  mk.pose.orientation.w = 1.0;
269  mk.scale.x = mk.scale.y = mk.scale.z = 0.035;
270  mk.color = color;
271  mk.lifetime = ros::Duration(30.0);
272  arr.markers.push_back(mk);
273  }
274  }
275 */
276 
278 {
279  constraint_approximations_.clear();
280  std::ifstream fin((path + "/manifest").c_str());
281  if (!fin.good())
282  {
284  "Manifest not found in folder '%s'. Not loading "
285  "constraint approximations.",
286  path.c_str());
287  return;
288  }
289 
290  ROS_INFO_NAMED(LOGNAME, "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  {
318  "Ignoring constraint approximation of type '%s' "
319  "for group '%s' from '%s'...",
320  state_space_parameterization.c_str(), group.c_str(), filename.c_str());
321  continue;
322  }
323 
325  "Loading constraint approximation of type '%s' for "
326  "group '%s' from '%s'...",
327  state_space_parameterization.c_str(), group.c_str(), filename.c_str());
328  moveit_msgs::Constraints msg;
329  hexToMsg(serialization, msg);
330  auto* cass = new ConstraintApproximationStateStorage(context_->getOMPLSimpleSetup()->getStateSpace());
331  cass->load((std::string{ path }.append("/").append(filename)).c_str());
332  ConstraintApproximationPtr cap(new ConstraintApproximation(group, state_space_parameterization, explicit_motions,
333  msg, filename, ompl::base::StateStoragePtr(cass),
334  milestones));
335  if (constraint_approximations_.find(cap->getName()) != constraint_approximations_.end())
336  ROS_WARN_NAMED(LOGNAME, "Overwriting constraint approximation named '%s'", cap->getName().c_str());
337  constraint_approximations_[cap->getName()] = cap;
338  std::size_t sum = 0;
339  for (std::size_t i = 0; i < cass->size(); ++i)
340  sum += cass->getMetadata(i).first.size();
342  "Loaded %lu states (%lu milestones) and %lu "
343  "connections (%0.1lf per state) "
344  "for constraint named '%s'%s",
345  cass->size(), cap->getMilestoneCount(), sum, (double)sum / (double)cap->getMilestoneCount(),
346  msg.name.c_str(), explicit_motions ? ". Explicit motions included." : "");
347  }
348  ROS_INFO_NAMED(LOGNAME, "Done loading constrained space approximations.");
349 }
350 
352 {
353  ROS_INFO_NAMED(LOGNAME, "Saving %u constrained space approximations to '%s'",
354  (unsigned int)constraint_approximations_.size(), path.c_str());
355  try
356  {
357  boost::filesystem::create_directories(path);
358  }
359  catch (...)
360  {
361  }
362 
363  std::ofstream fout((path + "/manifest").c_str());
364  if (fout.good())
365  for (std::map<std::string, ConstraintApproximationPtr>::const_iterator it = constraint_approximations_.begin();
366  it != constraint_approximations_.end(); ++it)
367  {
368  fout << it->second->getGroup() << std::endl;
369  fout << it->second->getStateSpaceParameterization() << std::endl;
370  fout << it->second->hasExplicitMotions() << std::endl;
371  fout << it->second->getMilestoneCount() << std::endl;
372  std::string serialization;
373  msgToHex(it->second->getConstraintsMsg(), serialization);
374  fout << serialization << std::endl;
375  fout << it->second->getFilename() << std::endl;
376  if (it->second->getStateStorage())
377  it->second->getStateStorage()->store((path + "/" + it->second->getFilename()).c_str());
378  }
379  else
380  ROS_ERROR_NAMED(LOGNAME, "Unable to save constraint approximation to '%s'", path.c_str());
381  fout.close();
382 }
383 
385 {
386  constraint_approximations_.clear();
387 }
388 
390 {
391  for (const std::pair<const std::string, ConstraintApproximationPtr>& constraint_approximation :
392  constraint_approximations_)
393  {
394  out << constraint_approximation.second->getGroup() << std::endl;
395  out << constraint_approximation.second->getStateSpaceParameterization() << std::endl;
396  out << constraint_approximation.second->hasExplicitMotions() << std::endl;
397  out << constraint_approximation.second->getMilestoneCount() << std::endl;
398  out << constraint_approximation.second->getFilename() << std::endl;
399  out << constraint_approximation.second->getConstraintsMsg() << std::endl;
400  }
401 }
402 
403 const ompl_interface::ConstraintApproximationPtr&
404 ompl_interface::ConstraintsLibrary::getConstraintApproximation(const moveit_msgs::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 
416  const std::string& group,
417  const planning_scene::PlanningSceneConstPtr& scene,
419 {
420  return addConstraintApproximation(constr, constr, group, scene, options);
421 }
422 
424 ompl_interface::ConstraintsLibrary::addConstraintApproximation(const moveit_msgs::Constraints& constr_sampling,
425  const moveit_msgs::Constraints& constr_hard,
426  const std::string& group,
427  const planning_scene::PlanningSceneConstPtr& scene,
429 {
431  if (context_->getGroupName() != group &&
432  context_->getOMPLStateSpace()->getParameterizationType() != options.state_space_parameterization)
433  {
434  ROS_INFO_NAMED(LOGNAME, "Ignoring constraint approximation of type '%s' for group '%s'...",
435  options.state_space_parameterization.c_str(), group.c_str());
436  return res;
437  }
438 
439  context_->clear();
440  context_->setPlanningScene(scene);
441  context_->setCompleteInitialState(scene->getCurrentState());
442 
444  ompl::base::StateStoragePtr state_storage =
445  constructConstraintApproximation(context_, constr_sampling, constr_hard, options, res);
446  ROS_INFO_NAMED(LOGNAME, "Spent %lf seconds constructing the database", (ros::WallTime::now() - start).toSec());
447  if (state_storage)
448  {
449  ConstraintApproximationPtr constraint_approx(new ConstraintApproximation(
450  group, options.state_space_parameterization, options.explicit_motions, constr_hard,
451  group + "_" + boost::posix_time::to_iso_extended_string(boost::posix_time::microsec_clock::universal_time()) +
452  ".ompldb",
453  state_storage, res.milestones));
454  if (constraint_approximations_.find(constraint_approx->getName()) != constraint_approximations_.end())
455  ROS_WARN_NAMED(LOGNAME, "Overwriting constraint approximation named '%s'", constraint_approx->getName().c_str());
456  constraint_approximations_[constraint_approx->getName()] = constraint_approx;
457  res.approx = constraint_approx;
458  }
459  else
460  ROS_ERROR_NAMED(LOGNAME, "Unable to construct constraint approximation for group '%s'", group.c_str());
461  return res;
462 }
463 
465  ModelBasedPlanningContext* pcontext, const moveit_msgs::Constraints& constr_sampling,
466  const moveit_msgs::Constraints& constr_hard, const ConstraintApproximationConstructionOptions& options,
468 {
469  // state storage structure
471  ob::StateStoragePtr state_storage(cass);
472 
473  // construct a sampler for the sampling constraints
475  moveit::core::Transforms no_transforms(pcontext->getRobotModel()->getModelFrame());
476  kset.add(constr_hard, no_transforms);
477 
478  const moveit::core::RobotState& default_state = pcontext->getCompleteInitialRobotState();
479 
480  unsigned int attempts = 0;
481 
482  double bounds_val = std::numeric_limits<double>::max() / 2.0 - 1.0;
483  pcontext->getOMPLStateSpace()->setPlanningVolume(-bounds_val, bounds_val, -bounds_val, bounds_val, -bounds_val,
484  bounds_val);
485  pcontext->getOMPLStateSpace()->setup();
486 
487  // construct the constrained states
488 
489  moveit::core::RobotState robot_state(default_state);
490  const constraint_samplers::ConstraintSamplerManagerPtr& csmng = pcontext->getConstraintSamplerManager();
491  ConstrainedSampler* constrained_sampler = nullptr;
492  if (csmng)
493  {
494  constraint_samplers::ConstraintSamplerPtr constraint_sampler =
495  csmng->selectSampler(pcontext->getPlanningScene(), pcontext->getJointModelGroup()->getName(), constr_sampling);
496  if (constraint_sampler)
497  constrained_sampler = new ConstrainedSampler(pcontext, constraint_sampler);
498  }
499 
500  ob::StateSamplerPtr ss(constrained_sampler ? ob::StateSamplerPtr(constrained_sampler) :
501  pcontext->getOMPLStateSpace()->allocDefaultStateSampler());
502 
503  ompl::base::ScopedState<> temp(pcontext->getOMPLStateSpace());
504  int done = -1;
505  bool slow_warn = false;
506  ompl::time::point start = ompl::time::now();
507  while (state_storage->size() < options.samples)
508  {
509  ++attempts;
510  int done_now = 100 * state_storage->size() / options.samples;
511  if (done != done_now)
512  {
513  done = done_now;
514  ROS_INFO_NAMED(LOGNAME, "%d%% complete (kept %0.1lf%% sampled states)", done,
515  100.0 * (double)state_storage->size() / (double)attempts);
516  }
517 
518  if (!slow_warn && attempts > 10 && attempts > state_storage->size() * 100)
519  {
520  slow_warn = true;
521  ROS_WARN_NAMED(LOGNAME, "Computation of valid state database is very slow...");
522  }
523 
524  if (attempts > options.samples && state_storage->size() == 0)
525  {
526  ROS_ERROR_NAMED(LOGNAME, "Unable to generate any samples");
527  break;
528  }
529 
530  ss->sampleUniform(temp.get());
531  pcontext->getOMPLStateSpace()->copyToRobotState(robot_state, temp.get());
532  if (kset.decide(robot_state).satisfied)
533  {
534  if (state_storage->size() < options.samples)
535  {
536  temp->as<ModelBasedStateSpace::StateType>()->tag = state_storage->size();
537  state_storage->addState(temp.get());
538  }
539  }
540  }
541 
542  result.state_sampling_time = ompl::time::seconds(ompl::time::now() - start);
543  ROS_INFO_NAMED(LOGNAME, "Generated %u states in %lf seconds", (unsigned int)state_storage->size(),
544  result.state_sampling_time);
545  if (constrained_sampler)
546  {
547  result.sampling_success_rate = constrained_sampler->getConstrainedSamplingRate();
548  ROS_INFO_NAMED(LOGNAME, "Constrained sampling rate: %lf", result.sampling_success_rate);
549  }
550 
551  result.milestones = state_storage->size();
552  if (options.edges_per_sample > 0)
553  {
554  ROS_INFO_NAMED(LOGNAME, "Computing graph connections (max %u edges per sample) ...", options.edges_per_sample);
555 
556  // construct connections
557  const ob::StateSpacePtr& space = pcontext->getOMPLSimpleSetup()->getStateSpace();
558  unsigned int milestones = state_storage->size();
559  std::vector<ob::State*> int_states(options.max_explicit_points, nullptr);
560  pcontext->getOMPLSimpleSetup()->getSpaceInformation()->allocStates(int_states);
561 
562  ompl::time::point start = ompl::time::now();
563  int good = 0;
564  int done = -1;
565 
566  for (std::size_t j = 0; j < milestones; ++j)
567  {
568  int done_now = 100 * j / milestones;
569  if (done != done_now)
570  {
571  done = done_now;
572  ROS_INFO_NAMED(LOGNAME, "%d%% complete", done);
573  }
574  if (cass->getMetadata(j).first.size() >= options.edges_per_sample)
575  continue;
576 
577  const ob::State* sj = state_storage->getState(j);
578 
579  for (std::size_t i = j + 1; i < milestones; ++i)
580  {
581  if (cass->getMetadata(i).first.size() >= options.edges_per_sample)
582  continue;
583  double d = space->distance(state_storage->getState(i), sj);
584  if (d >= options.max_edge_length)
585  continue;
586  unsigned int isteps =
587  std::min<unsigned int>(options.max_explicit_points, d / options.explicit_points_resolution);
588  double step = 1.0 / (double)isteps;
589  bool ok = true;
590  space->interpolate(state_storage->getState(i), sj, step, int_states[0]);
591  for (unsigned int k = 1; k < isteps; ++k)
592  {
593  double this_step = step / (1.0 - (k - 1) * step);
594  space->interpolate(int_states[k - 1], sj, this_step, int_states[k]);
595  pcontext->getOMPLStateSpace()->copyToRobotState(robot_state, int_states[k]);
596  if (!kset.decide(robot_state).satisfied)
597  {
598  ok = false;
599  break;
600  }
601  }
602 
603  if (ok)
604  {
605  cass->getMetadata(i).first.push_back(j);
606  cass->getMetadata(j).first.push_back(i);
607 
608  if (options.explicit_motions)
609  {
610  cass->getMetadata(i).second[j].first = state_storage->size();
611  for (unsigned int k = 0; k < isteps; ++k)
612  {
613  int_states[k]->as<ModelBasedStateSpace::StateType>()->tag = -1;
614  state_storage->addState(int_states[k]);
615  }
616  cass->getMetadata(i).second[j].second = state_storage->size();
617  cass->getMetadata(j).second[i] = cass->getMetadata(i).second[j];
618  }
619 
620  good++;
621  if (cass->getMetadata(j).first.size() >= options.edges_per_sample)
622  break;
623  }
624  }
625  }
626 
627  result.state_connection_time = ompl::time::seconds(ompl::time::now() - start);
628  ROS_INFO_NAMED(LOGNAME, "Computed possible connections in %lf seconds. Added %d connections",
629  result.state_connection_time, good);
630  pcontext->getOMPLSimpleSetup()->getSpaceInformation()->freeStates(int_states);
631 
632  return state_storage;
633  }
634 
635  // TODO(davetcoleman): this function did not originally return a value,
636  // causing compiler warnings in ROS Melodic
637  // Update with more intelligent logic as needed
638  ROS_ERROR_NAMED(LOGNAME, "No StateStoragePtr found - implement better solution here.");
639  return state_storage;
640 }
ompl_interface::ConstraintApproximationConstructionOptions::max_explicit_points
unsigned int max_explicit_points
Definition: constraints_library.h:178
ompl_interface::ConstraintsLibrary::addConstraintApproximation
ConstraintApproximationConstructionResults addConstraintApproximation(const moveit_msgs::Constraints &constr_sampling, const moveit_msgs::Constraints &constr_hard, const std::string &group, const planning_scene::PlanningSceneConstPtr &scene, const ConstraintApproximationConstructionOptions &options)
Definition: constraints_library.cpp:424
ros::serialization::OStream
ompl_interface::ConstraintApproximationStateSampler::max_index_
unsigned int max_index_
Definition: constraints_library.cpp:177
ompl_interface::ConstraintsLibrary::loadConstraintApproximations
void loadConstraintApproximations(const std::string &path)
Definition: constraints_library.cpp:277
ompl_interface::ModelBasedPlanningContext::getJointModelGroup
const moveit::core::JointModelGroup * getJointModelGroup() const
Definition: model_based_planning_context.h:140
ros::serialization::deserialize
void deserialize(Stream &stream, boost::array< T, N > &t)
ompl_interface::ConstraintApproximationStateSampler::inv_dim_
double inv_dim_
Definition: constraints_library.cpp:178
ompl_interface::ConstraintApproximationConstructionOptions::samples
unsigned int samples
Definition: constraints_library.h:173
ompl_interface::ConstraintApproximationConstructionResults::state_connection_time
double state_connection_time
Definition: constraints_library.h:186
ompl_interface::ConstrainedSampler
Definition: constrained_sampler.h:79
ompl_interface::ConstraintApproximation
Definition: constraint_approximations.h:82
ompl_interface::ModelBasedPlanningContext
Definition: model_based_planning_context.h:105
ompl_interface::ModelBasedPlanningContext::getOMPLSimpleSetup
const og::SimpleSetupPtr & getOMPLSimpleSetup() const
Definition: model_based_planning_context.h:155
ompl_interface::ConstraintsLibrary::constructConstraintApproximation
ompl::base::StateStoragePtr constructConstraintApproximation(ModelBasedPlanningContext *pcontext, const moveit_msgs::Constraints &constr_sampling, const moveit_msgs::Constraints &constr_hard, const ConstraintApproximationConstructionOptions &options, ConstraintApproximationConstructionResults &result)
Definition: constraints_library.cpp:464
ros::serialization::serializationLength
uint32_t serializationLength(const boost::array< T, N > &t)
kinematic_constraints::KinematicConstraintSet::decide
ConstraintEvaluationResult decide(const moveit::core::RobotState &state, bool verbose=false) const
ompl_interface
The MoveIt interface to OMPL.
Definition: constrained_goal_sampler.h:46
ompl_interface::ConstraintApproximation::ConstraintApproximation
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_interface::ConstraintApproximation::milestones_
std::size_t milestones_
Definition: constraints_library.h:157
ompl_interface::ConstraintApproximation::getInterpolationFunction
InterpolationFunction getInterpolationFunction() const
Definition: constraints_library.cpp:216
ompl_interface::ConstraintApproximationConstructionResults::approx
ConstraintApproximationPtr approx
Definition: constraints_library.h:183
ompl_interface::ModelBasedStateSpace::StateType
Definition: model_based_state_space.h:109
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
moveit::core::RobotState
kinematic_constraints::ConstraintEvaluationResult::satisfied
bool satisfied
ros::serialization::IStream
step
unsigned int step
ompl_interface::ConstraintApproximation::space_signature_
std::vector< int > space_signature_
Definition: constraint_approximations.h:100
ok
ROSCPP_DECL bool ok()
ompl_interface::ConstrainedStateMetadata
std::pair< std::vector< std::size_t >, std::map< std::size_t, std::pair< std::size_t, std::size_t > > > ConstrainedStateMetadata
Definition: constraints_library.h:80
ompl_interface::ConstraintApproximationConstructionResults
Definition: constraints_library.h:181
ompl_interface::ConstraintApproximation::state_storage_
ConstraintApproximationStateStorage * state_storage_
Definition: constraint_approximations.h:104
ompl_interface::ConstraintApproximation::getStateSamplerAllocator
ompl::base::StateSamplerAllocator getStateSamplerAllocator(const moveit_msgs::Constraints &msg) const
Definition: constraints_library.cpp:226
ompl_interface::ConstraintApproximationStateStorage
ompl::base::StateStorageWithMetadata< std::vector< std::size_t > > ConstraintApproximationStateStorage
Definition: constraint_approximations.h:79
moveit::core::JointModelGroup::getName
const std::string & getName() const
ompl_interface::ConstraintApproximationStateSampler::ConstraintApproximationStateSampler
ConstraintApproximationStateSampler(const ob::StateSpace *space, const ConstraintApproximationStateStorage *state_storage, std::size_t milestones)
Definition: constraints_library.cpp:119
ompl_interface::ConstraintApproximationConstructionOptions
Definition: constraints_library.h:160
ompl_interface::ConstraintApproximationStateSampler::sampleUniformNear
void sampleUniformNear(ob::State *state, const ob::State *near, const double distance) override
Definition: constraints_library.cpp:132
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
ompl_interface::ConstraintsLibrary::saveConstraintApproximations
void saveConstraintApproximations(const std::string &path)
Definition: constraints_library.cpp:351
ompl_interface::ConstraintApproximationStateSampler::dirty_
std::set< std::size_t > dirty_
Definition: constraints_library.cpp:176
kinematic_constraints::KinematicConstraintSet::add
bool add(const moveit_msgs::Constraints &c, const moveit::core::Transforms &tf)
ompl_interface::LOGNAME
constexpr char LOGNAME[]
Definition: constrained_goal_sampler.cpp:78
ros::WallTime::now
static WallTime now()
constraints_library.h
ompl_interface::ConstraintApproximationStateSampler::state_storage_
const ConstraintApproximationStateStorage * state_storage_
The states to sample from.
Definition: constraints_library.cpp:175
ompl_interface::ConstraintsLibrary::printConstraintApproximations
void printConstraintApproximations(std::ostream &out=std::cout) const
Definition: constraints_library.cpp:389
ompl_interface::ConstraintsLibrary::clearConstraintApproximations
void clearConstraintApproximations()
Definition: constraints_library.cpp:384
ompl_interface::ConstraintApproximationConstructionResults::sampling_success_rate
double sampling_success_rate
Definition: constraints_library.h:187
ompl_interface::ModelBasedPlanningContext::getOMPLStateSpace
const ModelBasedStateSpacePtr & getOMPLStateSpace() const
Definition: model_based_planning_context.h:150
boost::shared_array< uint8_t >
ompl_interface::ConstraintApproximationStateSampler::sampleGaussian
void sampleGaussian(ob::State *state, const ob::State *mean, const double stdDev) override
Definition: constraints_library.cpp:168
d
d
ompl_interface::ConstraintApproximationConstructionOptions::edges_per_sample
unsigned int edges_per_sample
Definition: constraints_library.h:174
kinematic_constraints::KinematicConstraintSet
constrained_sampler.h
ros::WallTime
ompl_interface::ConstraintApproximationConstructionOptions::explicit_points_resolution
double explicit_points_resolution
Definition: constraints_library.h:177
ompl_interface::ConstraintsLibrary::getConstraintApproximation
const ConstraintApproximationPtr & getConstraintApproximation(const moveit_msgs::Constraints &msg) const
Definition: constraints_library.cpp:404
ompl_interface::ModelBasedPlanningContext::getConstraintSamplerManager
const constraint_samplers::ConstraintSamplerManagerPtr & getConstraintSamplerManager()
Definition: model_based_planning_context.h:251
ompl_interface::interpolateUsingStoredStates
bool interpolateUsingStoredStates(const ConstraintApproximationStateStorage *state_storage, const ob::State *from, const ob::State *to, const double t, ob::State *state)
Definition: constraints_library.cpp:181
distance
template void distance(DistanceTraversalNodeBase< double > *node, BVHFrontList *front_list, int qsize)
ompl_interface::ModelBasedPlanningContext::getRobotModel
const moveit::core::RobotModelConstPtr & getRobotModel() const
Definition: model_based_planning_context.h:135
start
ROSCPP_DECL void start()
planning_interface::PlanningContext::getPlanningScene
const planning_scene::PlanningSceneConstPtr & getPlanningScene() const
append
ROSCPP_DECL std::string append(const std::string &left, const std::string &right)
moveit::core::Transforms
std
ompl_interface::allocConstraintApproximationStateSampler
ompl::base::StateSamplerPtr allocConstraintApproximationStateSampler(const ob::StateSpace *space, const std::vector< int > &expected_signature, const ConstraintApproximationStateStorage *state_storage, std::size_t milestones)
Definition: constraints_library.cpp:227
ompl_interface::ConstraintApproximationConstructionResults::state_sampling_time
double state_sampling_time
Definition: constraints_library.h:185
ompl_interface::ConstraintApproximationConstructionOptions::state_space_parameterization
std::string state_space_parameterization
Definition: constraints_library.h:172
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
index
unsigned int index
ompl_interface::InterpolationFunction
std::function< bool(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state)> InterpolationFunction
Definition: model_based_state_space.h:81
ompl_interface::ConstraintApproximationConstructionOptions::explicit_motions
bool explicit_motions
Definition: constraints_library.h:176
ompl_interface::ConstraintApproximationConstructionResults::milestones
std::size_t milestones
Definition: constraints_library.h:184
profiler.h
ompl_interface::ConstraintApproximationStateSampler::sampleUniform
void sampleUniform(ob::State *state) override
Definition: constraints_library.cpp:127
ompl_interface::ConstraintApproximationConstructionOptions::max_edge_length
double max_edge_length
Definition: constraints_library.h:175
ros::serialization::serialize
void serialize(Stream &stream, const boost::array< T, N > &t)
t
geometry_msgs::TransformStamped t
ompl_interface::ConstrainedSampler::getConstrainedSamplingRate
double getConstrainedSamplingRate() const
Definition: constrained_sampler.cpp:56
ompl_interface::ModelBasedPlanningContext::getCompleteInitialRobotState
const moveit::core::RobotState & getCompleteInitialRobotState() const
Definition: model_based_planning_context.h:145


ompl
Author(s): Ioan Sucan
autogenerated on Thu Apr 18 2024 02:24:37