38 #include <ompl/base/goals/GoalLazySamples.h> 
   42 ompl::base::SpaceInformationPtr getGoalsSI(
const std::vector<ompl::base::GoalPtr>& goals)
 
   45     return ompl::base::SpaceInformationPtr();
 
   46   for (
const ompl::base::GoalPtr& goal : goals)
 
   47     if (!goal->hasType(ompl::base::GOAL_SAMPLEABLE_REGION))
 
   48       throw ompl::Exception(
"Multiplexed goals must be instances of GoalSampleableRegion");
 
   49   for (
const ompl::base::GoalPtr& goal : goals)
 
   50     if (goal->getSpaceInformation() != goals[0]->getSpaceInformation())
 
   51       throw ompl::Exception(
"The instance of SpaceInformation must be the same among the goals to be considered");
 
   52   return goals[0]->getSpaceInformation();
 
   57   : ompl::base::GoalSampleableRegion(getGoalsSI(goals)), goals_(goals), gindex_(0)
 
   63   for (ompl::base::GoalPtr& goal : goals_)
 
   64     if (goal->hasType(ompl::base::GOAL_LAZY_SAMPLES))
 
   65       static_cast<ompl::base::GoalLazySamples*
>(goal.get())->startSampling();
 
   70   for (ompl::base::GoalPtr& goal : goals_)
 
   71     if (goal->hasType(ompl::base::GOAL_LAZY_SAMPLES))
 
   72       static_cast<ompl::base::GoalLazySamples*
>(goal.get())->stopSampling();
 
   77   for (std::size_t i = 0; i < goals_.size(); ++i)
 
   79     if (goals_[gindex_]->as<ompl::base::GoalSampleableRegion>()->maxSampleCount() > 0)
 
   81       goals_[gindex_]->as<ompl::base::GoalSampleableRegion>()->sampleGoal(st);
 
   84     gindex_ = (gindex_ + 1) % goals_.size();
 
   86   throw ompl::Exception(
"There are no states to sample");
 
   92   for (
const ompl::base::GoalPtr& goal : goals_)
 
   93     sc += goal->as<GoalSampleableRegion>()->maxSampleCount();
 
   99   for (
const ompl::base::GoalPtr& goal : goals_)
 
  100     if (goal->as<ompl::base::GoalSampleableRegion>()->canSample())
 
  107   for (
const ompl::base::GoalPtr& goal : goals_)
 
  108     if (goal->as<ompl::base::GoalSampleableRegion>()->couldSample())
 
  115   for (
const ompl::base::GoalPtr& goal : goals_)
 
  116     if (goal->isSatisfied(st, 
distance))
 
  123   double min_d = std::numeric_limits<double>::infinity();
 
  124   for (
const ompl::base::GoalPtr& goal : goals_)
 
  126     double d = goal->as<ompl::base::GoalRegion>()->distanceGoal(st);
 
  135   out << 
"MultiGoal [\n";
 
  136   for (
const ompl::base::GoalPtr& goal : goals_)
 
void startSampling()
If there are any member lazy samplers, start them.
 
bool couldSample() const override
Query if sampler could find a sample in the future.
 
double distanceGoal(const ompl::base::State *st) const override
Find the distance of this state from the goal.
 
virtual bool canSample() const
Query if sampler can find any sample.
 
unsigned int maxSampleCount() const override
Get the max sample count.
 
GoalSampleableRegionMux(const std::vector< ompl::base::GoalPtr > &goals)
Constructor.
 
void print(std::ostream &out=std::cout) const override
Pretty print goal information.
 
void sampleGoal(ompl::base::State *st) const override
Sample a goal.
 
bool isSatisfied(const ompl::base::State *st, double *distance) const override
Is the goal satisfied for this state (given a distance)
 
void stopSampling()
If there are any member lazy samplers, stop them.
 
double distance(const urdf::Pose &transform)