37 #include <boost/date_time/posix_time/posix_time.hpp>
43 #include <ompl/tools/config/SelfConfig.h>
48 static const rclcpp::Logger LOGGER =
rclcpp::get_logger(
"moveit.ompl_planning.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' };
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)
62 RCLCPP_ERROR(LOGGER,
"Failed to serialize message!");
65 const size_t serial_size_arg = serialized_msg.buffer_length;
67 hex.resize(serial_size_arg * 2);
68 for (std::size_t i = 0; i < serial_size_arg; ++i)
70 hex[i * 2] = SYMBOL[serialized_msg.buffer[i] / 16];
71 hex[i * 2 + 1] = SYMBOL[serialized_msg.buffer[i] % 16];
76 void hexToMsg(
const std::string& hex, T& msg)
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)
84 RCLCPP_ERROR(LOGGER,
"Failed to allocate message buffer!");
88 for (std::size_t i = 0; i < serial_size_arg; ++i)
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));
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)
98 RCLCPP_ERROR(LOGGER,
"Failed to deserialize message!");
112 inv_dim_ = space->getDimension() > 0 ? 1.0 /
static_cast<double>(space->getDimension()) : 1.0;
128 if (!md.first.empty())
130 std::size_t matt = md.first.size() / 3;
134 index = md.first[rng_.uniformInt(0, md.first.size() - 1)];
135 }
while (
dirty_.find(index) !=
dirty_.end() && ++att < matt);
149 double dist = space_->distance(near,
state_storage_->getState(index));
154 space_->interpolate(near,
state_storage_->getState(index),
d / dist, state);
160 void sampleGaussian(ob::State* state,
const ob::State* mean,
const double stdDev)
override
174 const ob::State* to,
const double t, ob::State* state)
179 if (tag_from < 0 || tag_to < 0)
182 if (tag_from == tag_to)
184 state_storage->getStateSpace()->copyState(state, to);
190 auto it = md.second.find(tag_to);
191 if (it == md.second.end())
193 const std::pair<std::size_t, std::size_t>& istates = it->second;
194 std::size_t index =
static_cast<std::size_t
>((istates.second - istates.first + 2) * t + 0.5);
198 state_storage->getStateSpace()->copyState(state, from);
203 if (index >= istates.second - istates.first)
205 state_storage->getStateSpace()->copyState(state, to);
209 state_storage->getStateSpace()->copyState(state, state_storage->getState(istates.first + index));
218 if (explicit_motions_ && milestones_ > 0 && milestones_ < state_storage_->size())
221 [
this](
const ompl::base::State* from,
const ompl::base::State* to,
const double t, ompl::base::State* state) {
228 ompl::base::StateSamplerPtr
231 std::size_t milestones)
233 std::vector<int> sig;
234 space->computeSignature(sig);
235 if (sig != expected_signature)
237 return ompl::base::StateSamplerPtr();
241 return std::make_shared<ConstraintApproximationStateSampler>(space, state_storage, milestones);
247 std::string
group, std::string state_space_parameterization,
bool explicit_motions,
248 moveit_msgs::msg::Constraints msg, std::string filename, ompl::base::StateStoragePtr storage,
249 std::size_t milestones)
250 : group_(std::move(
group))
251 , state_space_parameterization_(std::move(state_space_parameterization))
252 , explicit_motions_(explicit_motions)
253 , constraint_msg_(std::move(msg))
254 , ompldb_filename_(std::move(filename))
255 , state_storage_ptr_(std::move(storage))
256 , milestones_(milestones)
264 ompl::base::StateSamplerAllocator
267 if (state_storage_->size() == 0)
268 return ompl::base::StateSamplerAllocator();
269 return [
this](
const ompl::base::StateSpace* ss) {
318 constraint_approximations_.clear();
319 std::ifstream fin((path +
"/manifest").c_str());
323 "Manifest not found in folder '%s'. Not loading "
324 "constraint approximations.",
329 RCLCPP_INFO(LOGGER,
"Loading constrained space approximations from '%s'...", path.c_str());
331 while (fin.good() && !fin.eof())
333 std::string
group, state_space_parameterization, serialization, filename;
334 bool explicit_motions;
335 unsigned int milestones;
339 fin >> state_space_parameterization;
342 fin >> explicit_motions;
348 fin >> serialization;
353 if (context_->getGroupName() !=
group &&
354 context_->getOMPLStateSpace()->getParameterizationType() != state_space_parameterization)
356 RCLCPP_INFO(LOGGER,
"Ignoring constraint approximation of type '%s' for group '%s' from '%s'...",
357 state_space_parameterization.c_str(),
group.c_str(), filename.c_str());
361 RCLCPP_INFO(LOGGER,
"Loading constraint approximation of type '%s' for group '%s' from '%s'...",
362 state_space_parameterization.c_str(),
group.c_str(), filename.c_str());
363 moveit_msgs::msg::Constraints msg;
364 hexToMsg(serialization, msg);
366 cass->load((std::string{ path }.append(
"/").
append(filename)).c_str());
367 auto cap = std::make_shared<ConstraintApproximation>(
group, state_space_parameterization, explicit_motions, msg,
368 filename, ompl::base::StateStoragePtr(cass), milestones);
369 if (constraint_approximations_.find(cap->getName()) != constraint_approximations_.end())
370 RCLCPP_WARN(LOGGER,
"Overwriting constraint approximation named '%s'", cap->getName().c_str());
371 constraint_approximations_[cap->getName()] = cap;
373 for (std::size_t i = 0; i < cass->size(); ++i)
374 sum += cass->getMetadata(i).first.size();
376 "Loaded %lu states (%lu milestones) and %lu connections (%0.1lf per state) "
377 "for constraint named '%s'%s",
378 cass->size(), cap->getMilestoneCount(),
sum,
379 static_cast<double>(
sum) /
static_cast<double>(cap->getMilestoneCount()), msg.name.c_str(),
380 explicit_motions ?
". Explicit motions included." :
"");
382 RCLCPP_INFO(LOGGER,
"Done loading constrained space approximations.");
387 RCLCPP_INFO(LOGGER,
"Saving %u constrained space approximations to '%s'",
388 static_cast<unsigned int>(constraint_approximations_.size()), path.c_str());
391 std::filesystem::create_directory(path);
397 std::ofstream fout((path +
"/manifest").c_str());
400 for (std::map<std::string, ConstraintApproximationPtr>::const_iterator it = constraint_approximations_.begin();
401 it != constraint_approximations_.end(); ++it)
403 fout << it->second->getGroup() <<
'\n';
404 fout << it->second->getStateSpaceParameterization() <<
'\n';
405 fout << it->second->hasExplicitMotions() <<
'\n';
406 fout << it->second->getMilestoneCount() <<
'\n';
407 std::string serialization;
408 msgToHex(it->second->getConstraintsMsg(), serialization);
409 fout << serialization <<
'\n';
410 fout << it->second->getFilename() <<
'\n';
411 if (it->second->getStateStorage())
412 it->second->getStateStorage()->store((path +
"/" + it->second->getFilename()).c_str());
417 RCLCPP_ERROR(LOGGER,
"Unable to save constraint approximation to '%s'", path.c_str());
424 constraint_approximations_.clear();
429 for (
const std::pair<const std::string, ConstraintApproximationPtr>& constraint_approximation :
430 constraint_approximations_)
432 out << constraint_approximation.second->getGroup() <<
'\n';
433 out << constraint_approximation.second->getStateSpaceParameterization() <<
'\n';
434 out << constraint_approximation.second->hasExplicitMotions() <<
'\n';
435 out << constraint_approximation.second->getMilestoneCount() <<
'\n';
436 out << constraint_approximation.second->getFilename() <<
'\n';
442 const ompl_interface::ConstraintApproximationPtr&
445 auto it = constraint_approximations_.find(msg.name);
446 if (it != constraint_approximations_.end())
449 static ConstraintApproximationPtr empty;
455 const std::string&
group,
456 const planning_scene::PlanningSceneConstPtr& scene,
459 return addConstraintApproximation(constr, constr,
group, scene,
options);
464 const moveit_msgs::msg::Constraints& constr_hard,
465 const std::string&
group,
466 const planning_scene::PlanningSceneConstPtr& scene,
470 if (context_->getGroupName() !=
group &&
471 context_->getOMPLStateSpace()->getParameterizationType() !=
options.state_space_parameterization)
473 RCLCPP_INFO(LOGGER,
"Ignoring constraint approximation of type '%s' for group '%s'...",
474 options.state_space_parameterization.c_str(),
group.c_str());
479 context_->setPlanningScene(scene);
480 context_->setCompleteInitialState(scene->getCurrentState());
483 auto start = clock.now();
484 ompl::base::StateStoragePtr state_storage =
485 constructConstraintApproximation(context_, constr_sampling, constr_hard,
options, res);
486 RCLCPP_INFO(LOGGER,
"Spent %lf seconds constructing the database", (clock.now() - start).seconds());
489 auto constraint_approx = std::make_shared<ConstraintApproximation>(
491 group +
"_" + boost::posix_time::to_iso_extended_string(boost::posix_time::microsec_clock::universal_time()) +
494 if (constraint_approximations_.find(constraint_approx->getName()) != constraint_approximations_.end())
495 RCLCPP_WARN(LOGGER,
"Overwriting constraint approximation named '%s'", constraint_approx->getName().c_str());
496 constraint_approximations_[constraint_approx->getName()] = constraint_approx;
497 res.
approx = constraint_approx;
500 RCLCPP_ERROR(LOGGER,
"Unable to construct constraint approximation for group '%s'",
group.c_str());
504 ompl::base::StateStoragePtr ompl_interface::ConstraintsLibrary::constructConstraintApproximation(
511 ob::StateStoragePtr state_storage(cass);
516 kset.add(constr_hard, no_transforms);
520 unsigned int attempts = 0;
522 double bounds_val = std::numeric_limits<double>::max() / 2.0 - 1.0;
523 pcontext->
getOMPLStateSpace()->setPlanningVolume(-bounds_val, bounds_val, -bounds_val, bounds_val, -bounds_val,
534 constraint_samplers::ConstraintSamplerPtr constraint_sampler =
536 if (constraint_sampler)
540 ob::StateSamplerPtr ss(constrained_sampler ? ob::StateSamplerPtr(constrained_sampler) :
545 bool slow_warn =
false;
546 ompl::time::point start = ompl::time::now();
547 while (state_storage->size() <
options.samples)
550 int done_now = 100 * state_storage->size() /
options.samples;
551 if (done != done_now)
554 RCLCPP_INFO(LOGGER,
"%d%% complete (kept %0.1lf%% sampled states)", done,
555 100.0 *
static_cast<double>(state_storage->size()) /
static_cast<double>(attempts));
558 if (!slow_warn && attempts > 10 && attempts > state_storage->size() * 100)
561 RCLCPP_WARN(LOGGER,
"Computation of valid state database is very slow...");
564 if (attempts >
options.samples && state_storage->size() == 0)
566 RCLCPP_ERROR(LOGGER,
"Unable to generate any samples");
570 ss->sampleUniform(temp.get());
572 if (kset.decide(robot_state).satisfied)
574 if (state_storage->size() <
options.samples)
576 temp->as<ModelBasedStateSpace::StateType>()->tag = state_storage->size();
577 state_storage->addState(temp.get());
583 RCLCPP_INFO(LOGGER,
"Generated %u states in %lf seconds",
static_cast<unsigned int>(state_storage->size()),
585 if (constrained_sampler)
592 if (
options.edges_per_sample > 0)
594 RCLCPP_INFO(LOGGER,
"Computing graph connections (max %u edges per sample) ...",
options.edges_per_sample);
598 unsigned int milestones = state_storage->size();
599 std::vector<ob::State*> int_states(
options.max_explicit_points,
nullptr);
602 ompl::time::point start = ompl::time::now();
606 for (std::size_t j = 0; j < milestones; ++j)
608 int done_now = 100 * j / milestones;
609 if (done != done_now)
612 RCLCPP_INFO(LOGGER,
"%d%% complete", done);
614 if (cass->getMetadata(j).first.size() >=
options.edges_per_sample)
617 const ob::State* sj = state_storage->getState(j);
619 for (std::size_t i = j + 1; i < milestones; ++i)
621 if (cass->getMetadata(i).first.size() >=
options.edges_per_sample)
623 double d = space->distance(state_storage->getState(i), sj);
626 unsigned int isteps =
627 std::min<unsigned int>(
options.max_explicit_points,
d /
options.explicit_points_resolution);
628 double step = 1.0 /
static_cast<double>(isteps);
630 space->interpolate(state_storage->getState(i), sj, step, int_states[0]);
631 for (
unsigned int k = 1; k < isteps; ++k)
633 double this_step = step / (1.0 - (k - 1) * step);
634 space->interpolate(int_states[k - 1], sj, this_step, int_states[k]);
636 if (!kset.decide(robot_state).satisfied)
645 cass->getMetadata(i).first.push_back(j);
646 cass->getMetadata(j).first.push_back(i);
650 cass->getMetadata(i).second[j].first = state_storage->size();
651 for (
unsigned int k = 0; k < isteps; ++k)
653 int_states[k]->as<ModelBasedStateSpace::StateType>()->tag = -1;
654 state_storage->addState(int_states[k]);
656 cass->getMetadata(i).second[j].second = state_storage->size();
657 cass->getMetadata(j).second[i] = cass->getMetadata(i).second[j];
661 if (cass->getMetadata(j).first.size() >=
options.edges_per_sample)
668 RCLCPP_INFO(LOGGER,
"Computed possible connexions in %lf seconds. Added %d connexions",
672 return state_storage;
678 RCLCPP_ERROR(LOGGER,
"No StateStoragePtr found - implement better solution here.");
679 return state_storage;
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.
double getConstrainedSamplingRate() const
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
std::set< std::size_t > dirty_
ConstraintApproximationStateSampler(const ob::StateSpace *space, const ConstraintApproximationStateStorage *state_storage, std::size_t milestones)
const ConstraintApproximationStateStorage * state_storage_
The states to sample from.
void sampleUniform(ob::State *state) override
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 clearConstraintApproximations()
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.
rclcpp::Logger get_logger()
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)
std::string append(const std::string &left, const std::string &right)
CostFn sum(const std::vector< CostFn > &cost_functions)
ConstraintApproximationPtr approx
double state_sampling_time
double state_connection_time
double sampling_success_rate
ompl::base::StateStoragePtr state_storage_ptr_
ConstraintApproximationStateStorage * state_storage_
std::vector< int > space_signature_
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