37 #include <boost/date_time/posix_time/posix_time.hpp>
38 #include <boost/filesystem.hpp>
43 #include <ompl/tools/config/SelfConfig.h>
48 constexpr
char LOGNAME[] =
"constraints_library";
53 void msgToHex(
const T& msg, std::string& hex)
55 static const char SYMBOL[] = {
'0',
'1',
'2',
'3',
'4',
'5',
'6',
'7',
'8',
'9',
'A',
'B',
'C',
'D',
'E',
'F' };
61 hex.resize(serial_size_arg * 2);
62 for (std::size_t i = 0; i < serial_size_arg; ++i)
64 hex[i * 2] = SYMBOL[buffer_arg[i] / 16];
65 hex[i * 2 + 1] = SYMBOL[buffer_arg[i] % 16];
70 void hexToMsg(
const std::string& hex, T& msg)
72 const size_t serial_size_arg = hex.length() / 2;
74 for (std::size_t i = 0; i < serial_size_arg; ++i)
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));
84 class ConstraintApproximationStateSampler :
public ob::StateSampler
92 inv_dim_ = space->getDimension() > 0 ? 1.0 / (double)space->getDimension() : 1.0;
100 void sampleUniformNear(ob::State* state,
const ob::State* near,
const double distance)
override
103 int tag = near->as<ModelBasedStateSpace::StateType>()->tag;
108 if (!md.first.empty())
110 std::size_t matt = md.first.size() / 3;
114 index = md.first[rng_.uniformInt(0, md.first.size() - 1)];
115 }
while (
dirty_.find(index) !=
dirty_.end() && ++att < matt);
125 double dist = space_->distance(near,
state_storage_->getState(index));
136 void sampleGaussian(ob::State* state,
const ob::State* mean,
const double stdDev)
override
144 std::set<std::size_t>
dirty_;
150 const ob::State* to,
const double t, ob::State* state)
152 int tag_from = from->as<ModelBasedStateSpace::StateType>()->tag;
153 int tag_to = to->as<ModelBasedStateSpace::StateType>()->tag;
155 if (tag_from < 0 || tag_to < 0)
158 if (tag_from == tag_to)
159 state_storage->getStateSpace()->copyState(state, to);
164 auto it = md.second.find(tag_to);
165 if (it == md.second.end())
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);
171 state_storage->getStateSpace()->copyState(state, from);
175 if (index >= istates.second - istates.first)
176 state_storage->getStateSpace()->copyState(state, to);
178 state_storage->getStateSpace()->copyState(state, state_storage->getState(istates.first + index));
186 if (explicit_motions_ && milestones_ > 0 && milestones_ < state_storage_->size())
188 [
this](
const ompl::base::State* from,
const ompl::base::State* to,
const double t, ompl::base::State* state) {
194 ompl::base::StateSamplerPtr
197 std::size_t milestones)
199 std::vector<int> sig;
200 space->computeSignature(sig);
201 if (sig != expected_signature)
202 return ompl::base::StateSamplerPtr();
204 return ompl::base::StateSamplerPtr(
new ConstraintApproximationStateSampler(space, state_storage, milestones));
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)
220 state_storage_->getStateSpace()->computeSignature(space_signature_);
221 if (milestones_ == 0)
222 milestones_ = state_storage_->size();
225 ompl::base::StateSamplerAllocator
229 return ompl::base::StateSamplerAllocator();
230 return [
this](
const ompl::base::StateSpace* ss) {
279 constraint_approximations_.clear();
280 std::ifstream fin((path +
"/manifest").c_str());
284 "Manifest not found in folder '%s'. Not loading "
285 "constraint approximations.",
292 while (fin.good() && !fin.eof())
294 std::string group, state_space_parameterization, serialization, filename;
295 bool explicit_motions;
296 unsigned int milestones;
300 fin >> state_space_parameterization;
303 fin >> explicit_motions;
309 fin >> serialization;
314 if (context_->getGroupName() != group &&
315 context_->getOMPLStateSpace()->getParameterizationType() != state_space_parameterization)
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());
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);
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),
335 if (constraint_approximations_.find(cap->getName()) != constraint_approximations_.end())
337 constraint_approximations_[cap->getName()] = cap;
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." :
"");
354 (
unsigned int)constraint_approximations_.size(), path.c_str());
357 boost::filesystem::create_directories(path);
363 std::ofstream fout((path +
"/manifest").c_str());
365 for (std::map<std::string, ConstraintApproximationPtr>::const_iterator it = constraint_approximations_.begin();
366 it != constraint_approximations_.end(); ++it)
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());
386 constraint_approximations_.clear();
391 for (
const std::pair<const std::string, ConstraintApproximationPtr>& constraint_approximation :
392 constraint_approximations_)
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;
403 const ompl_interface::ConstraintApproximationPtr&
406 auto it = constraint_approximations_.find(msg.name);
407 if (it != constraint_approximations_.end())
410 static ConstraintApproximationPtr empty;
416 const std::string& group,
417 const planning_scene::PlanningSceneConstPtr& scene,
420 return addConstraintApproximation(constr, constr, group, scene, options);
425 const moveit_msgs::Constraints& constr_hard,
426 const std::string& group,
427 const planning_scene::PlanningSceneConstPtr& scene,
431 if (context_->getGroupName() != group &&
440 context_->setPlanningScene(scene);
441 context_->setCompleteInitialState(scene->getCurrentState());
444 ompl::base::StateStoragePtr state_storage =
445 constructConstraintApproximation(context_, constr_sampling, constr_hard, options, res);
451 group +
"_" + boost::posix_time::to_iso_extended_string(boost::posix_time::microsec_clock::universal_time()) +
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;
471 ob::StateStoragePtr state_storage(cass);
476 kset.
add(constr_hard, no_transforms);
480 unsigned int attempts = 0;
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,
494 constraint_samplers::ConstraintSamplerPtr constraint_sampler =
496 if (constraint_sampler)
500 ob::StateSamplerPtr ss(constrained_sampler ? ob::StateSamplerPtr(constrained_sampler) :
505 bool slow_warn =
false;
506 ompl::time::point
start = ompl::time::now();
507 while (state_storage->size() < options.
samples)
510 int done_now = 100 * state_storage->size() / options.
samples;
511 if (done != done_now)
515 100.0 * (
double)state_storage->size() / (
double)attempts);
518 if (!slow_warn && attempts > 10 && attempts > state_storage->size() * 100)
524 if (attempts > options.
samples && state_storage->size() == 0)
530 ss->sampleUniform(temp.get());
534 if (state_storage->size() < options.
samples)
537 state_storage->addState(temp.get());
545 if (constrained_sampler)
558 unsigned int milestones = state_storage->size();
562 ompl::time::point
start = ompl::time::now();
566 for (std::size_t j = 0; j < milestones; ++j)
568 int done_now = 100 * j / milestones;
569 if (done != done_now)
577 const ob::State* sj = state_storage->getState(j);
579 for (std::size_t i = j + 1; i < milestones; ++i)
583 double d = space->distance(state_storage->getState(i), sj);
586 unsigned int isteps =
588 double step = 1.0 / (double)isteps;
590 space->interpolate(state_storage->getState(i), sj,
step, int_states[0]);
591 for (
unsigned int k = 1; k < isteps; ++k)
593 double this_step =
step / (1.0 - (k - 1) *
step);
594 space->interpolate(int_states[k - 1], sj, this_step, int_states[k]);
605 cass->getMetadata(i).first.push_back(j);
606 cass->getMetadata(j).first.push_back(i);
610 cass->getMetadata(i).second[j].first = state_storage->size();
611 for (
unsigned int k = 0; k < isteps; ++k)
614 state_storage->addState(int_states[k]);
616 cass->getMetadata(i).second[j].second = state_storage->size();
617 cass->getMetadata(j).second[i] = cass->getMetadata(i).second[j];
632 return state_storage;
639 return state_storage;