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
00039 namespace
00040 {
00041 ompl::base::SpaceInformationPtr getGoalsSI(const std::vector<ompl::base::GoalPtr> &goals)
00042 {
00043 if (goals.empty())
00044 return ompl::base::SpaceInformationPtr();
00045 for (std::size_t i = 0 ; i < goals.size() ; ++i)
00046 if (!goals[i]->hasType(ompl::base::GOAL_SAMPLEABLE_REGION))
00047 throw ompl::Exception("Multiplexed goals must be instances of GoalSampleableRegion");
00048 for (std::size_t i = 1 ; i < goals.size() ; ++i)
00049 if (goals[i]->getSpaceInformation() != goals[0]->getSpaceInformation())
00050 throw ompl::Exception("The instance of SpaceInformation must be the same among the goals to be considered");
00051 return goals[0]->getSpaceInformation();
00052 }
00053 }
00054
00055 ompl_interface::GoalSampleableRegionMux::GoalSampleableRegionMux(const std::vector<ompl::base::GoalPtr> &goals) :
00056 ompl::base::GoalSampleableRegion(getGoalsSI(goals)), goals_(goals), gindex_(0)
00057 {
00058 }
00059
00060 void ompl_interface::GoalSampleableRegionMux::sampleGoal(ompl::base::State *st) const
00061 {
00062 for (std::size_t i = 0 ; i < goals_.size() ; ++i)
00063 {
00064 if (goals_[gindex_]->as<ompl::base::GoalSampleableRegion>()->maxSampleCount() > 0)
00065 {
00066 goals_[gindex_]->as<ompl::base::GoalSampleableRegion>()->sampleGoal(st);
00067 return;
00068 }
00069 gindex_ = (gindex_ + 1) % goals_.size();
00070 }
00071 throw ompl::Exception("There are no states to sample");
00072 }
00073
00074 unsigned int ompl_interface::GoalSampleableRegionMux::maxSampleCount() const
00075 {
00076 unsigned int sc = 0;
00077 for (std::size_t i = 0 ; i < goals_.size() ; ++i)
00078 sc += goals_[i]->as<GoalSampleableRegion>()->maxSampleCount();
00079 return sc;
00080 }
00081
00082 bool ompl_interface::GoalSampleableRegionMux::canSample() const
00083 {
00084 for (std::size_t i = 0 ; i < goals_.size() ; ++i)
00085 if (goals_[i]->as<ompl::base::GoalSampleableRegion>()->canSample())
00086 return true;
00087 return false;
00088 }
00089
00090 bool ompl_interface::GoalSampleableRegionMux::isSatisfied(const ompl::base::State *st, double *distance) const
00091 {
00092 for (std::size_t i = 0 ; i < goals_.size() ; ++i)
00093 if (goals_[i]->isSatisfied(st, distance))
00094 return true;
00095 return false;
00096 }
00097
00098 double ompl_interface::GoalSampleableRegionMux::distanceGoal(const ompl::base::State *st) const
00099 {
00100 double min_d = std::numeric_limits<double>::infinity();
00101 for (std::size_t i = 0 ; i < goals_.size() ; ++i)
00102 {
00103 double d = goals_[i]->as<ompl::base::GoalRegion>()->distanceGoal(st);
00104 if (d < min_d)
00105 min_d = d;
00106 }
00107 return min_d;
00108 }
00109
00110 void ompl_interface::GoalSampleableRegionMux::print(std::ostream &out) const
00111 {
00112 out << "MultiGoal [" << std::endl;
00113 for (std::size_t i = 0 ; i < goals_.size() ; ++i)
00114 goals_[i]->print(out);
00115 out << "]" << std::endl;
00116 }