Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <moveit/ompl_interface/detail/goal_union.h>
00038 #include <ompl/base/goals/GoalLazySamples.h>
00039
00040 namespace
00041 {
00042 ompl::base::SpaceInformationPtr getGoalsSI(const std::vector<ompl::base::GoalPtr> &goals)
00043 {
00044 if (goals.empty())
00045 return ompl::base::SpaceInformationPtr();
00046 for (std::size_t i = 0 ; i < goals.size() ; ++i)
00047 if (!goals[i]->hasType(ompl::base::GOAL_SAMPLEABLE_REGION))
00048 throw ompl::Exception("Multiplexed goals must be instances of GoalSampleableRegion");
00049 for (std::size_t i = 1 ; i < goals.size() ; ++i)
00050 if (goals[i]->getSpaceInformation() != goals[0]->getSpaceInformation())
00051 throw ompl::Exception("The instance of SpaceInformation must be the same among the goals to be considered");
00052 return goals[0]->getSpaceInformation();
00053 }
00054 }
00055
00056 ompl_interface::GoalSampleableRegionMux::GoalSampleableRegionMux(const std::vector<ompl::base::GoalPtr> &goals) :
00057 ompl::base::GoalSampleableRegion(getGoalsSI(goals)), goals_(goals), gindex_(0)
00058 {
00059 }
00060
00061 void ompl_interface::GoalSampleableRegionMux::startSampling()
00062 {
00063 for (std::size_t i = 0 ; i < goals_.size() ; ++i)
00064 if (goals_[i]->hasType(ompl::base::GOAL_LAZY_SAMPLES))
00065 static_cast<ompl::base::GoalLazySamples*>(goals_[i].get())->startSampling();
00066 }
00067
00068 void ompl_interface::GoalSampleableRegionMux::stopSampling()
00069 {
00070 for (std::size_t i = 0 ; i < goals_.size() ; ++i)
00071 if (goals_[i]->hasType(ompl::base::GOAL_LAZY_SAMPLES))
00072 static_cast<ompl::base::GoalLazySamples*>(goals_[i].get())->stopSampling();
00073 }
00074
00075 void ompl_interface::GoalSampleableRegionMux::sampleGoal(ompl::base::State *st) const
00076 {
00077 for (std::size_t i = 0 ; i < goals_.size() ; ++i)
00078 {
00079 if (goals_[gindex_]->as<ompl::base::GoalSampleableRegion>()->maxSampleCount() > 0)
00080 {
00081 goals_[gindex_]->as<ompl::base::GoalSampleableRegion>()->sampleGoal(st);
00082 return;
00083 }
00084 gindex_ = (gindex_ + 1) % goals_.size();
00085 }
00086 throw ompl::Exception("There are no states to sample");
00087 }
00088
00089 unsigned int ompl_interface::GoalSampleableRegionMux::maxSampleCount() const
00090 {
00091 unsigned int sc = 0;
00092 for (std::size_t i = 0 ; i < goals_.size() ; ++i)
00093 sc += goals_[i]->as<GoalSampleableRegion>()->maxSampleCount();
00094 return sc;
00095 }
00096
00097 bool ompl_interface::GoalSampleableRegionMux::canSample() const
00098 {
00099 for (std::size_t i = 0 ; i < goals_.size() ; ++i)
00100 if (goals_[i]->as<ompl::base::GoalSampleableRegion>()->canSample())
00101 return true;
00102 return false;
00103 }
00104
00105 bool ompl_interface::GoalSampleableRegionMux::couldSample() const
00106 {
00107 for (std::size_t i = 0 ; i < goals_.size() ; ++i)
00108 if (goals_[i]->as<ompl::base::GoalSampleableRegion>()->couldSample())
00109 return true;
00110 return false;
00111 }
00112
00113 bool ompl_interface::GoalSampleableRegionMux::isSatisfied(const ompl::base::State *st, double *distance) const
00114 {
00115 for (std::size_t i = 0 ; i < goals_.size() ; ++i)
00116 if (goals_[i]->isSatisfied(st, distance))
00117 return true;
00118 return false;
00119 }
00120
00121 double ompl_interface::GoalSampleableRegionMux::distanceGoal(const ompl::base::State *st) const
00122 {
00123 double min_d = std::numeric_limits<double>::infinity();
00124 for (std::size_t i = 0 ; i < goals_.size() ; ++i)
00125 {
00126 double d = goals_[i]->as<ompl::base::GoalRegion>()->distanceGoal(st);
00127 if (d < min_d)
00128 min_d = d;
00129 }
00130 return min_d;
00131 }
00132
00133 void ompl_interface::GoalSampleableRegionMux::print(std::ostream &out) const
00134 {
00135 out << "MultiGoal [" << std::endl;
00136 for (std::size_t i = 0 ; i < goals_.size() ; ++i)
00137 goals_[i]->print(out);
00138 out << "]" << std::endl;
00139 }