37#include <boost/date_time/posix_time/posix_time.hpp>
44#include <ompl/tools/config/SelfConfig.h>
57void msgToHex(
const T& msg, std::string& hex)
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)
66 RCLCPP_ERROR(
getLogger(),
"Failed to serialize message!");
69 const size_t serial_size_arg = serialized_msg.buffer_length;
71 hex.resize(serial_size_arg * 2);
72 for (std::size_t i = 0; i < serial_size_arg; ++i)
74 hex[i * 2] = SYMBOL[serialized_msg.buffer[i] / 16];
75 hex[i * 2 + 1] = SYMBOL[serialized_msg.buffer[i] % 16];
80void hexToMsg(
const std::string& hex, T& msg)
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)
88 RCLCPP_ERROR(
getLogger(),
"Failed to allocate message buffer!");
92 for (std::size_t i = 0; i < serial_size_arg; ++i)
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));
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)
102 RCLCPP_ERROR(
getLogger(),
"Failed to deserialize message!");
116 inv_dim_ = space->getDimension() > 0 ? 1.0 /
static_cast<double>(space->getDimension()) : 1.0;
132 if (!md.first.empty())
134 std::size_t matt = md.first.size() / 3;
138 index = md.first[rng_.uniformInt(0, md.first.size() - 1)];
139 }
while (
dirty_.find(index) !=
dirty_.end() && ++att < matt);
157 double d = pow(rng_.uniform01(),
inv_dim_) * distance;
158 space_->interpolate(near,
state_storage_->getState(index), d / dist, state);
164 void sampleGaussian(ob::State* state,
const ob::State* mean,
const double stdDev)
override
178 const ob::State* to,
const double t, ob::State* state)
183 if (tag_from < 0 || tag_to < 0)
186 if (tag_from == tag_to)
188 state_storage->getStateSpace()->copyState(state, to);
194 auto it = md.second.find(tag_to);
195 if (it == md.second.end())
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);
202 state_storage->getStateSpace()->copyState(state, from);
207 if (index >= istates.second - istates.first)
209 state_storage->getStateSpace()->copyState(state, to);
213 state_storage->getStateSpace()->copyState(state, state_storage->getState(istates.first + index));
225 [
this](
const ompl::base::State* from,
const ompl::base::State* to,
const double t, ompl::base::State* state) {
232ompl::base::StateSamplerPtr
235 std::size_t milestones)
237 std::vector<int> sig;
238 space->computeSignature(sig);
239 if (sig != expected_signature)
241 return ompl::base::StateSamplerPtr();
245 return std::make_shared<ConstraintApproximationStateSampler>(space, state_storage, milestones);
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)
267ompl::base::StateSamplerAllocator
271 return ompl::base::StateSamplerAllocator();
272 return [
this](
const ompl::base::StateSpace* ss) {
279 constraint_approximations_.clear();
280 std::ifstream fin((path +
"/manifest").c_str());
283 RCLCPP_WARN(getLogger(),
284 "Manifest not found in folder '%s'. Not loading "
285 "constraint approximations.",
290 RCLCPP_INFO(getLogger(),
"Loading constrained space approximations from '%s'...", path.c_str());
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;
315 context_->
getOMPLStateSpace()->getParameterizationType() != state_space_parameterization)
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());
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);
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;
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." :
"");
343 RCLCPP_INFO(getLogger(),
"Done loading constrained space approximations.");
348 RCLCPP_INFO(getLogger(),
"Saving %u constrained space approximations to '%s'",
349 static_cast<unsigned int>(constraint_approximations_.size()), path.c_str());
352 std::filesystem::create_directory(path);
358 std::ofstream fout((path +
"/manifest").c_str());
361 for (std::map<std::string, ConstraintApproximationPtr>::const_iterator it = constraint_approximations_.begin();
362 it != constraint_approximations_.end(); ++it)
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());
378 RCLCPP_ERROR(getLogger(),
"Unable to save constraint approximation to '%s'", path.c_str());
385 constraint_approximations_.clear();
390 for (
const std::pair<const std::string, ConstraintApproximationPtr>& constraint_approximation :
391 constraint_approximations_)
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';
403const ConstraintApproximationPtr&
406 auto it = constraint_approximations_.find(msg.name);
407 if (it != constraint_approximations_.end())
410 static ConstraintApproximationPtr empty;
416 const planning_scene::PlanningSceneConstPtr& scene,
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,
429 context_->
getOMPLStateSpace()->getParameterizationType() != options.state_space_parameterization)
431 RCLCPP_INFO(getLogger(),
"Ignoring constraint approximation of type '%s' for group '%s'...",
432 options.state_space_parameterization.c_str(), group.c_str());
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());
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()) +
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;
458 RCLCPP_ERROR(getLogger(),
"Unable to construct constraint approximation for group '%s'", group.c_str());
462ompl::base::StateStoragePtr ConstraintsLibrary::constructConstraintApproximation(
469 ob::StateStoragePtr state_storage(cass);
474 kset.add(constr_hard, no_transforms);
478 unsigned int attempts = 0;
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,
492 constraint_samplers::ConstraintSamplerPtr constraint_sampler =
494 if (constraint_sampler)
498 ob::StateSamplerPtr ss(constrained_sampler ? ob::StateSamplerPtr(constrained_sampler) :
499 pcontext->getOMPLStateSpace()->allocDefaultStateSampler());
503 bool slow_warn =
false;
504 ompl::time::point start = ompl::time::now();
505 while (state_storage->size() < options.samples)
508 int done_now = 100 * state_storage->size() / options.samples;
509 if (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));
516 if (!slow_warn && attempts > 10 && attempts > state_storage->size() * 100)
519 RCLCPP_WARN(
getLogger(),
"Computation of valid state database is very slow...");
522 if (attempts >
options.samples && state_storage->size() == 0)
524 RCLCPP_ERROR(
getLogger(),
"Unable to generate any samples");
528 ss->sampleUniform(temp.get());
530 if (kset.decide(robot_state).satisfied)
532 if (state_storage->size() <
options.samples)
534 temp->as<ModelBasedStateSpace::StateType>()->tag = state_storage->size();
535 state_storage->addState(temp.get());
541 RCLCPP_INFO(
getLogger(),
"Generated %u states in %lf seconds",
static_cast<unsigned int>(state_storage->size()),
543 if (constrained_sampler)
550 if (
options.edges_per_sample > 0)
552 RCLCPP_INFO(
getLogger(),
"Computing graph connections (max %u edges per sample) ...",
options.edges_per_sample);
556 unsigned int milestones = state_storage->size();
557 std::vector<ob::State*> int_states(
options.max_explicit_points,
nullptr);
560 ompl::time::point start = ompl::time::now();
564 for (std::size_t j = 0; j < milestones; ++j)
566 int done_now = 100 * j / milestones;
567 if (done != done_now)
570 RCLCPP_INFO(
getLogger(),
"%d%% complete", done);
572 if (cass->getMetadata(j).first.size() >=
options.edges_per_sample)
575 const ob::State* sj = state_storage->getState(j);
577 for (std::size_t i = j + 1; i < milestones; ++i)
579 if (cass->getMetadata(i).first.size() >=
options.edges_per_sample)
581 double d = space->distance(state_storage->getState(i), sj);
582 if (d >=
options.max_edge_length)
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);
588 space->interpolate(state_storage->getState(i), sj, step, int_states[0]);
589 for (
unsigned int k = 1; k < isteps; ++k)
591 double this_step = step / (1.0 - (k - 1) * step);
592 space->interpolate(int_states[k - 1], sj, this_step, int_states[k]);
594 if (!kset.decide(robot_state).satisfied)
603 cass->getMetadata(i).first.push_back(j);
604 cass->getMetadata(j).first.push_back(i);
608 cass->getMetadata(i).second[j].first = state_storage->size();
609 for (
unsigned int k = 0; k < isteps; ++k)
611 int_states[k]->as<ModelBasedStateSpace::StateType>()->tag = -1;
612 state_storage->addState(int_states[k]);
614 cass->getMetadata(i).second[j].second = state_storage->size();
615 cass->getMetadata(j).second[i] = cass->getMetadata(i).second[j];
619 if (cass->getMetadata(j).first.size() >=
options.edges_per_sample)
626 RCLCPP_INFO(
getLogger(),
"Computed possible connexions in %lf seconds. Added %d connexions",
630 return state_storage;
636 RCLCPP_ERROR(
getLogger(),
"No StateStoragePtr found - implement better solution here.");
637 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
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 clearConstraintApproximations()
void loadConstraintApproximations(const std::string &path)
const ConstraintApproximationPtr & getConstraintApproximation(const moveit_msgs::msg::Constraints &msg) const
void clear() override
Clear the data structures used by the planner.
const moveit::core::RobotState & getCompleteInitialRobotState() const
const moveit::core::RobotModelConstPtr & getRobotModel() const
const ModelBasedStateSpacePtr & getOMPLStateSpace() const
void setCompleteInitialState(const moveit::core::RobotState &complete_initial_robot_state)
const moveit::core::JointModelGroup * getJointModelGroup() const
const og::SimpleSetupPtr & getOMPLSimpleSetup() const
const constraint_samplers::ConstraintSamplerManagerPtr & getConstraintSamplerManager()
void setPlanningScene(const planning_scene::PlanningSceneConstPtr &planning_scene)
Set the planning scene for this context.
const planning_scene::PlanningSceneConstPtr & getPlanningScene() const
Get the planning scene associated to this planning context.
const std::string & getGroupName() const
Get the name of the group this planning context is for.
rclcpp::Logger getLogger()
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced 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
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)
InterpolationFunction getInterpolationFunction() const
ompl::base::StateSamplerAllocator getStateSamplerAllocator(const moveit_msgs::msg::Constraints &msg) const