ompl_native_solvers.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2018, University of Edinburgh
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 //
8 // * Redistributions of source code must retain the above copyright notice,
9 // this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without specific
15 // prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 // POSSIBILITY OF SUCH DAMAGE.
28 //
29 
30 #include <ompl/geometric/planners/cforest/CForest.h>
31 #include <ompl/geometric/planners/est/EST.h>
32 #include <ompl/geometric/planners/kpiece/BKPIECE1.h>
33 #include <ompl/geometric/planners/kpiece/KPIECE1.h>
34 #include <ompl/geometric/planners/prm/LazyPRM.h>
35 #include <ompl/geometric/planners/prm/PRM.h>
36 #include <ompl/geometric/planners/prm/PRMstar.h>
37 #include <ompl/geometric/planners/rrt/LBTRRT.h>
38 #include <ompl/geometric/planners/rrt/RRT.h>
39 #include <ompl/geometric/planners/rrt/RRTConnect.h>
40 #include <ompl/geometric/planners/rrt/RRTstar.h>
41 
43 
45 REGISTER_MOTIONSOLVER_TYPE("RRTConnectSolver", exotica::RRTConnectSolver)
46 REGISTER_MOTIONSOLVER_TYPE("PRMSolver", exotica::PRMSolver)
47 REGISTER_MOTIONSOLVER_TYPE("LazyPRMSolver", exotica::LazyPRMSolver)
48 REGISTER_MOTIONSOLVER_TYPE("ESTSolver", exotica::ESTSolver)
49 REGISTER_MOTIONSOLVER_TYPE("KPIECESolver", exotica::KPIECESolver)
50 REGISTER_MOTIONSOLVER_TYPE("BKPIECESolver", exotica::BKPIECESolver)
51 REGISTER_MOTIONSOLVER_TYPE("RRTStarSolver", exotica::RRTStarSolver)
52 REGISTER_MOTIONSOLVER_TYPE("LBTRRTSolver", exotica::LBTRRTSolver)
53 
54 namespace exotica
55 {
56 RRTStarSolver::RRTStarSolver() = default;
57 
58 void RRTStarSolver::Instantiate(const RRTStarSolverInitializer &init)
59 {
60  init_ = OMPLSolverInitializer(RRTStarSolverInitializer(init));
61  algorithm_ = "Exotica_RRTStar";
62  planner_allocator_ = boost::bind(&AllocatePlanner<ompl::geometric::RRTstar>, _1, _2);
63 }
64 
65 LBTRRTSolver::LBTRRTSolver() = default;
66 
67 void LBTRRTSolver::Instantiate(const LBTRRTSolverInitializer &init)
68 {
69  init_ = OMPLSolverInitializer(LBTRRTSolverInitializer(init));
70  algorithm_ = "Exotica_LBTRRT";
71  planner_allocator_ = boost::bind(&AllocatePlanner<ompl::geometric::LBTRRT>, _1, _2);
72 }
73 
74 RRTSolver::RRTSolver() = default;
75 
76 void RRTSolver::Instantiate(const RRTSolverInitializer &init)
77 {
78  init_ = OMPLSolverInitializer(RRTSolverInitializer(init));
79  algorithm_ = "Exotica_RRT";
80  planner_allocator_ = boost::bind(&AllocatePlanner<ompl::geometric::RRT>, _1, _2);
81 }
82 
83 RRTConnectSolver::RRTConnectSolver() = default;
84 
85 void RRTConnectSolver::Instantiate(const RRTConnectSolverInitializer &init)
86 {
87  init_ = OMPLSolverInitializer(RRTConnectSolverInitializer(init));
88  algorithm_ = "Exotica_RRTConnect";
89  planner_allocator_ = boost::bind(&AllocatePlanner<ompl::geometric::RRTConnect>, _1, _2);
90 }
91 
92 void RRTConnectSolver::SetRange(double range)
93 {
94  ompl_ptr<ompl::geometric::RRTConnect> rrtcon = ompl_cast<ompl::geometric::RRTConnect>(ompl_simple_setup_->getPlanner());
95  rrtcon->setRange(range);
96 }
97 
98 double RRTConnectSolver::GetRange()
99 {
100  ompl_ptr<ompl::geometric::RRTConnect> rrtcon = ompl_cast<ompl::geometric::RRTConnect>(ompl_simple_setup_->getPlanner());
101  return rrtcon->getRange();
102 }
103 
104 ESTSolver::ESTSolver() = default;
105 
106 void ESTSolver::Instantiate(const ESTSolverInitializer &init)
107 {
108  init_ = OMPLSolverInitializer(ESTSolverInitializer(init));
109  algorithm_ = "Exotica_EST";
110  planner_allocator_ = boost::bind(&AllocatePlanner<ompl::geometric::EST>, _1, _2);
111 }
112 
113 KPIECESolver::KPIECESolver() = default;
114 
115 void KPIECESolver::Instantiate(const KPIECESolverInitializer &init)
116 {
117  init_ = OMPLSolverInitializer(KPIECESolverInitializer(init));
118  algorithm_ = "Exotica_KPIECE";
119  planner_allocator_ = boost::bind(&AllocatePlanner<ompl::geometric::KPIECE1>, _1, _2);
120 }
121 
122 BKPIECESolver::BKPIECESolver() = default;
123 
124 void BKPIECESolver::Instantiate(const BKPIECESolverInitializer &init)
125 {
126  init_ = OMPLSolverInitializer(BKPIECESolverInitializer(init));
127  algorithm_ = "Exotica_BKPIECE";
128  planner_allocator_ = boost::bind(&AllocatePlanner<ompl::geometric::BKPIECE1>, _1, _2);
129 }
130 
131 PRMSolver::PRMSolver() = default;
132 
133 void PRMSolver::Instantiate(const PRMSolverInitializer &init)
134 {
135  init_ = OMPLSolverInitializer(PRMSolverInitializer(init));
136  algorithm_ = "Exotica_PRM";
137  planner_allocator_ = boost::bind(&AllocatePlanner<ompl::geometric::PRM>, _1, _2);
138  multi_query_ = init.MultiQuery;
139 }
140 
141 void PRMSolver::GrowRoadmap(double t)
142 {
143  ompl_ptr<ompl::geometric::PRM> prm = ompl_cast<ompl::geometric::PRM>(ompl_simple_setup_->getPlanner());
144  prm->growRoadmap(t);
145 }
146 
147 void PRMSolver::ExpandRoadmap(double t)
148 {
149  ompl_ptr<ompl::geometric::PRM> prm = ompl_cast<ompl::geometric::PRM>(ompl_simple_setup_->getPlanner());
150  prm->expandRoadmap(t);
151 }
152 
153 void PRMSolver::Clear()
154 {
155  ompl_ptr<ompl::geometric::PRM> prm = ompl_cast<ompl::geometric::PRM>(ompl_simple_setup_->getPlanner());
156  ompl_simple_setup_->getPlanner()->setProblemDefinition(ompl_simple_setup_->getProblemDefinition());
157  prm->clear();
158 }
159 
160 void PRMSolver::ClearQuery()
161 {
162  ompl_ptr<ompl::geometric::PRM> prm = ompl_cast<ompl::geometric::PRM>(ompl_simple_setup_->getPlanner());
163  prm->clearQuery();
164 }
165 
166 void PRMSolver::Setup()
167 {
168  ompl_ptr<ompl::geometric::PRM> prm = ompl_cast<ompl::geometric::PRM>(ompl_simple_setup_->getPlanner());
169  prm->setup();
170 }
171 
172 int PRMSolver::EdgeCount()
173 {
174  ompl_ptr<ompl::geometric::PRM> prm = ompl_cast<ompl::geometric::PRM>(ompl_simple_setup_->getPlanner());
175  return prm->edgeCount();
176 }
177 
178 int PRMSolver::MilestoneCount()
179 {
180  ompl_ptr<ompl::geometric::PRM> prm = ompl_cast<ompl::geometric::PRM>(ompl_simple_setup_->getPlanner());
181  return prm->milestoneCount();
182 }
183 
184 bool PRMSolver::IsMultiQuery() const
185 {
186  return multi_query_;
187 }
188 
189 void PRMSolver::SetMultiQuery(bool val)
190 {
191  multi_query_ = val;
192 }
193 
194 LazyPRMSolver::LazyPRMSolver() = default;
195 
196 void LazyPRMSolver::Instantiate(const LazyPRMSolverInitializer &init)
197 {
198  init_ = OMPLSolverInitializer(LazyPRMSolverInitializer(init));
199  algorithm_ = "Exotica_LazyPRM";
200  planner_allocator_ = boost::bind(&AllocatePlanner<ompl::geometric::LazyPRM>, _1, _2);
201  multi_query_ = init.MultiQuery;
202 }
203 
204 void LazyPRMSolver::Clear()
205 {
206  ompl_ptr<ompl::geometric::LazyPRM> prm = ompl_cast<ompl::geometric::LazyPRM>(ompl_simple_setup_->getPlanner());
207  prm->clear();
208 }
209 
210 void LazyPRMSolver::ClearQuery()
211 {
212  ompl_ptr<ompl::geometric::LazyPRM> prm = ompl_cast<ompl::geometric::LazyPRM>(ompl_simple_setup_->getPlanner());
213  prm->clearQuery();
214 }
215 
216 void LazyPRMSolver::Setup()
217 {
218  ompl_ptr<ompl::geometric::LazyPRM> prm = ompl_cast<ompl::geometric::LazyPRM>(ompl_simple_setup_->getPlanner());
219  prm->setup();
220 }
221 
222 int LazyPRMSolver::EdgeCount()
223 {
224  ompl_ptr<ompl::geometric::LazyPRM> prm = ompl_cast<ompl::geometric::LazyPRM>(ompl_simple_setup_->getPlanner());
225  return prm->edgeCount();
226 }
227 
228 int LazyPRMSolver::MilestoneCount()
229 {
230  ompl_ptr<ompl::geometric::LazyPRM> prm = ompl_cast<ompl::geometric::LazyPRM>(ompl_simple_setup_->getPlanner());
231  return prm->milestoneCount();
232 }
233 
234 bool LazyPRMSolver::IsMultiQuery() const
235 {
236  return multi_query_;
237 }
238 
239 void LazyPRMSolver::SetMultiQuery(bool val)
240 {
241  multi_query_ = val;
242 }
243 } // namespace exotica
#define REGISTER_MOTIONSOLVER_TYPE(TYPE, DERIV)
boost::shared_ptr< T > ompl_cast(boost::shared_ptr< T1 > ptr)
Definition: ompl_solver.h:48


exotica_ompl_solver
Author(s): Yiming Yang
autogenerated on Sat Apr 10 2021 02:36:37