moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
goal_union.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2011, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Ioan Sucan */
36
38#include <ompl/base/goals/GoalLazySamples.h>
39
40namespace
41{
42ompl::base::SpaceInformationPtr getGoalsSI(const std::vector<ompl::base::GoalPtr>& goals)
43{
44 if (goals.empty())
45 return ompl::base::SpaceInformationPtr();
46 for (const ompl::base::GoalPtr& goal : goals)
47 {
48 if (!goal->hasType(ompl::base::GOAL_SAMPLEABLE_REGION))
49 throw ompl::Exception("Multiplexed goals must be instances of GoalSampleableRegion");
50 }
51 for (const ompl::base::GoalPtr& goal : goals)
52 {
53 if (goal->getSpaceInformation() != goals[0]->getSpaceInformation())
54 throw ompl::Exception("The instance of SpaceInformation must be the same among the goals to be considered");
55 }
56 return goals[0]->getSpaceInformation();
57}
58} // namespace
59
60ompl_interface::GoalSampleableRegionMux::GoalSampleableRegionMux(const std::vector<ompl::base::GoalPtr>& goals)
61 : ompl::base::GoalSampleableRegion(getGoalsSI(goals)), goals_(goals), gindex_(0)
62{
63}
64
66{
67 for (ompl::base::GoalPtr& goal : goals_)
68 {
69 if (goal->hasType(ompl::base::GOAL_LAZY_SAMPLES))
70 static_cast<ompl::base::GoalLazySamples*>(goal.get())->startSampling();
71 }
72}
73
75{
76 for (ompl::base::GoalPtr& goal : goals_)
77 {
78 if (goal->hasType(ompl::base::GOAL_LAZY_SAMPLES))
79 static_cast<ompl::base::GoalLazySamples*>(goal.get())->stopSampling();
80 }
81}
82
84{
85 for (std::size_t i = 0; i < goals_.size(); ++i)
86 {
87 if (goals_[gindex_]->as<ompl::base::GoalSampleableRegion>()->maxSampleCount() > 0)
88 {
89 goals_[gindex_]->as<ompl::base::GoalSampleableRegion>()->sampleGoal(st);
90 return;
91 }
92 gindex_ = (gindex_ + 1) % goals_.size();
93 }
94 throw ompl::Exception("There are no states to sample");
95}
96
98{
99 unsigned int sc = 0;
100 for (const ompl::base::GoalPtr& goal : goals_)
101 sc += goal->as<GoalSampleableRegion>()->maxSampleCount();
102 return sc;
103}
104
106{
107 for (const ompl::base::GoalPtr& goal : goals_)
108 {
109 if (goal->as<ompl::base::GoalSampleableRegion>()->canSample())
110 return true;
111 }
112 return false;
113}
114
116{
117 for (const ompl::base::GoalPtr& goal : goals_)
118 {
119 if (goal->as<ompl::base::GoalSampleableRegion>()->couldSample())
120 return true;
121 }
122 return false;
123}
124
125bool ompl_interface::GoalSampleableRegionMux::isSatisfied(const ompl::base::State* st, double* distance) const
126{
127 for (const ompl::base::GoalPtr& goal : goals_)
128 {
129 if (goal->isSatisfied(st, distance))
130 return true;
131 }
132 return false;
133}
134
135double ompl_interface::GoalSampleableRegionMux::distanceGoal(const ompl::base::State* st) const
136{
137 double min_d = std::numeric_limits<double>::infinity();
138 for (const ompl::base::GoalPtr& goal : goals_)
139 {
140 double d = goal->as<ompl::base::GoalRegion>()->distanceGoal(st);
141 if (d < min_d)
142 min_d = d;
143 }
144 return min_d;
145}
146
148{
149 out << "MultiGoal [\n";
150 for (const ompl::base::GoalPtr& goal : goals_)
151 goal->print(out);
152 out << "]\n";
153}
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.