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 / (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);
 
  145     double dist = space_->distance(near, 
state_storage_->getState(index));
 
  150       space_->interpolate(near, 
state_storage_->getState(index), 
d / dist, state);
 
  156   void sampleGaussian(ob::State* state, 
const ob::State* mean, 
const double stdDev)
 override 
  170                                   const ob::State* to, 
const double t, ob::State* state)
 
  175   if (tag_from < 0 || tag_to < 0)
 
  178   if (tag_from == tag_to)
 
  179     state_storage->getStateSpace()->copyState(state, to);
 
  184     auto it = md.second.find(tag_to);
 
  185     if (it == md.second.end())
 
  187     const std::pair<std::size_t, std::size_t>& istates = it->second;
 
  188     std::size_t index = (std::size_t)((istates.second - istates.first + 2) * t + 0.5);
 
  191       state_storage->getStateSpace()->copyState(state, from);
 
  195       if (index >= istates.second - istates.first)
 
  196         state_storage->getStateSpace()->copyState(state, to);
 
  198         state_storage->getStateSpace()->copyState(state, state_storage->getState(istates.first + index));
 
  206   if (explicit_motions_ && milestones_ > 0 && milestones_ < state_storage_->size())
 
  208         [
this](
const ompl::base::State* from, 
const ompl::base::State* to, 
const double t, ompl::base::State* state) {
 
  214 ompl::base::StateSamplerPtr
 
  217                                          std::size_t milestones)
 
  219   std::vector<int> sig;
 
  220   space->computeSignature(sig);
 
  221   if (sig != expected_signature)
 
  222     return ompl::base::StateSamplerPtr();
 
  224     return std::make_shared<ConstraintApproximationStateSampler>(space, state_storage, milestones);
 
  229     std::string 
group, std::string state_space_parameterization, 
bool explicit_motions,
 
  230     moveit_msgs::msg::Constraints msg, std::string filename, ompl::base::StateStoragePtr storage,
 
  231     std::size_t milestones)
 
  232   : group_(std::move(
group))
 
  233   , state_space_parameterization_(std::move(state_space_parameterization))
 
  234   , explicit_motions_(explicit_motions)
 
  235   , constraint_msg_(std::move(msg))
 
  236   , ompldb_filename_(std::move(filename))
 
  237   , state_storage_ptr_(std::move(storage))
 
  238   , milestones_(milestones)
 
  246 ompl::base::StateSamplerAllocator
 
  249   if (state_storage_->size() == 0)
 
  250     return ompl::base::StateSamplerAllocator();
 
  251   return [
this](
const ompl::base::StateSpace* ss) {
 
  300   constraint_approximations_.clear();
 
  301   std::ifstream fin((path + 
"/manifest").c_str());
 
  305                 "Manifest not found in folder '%s'. Not loading " 
  306                 "constraint approximations.",
 
  311   RCLCPP_INFO(LOGGER, 
"Loading constrained space approximations from '%s'...", path.c_str());
 
  313   while (fin.good() && !fin.eof())
 
  315     std::string 
group, state_space_parameterization, serialization, filename;
 
  316     bool explicit_motions;
 
  317     unsigned int milestones;
 
  321     fin >> state_space_parameterization;
 
  324     fin >> explicit_motions;
 
  330     fin >> serialization;
 
  335     if (context_->getGroupName() != 
group &&
 
  336         context_->getOMPLStateSpace()->getParameterizationType() != state_space_parameterization)
 
  338       RCLCPP_INFO(LOGGER, 
"Ignoring constraint approximation of type '%s' for group '%s' from '%s'...",
 
  339                   state_space_parameterization.c_str(), 
group.c_str(), filename.c_str());
 
  343     RCLCPP_INFO(LOGGER, 
"Loading constraint approximation of type '%s' for group '%s' from '%s'...",
 
  344                 state_space_parameterization.c_str(), 
group.c_str(), filename.c_str());
 
  345     moveit_msgs::msg::Constraints msg;
 
  346     hexToMsg(serialization, msg);
 
  348     cass->load((std::string{ path }.append(
"/").
append(filename)).c_str());
 
  349     auto cap = std::make_shared<ConstraintApproximation>(
group, state_space_parameterization, explicit_motions, msg,
 
  350                                                          filename, ompl::base::StateStoragePtr(cass), milestones);
 
  351     if (constraint_approximations_.find(cap->getName()) != constraint_approximations_.end())
 
  352       RCLCPP_WARN(LOGGER, 
"Overwriting constraint approximation named '%s'", cap->getName().c_str());
 
  353     constraint_approximations_[cap->getName()] = cap;
 
  355     for (std::size_t i = 0; i < cass->size(); ++i)
 
  356       sum += cass->getMetadata(i).first.size();
 
  358                 "Loaded %lu states (%lu milestones) and %lu connections (%0.1lf per state) " 
  359                 "for constraint named '%s'%s",
 
  360                 cass->size(), cap->getMilestoneCount(), sum, (
double)sum / (
double)cap->getMilestoneCount(),
 
  361                 msg.name.c_str(), explicit_motions ? 
". Explicit motions included." : 
"");
 
  363   RCLCPP_INFO(LOGGER, 
"Done loading constrained space approximations.");
 
  368   RCLCPP_INFO(LOGGER, 
"Saving %u constrained space approximations to '%s'",
 
  369               (
unsigned int)constraint_approximations_.size(), path.c_str());
 
  372     std::filesystem::create_directory(path);
 
  378   std::ofstream fout((path + 
"/manifest").c_str());
 
  380     for (std::map<std::string, ConstraintApproximationPtr>::const_iterator it = constraint_approximations_.begin();
 
  381          it != constraint_approximations_.end(); ++it)
 
  383       fout << it->second->getGroup() << 
'\n';
 
  384       fout << it->second->getStateSpaceParameterization() << 
'\n';
 
  385       fout << it->second->hasExplicitMotions() << 
'\n';
 
  386       fout << it->second->getMilestoneCount() << 
'\n';
 
  387       std::string serialization;
 
  388       msgToHex(it->second->getConstraintsMsg(), serialization);
 
  389       fout << serialization << 
'\n';
 
  390       fout << it->second->getFilename() << 
'\n';
 
  391       if (it->second->getStateStorage())
 
  392         it->second->getStateStorage()->store((path + 
"/" + it->second->getFilename()).c_str());
 
  395     RCLCPP_ERROR(LOGGER, 
"Unable to save constraint approximation to '%s'", path.c_str());
 
  401   constraint_approximations_.clear();
 
  406   for (
const std::pair<const std::string, ConstraintApproximationPtr>& constraint_approximation :
 
  407        constraint_approximations_)
 
  409     out << constraint_approximation.second->getGroup() << 
'\n';
 
  410     out << constraint_approximation.second->getStateSpaceParameterization() << 
'\n';
 
  411     out << constraint_approximation.second->hasExplicitMotions() << 
'\n';
 
  412     out << constraint_approximation.second->getMilestoneCount() << 
'\n';
 
  413     out << constraint_approximation.second->getFilename() << 
'\n';
 
  419 const ompl_interface::ConstraintApproximationPtr&
 
  422   auto it = constraint_approximations_.find(msg.name);
 
  423   if (it != constraint_approximations_.end())
 
  426   static ConstraintApproximationPtr empty;
 
  432                                                                const std::string& 
group,
 
  433                                                                const planning_scene::PlanningSceneConstPtr& 
scene,
 
  441                                                                const moveit_msgs::msg::Constraints& constr_hard,
 
  442                                                                const std::string& 
group,
 
  443                                                                const planning_scene::PlanningSceneConstPtr& 
scene,
 
  447   if (context_->getGroupName() != 
group &&
 
  448       context_->getOMPLStateSpace()->getParameterizationType() != 
options.state_space_parameterization)
 
  450     RCLCPP_INFO(LOGGER, 
"Ignoring constraint approximation of type '%s' for group '%s'...",
 
  451                 options.state_space_parameterization.c_str(), 
group.c_str());
 
  456   context_->setPlanningScene(
scene);
 
  457   context_->setCompleteInitialState(
scene->getCurrentState());
 
  460   auto start = clock.now();
 
  461   ompl::base::StateStoragePtr state_storage =
 
  462       constructConstraintApproximation(context_, constr_sampling, constr_hard, 
options, res);
 
  463   RCLCPP_INFO(LOGGER, 
"Spent %lf seconds constructing the database", (clock.now() - start).seconds());
 
  466     auto constraint_approx = std::make_shared<ConstraintApproximation>(
 
  468         group + 
"_" + boost::posix_time::to_iso_extended_string(boost::posix_time::microsec_clock::universal_time()) +
 
  471     if (constraint_approximations_.find(constraint_approx->getName()) != constraint_approximations_.end())
 
  472       RCLCPP_WARN(LOGGER, 
"Overwriting constraint approximation named '%s'", constraint_approx->getName().c_str());
 
  473     constraint_approximations_[constraint_approx->getName()] = constraint_approx;
 
  474     res.
approx = constraint_approx;
 
  477     RCLCPP_ERROR(LOGGER, 
"Unable to construct constraint approximation for group '%s'", 
group.c_str());
 
  481 ompl::base::StateStoragePtr ompl_interface::ConstraintsLibrary::constructConstraintApproximation(
 
  488   ob::StateStoragePtr state_storage(cass);
 
  493   kset.add(constr_hard, no_transforms);
 
  497   unsigned int attempts = 0;
 
  499   double bounds_val = std::numeric_limits<double>::max() / 2.0 - 1.0;
 
  500   pcontext->
getOMPLStateSpace()->setPlanningVolume(-bounds_val, bounds_val, -bounds_val, bounds_val, -bounds_val,
 
  511     constraint_samplers::ConstraintSamplerPtr constraint_sampler =
 
  513     if (constraint_sampler)
 
  517   ob::StateSamplerPtr ss(constrained_sampler ? ob::StateSamplerPtr(constrained_sampler) :
 
  522   bool slow_warn = 
false;
 
  523   ompl::time::point start = ompl::time::now();
 
  524   while (state_storage->size() < 
options.samples)
 
  527     int done_now = 100 * state_storage->size() / 
options.samples;
 
  528     if (done != done_now)
 
  531       RCLCPP_INFO(LOGGER, 
"%d%% complete (kept %0.1lf%% sampled states)", done,
 
  532                   100.0 * (
double)state_storage->size() / (
double)attempts);
 
  535     if (!slow_warn && attempts > 10 && attempts > state_storage->size() * 100)
 
  538       RCLCPP_WARN(LOGGER, 
"Computation of valid state database is very slow...");
 
  541     if (attempts > 
options.samples && state_storage->size() == 0)
 
  543       RCLCPP_ERROR(LOGGER, 
"Unable to generate any samples");
 
  547     ss->sampleUniform(temp.get());
 
  549     if (kset.decide(robot_state).satisfied)
 
  551       if (state_storage->size() < 
options.samples)
 
  553         temp->as<ModelBasedStateSpace::StateType>()->tag = state_storage->size();
 
  554         state_storage->addState(temp.get());
 
  560   RCLCPP_INFO(LOGGER, 
"Generated %u states in %lf seconds", (
unsigned int)state_storage->size(),
 
  562   if (constrained_sampler)
 
  569   if (
options.edges_per_sample > 0)
 
  571     RCLCPP_INFO(LOGGER, 
"Computing graph connections (max %u edges per sample) ...", 
options.edges_per_sample);
 
  575     unsigned int milestones = state_storage->size();
 
  576     std::vector<ob::State*> int_states(
options.max_explicit_points, 
nullptr);
 
  579     ompl::time::point start = ompl::time::now();
 
  583     for (std::size_t j = 0; j < milestones; ++j)
 
  585       int done_now = 100 * j / milestones;
 
  586       if (done != done_now)
 
  589         RCLCPP_INFO(LOGGER, 
"%d%% complete", done);
 
  591       if (cass->getMetadata(j).first.size() >= 
options.edges_per_sample)
 
  594       const ob::State* sj = state_storage->getState(j);
 
  596       for (std::size_t i = j + 1; i < milestones; ++i)
 
  598         if (cass->getMetadata(i).first.size() >= 
options.edges_per_sample)
 
  600         double d = space->distance(state_storage->getState(i), sj);
 
  603         unsigned int isteps =
 
  604             std::min<unsigned int>(
options.max_explicit_points, 
d / 
options.explicit_points_resolution);
 
  605         double step = 1.0 / (double)isteps;
 
  607         space->interpolate(state_storage->getState(i), sj, step, int_states[0]);
 
  608         for (
unsigned int k = 1; k < isteps; ++k)
 
  610           double this_step = step / (1.0 - (k - 1) * step);
 
  611           space->interpolate(int_states[k - 1], sj, this_step, int_states[k]);
 
  613           if (!kset.decide(robot_state).satisfied)
 
  622           cass->getMetadata(i).first.push_back(j);
 
  623           cass->getMetadata(j).first.push_back(i);
 
  627             cass->getMetadata(i).second[j].first = state_storage->size();
 
  628             for (
unsigned int k = 0; k < isteps; ++k)
 
  630               int_states[k]->as<ModelBasedStateSpace::StateType>()->tag = -1;
 
  631               state_storage->addState(int_states[k]);
 
  633             cass->getMetadata(i).second[j].second = state_storage->size();
 
  634             cass->getMetadata(j).second[i] = cass->getMetadata(i).second[j];
 
  638           if (cass->getMetadata(j).first.size() >= 
options.edges_per_sample)
 
  645     RCLCPP_INFO(LOGGER, 
"Computed possible connexions in %lf seconds. Added %d connexions",
 
  649     return state_storage;
 
  655   RCLCPP_ERROR(LOGGER, 
"No StateStoragePtr found - implement better solution here.");
 
  656   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.
 
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)
 
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