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 (std::size_t i = 0; i < goals.size(); ++i)
47 if (!goals[i]->hasType(ompl::base::GOAL_SAMPLEABLE_REGION))
48 throw ompl::Exception(
"Multiplexed goals must be instances of GoalSampleableRegion");
49 for (std::size_t i = 1; i < goals.size(); ++i)
50 if (goals[i]->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 (std::size_t i = 0; i <
goals_.size(); ++i)
64 if (
goals_[i]->hasType(ompl::base::GOAL_LAZY_SAMPLES))
70 for (std::size_t i = 0; i <
goals_.size(); ++i)
71 if (
goals_[i]->hasType(ompl::base::GOAL_LAZY_SAMPLES))
77 for (std::size_t i = 0; i <
goals_.size(); ++i)
79 if (
goals_[
gindex_]->as<ompl::base::GoalSampleableRegion>()->maxSampleCount() > 0)
86 throw ompl::Exception(
"There are no states to sample");
92 for (std::size_t i = 0; i <
goals_.size(); ++i)
93 sc +=
goals_[i]->as<GoalSampleableRegion>()->maxSampleCount();
99 for (std::size_t i = 0; i <
goals_.size(); ++i)
100 if (
goals_[i]->as<ompl::base::GoalSampleableRegion>()->canSample())
107 for (std::size_t i = 0; i <
goals_.size(); ++i)
108 if (
goals_[i]->as<ompl::base::GoalSampleableRegion>()->couldSample())
115 for (std::size_t i = 0; i <
goals_.size(); ++i)
123 double min_d = std::numeric_limits<double>::infinity();
124 for (std::size_t i = 0; i <
goals_.size(); ++i)
135 out <<
"MultiGoal [" << std::endl;
136 for (std::size_t i = 0; i <
goals_.size(); ++i)
138 out <<
"]" << std::endl;
std::vector< ompl::base::GoalPtr > goals_
virtual bool canSample() const
Query if sampler can find any sample.
virtual bool isSatisfied(const ompl::base::State *st, double *distance) const
Is the goal satisfied for this state (given a distance)
virtual bool couldSample() const
Query if sampler could find a sample in the future.
virtual void sampleGoal(ompl::base::State *st) const
Sample a goal.
virtual void print(std::ostream &out=std::cout) const
Pretty print goal information.
GoalSampleableRegionMux(const std::vector< ompl::base::GoalPtr > &goals)
Constructor.
virtual unsigned int maxSampleCount() const
Get the max sample count.
virtual double distanceGoal(const ompl::base::State *st) const
Find the distance of this state from the goal.
void stopSampling()
If there are any member lazy samplers, stop them.
void startSampling()
If there are any member lazy samplers, start them.