Line |
Branch |
Exec |
Source |
1 |
|
|
// Copyright (c) 2023 CNRS |
2 |
|
|
// Authors: Florent Lamiraux |
3 |
|
|
// |
4 |
|
|
|
5 |
|
|
// Redistribution and use in source and binary forms, with or without |
6 |
|
|
// modification, are permitted provided that the following conditions are |
7 |
|
|
// met: |
8 |
|
|
// |
9 |
|
|
// 1. Redistributions of source code must retain the above copyright |
10 |
|
|
// notice, this list of conditions and the following disclaimer. |
11 |
|
|
// |
12 |
|
|
// 2. Redistributions in binary form must reproduce the above copyright |
13 |
|
|
// notice, this list of conditions and the following disclaimer in the |
14 |
|
|
// documentation and/or other materials provided with the distribution. |
15 |
|
|
// |
16 |
|
|
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
17 |
|
|
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
18 |
|
|
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR |
19 |
|
|
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT |
20 |
|
|
// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, |
21 |
|
|
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT |
22 |
|
|
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, |
23 |
|
|
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY |
24 |
|
|
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT |
25 |
|
|
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE |
26 |
|
|
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH |
27 |
|
|
// DAMAGE. |
28 |
|
|
|
29 |
|
|
#include <hpp/core/collision-validation.hh> |
30 |
|
|
#include <hpp/core/config-projector.hh> |
31 |
|
|
#include <hpp/core/config-validations.hh> |
32 |
|
|
#include <hpp/core/constraint-set.hh> |
33 |
|
|
#include <hpp/core/distance/reeds-shepp.hh> |
34 |
|
|
#include <hpp/core/joint-bound-validation.hh> |
35 |
|
|
#include <hpp/core/path-optimization/rs-time-parameterization.hh> |
36 |
|
|
#include <hpp/core/path-optimization/simple-time-parameterization.hh> |
37 |
|
|
#include <hpp/core/path-optimizer.hh> |
38 |
|
|
#include <hpp/core/path-planner/bi-rrt-star.hh> |
39 |
|
|
#include <hpp/core/path-projector.hh> |
40 |
|
|
#include <hpp/core/path-validation-report.hh> |
41 |
|
|
#include <hpp/core/path-validation.hh> |
42 |
|
|
#include <hpp/core/path-vector.hh> |
43 |
|
|
#include <hpp/core/problem.hh> |
44 |
|
|
#include <hpp/core/steering-method/reeds-shepp.hh> |
45 |
|
|
#include <hpp/manipulation/graph/edge.hh> |
46 |
|
|
#include <hpp/manipulation/graph/graph.hh> |
47 |
|
|
#include <hpp/manipulation/path-planner/transition-planner.hh> |
48 |
|
|
#include <hpp/manipulation/problem.hh> |
49 |
|
|
#include <hpp/manipulation/roadmap.hh> |
50 |
|
|
|
51 |
|
|
namespace hpp { |
52 |
|
|
namespace manipulation { |
53 |
|
|
namespace pathPlanner { |
54 |
|
✗ |
TransitionPlannerPtr_t TransitionPlanner::createWithRoadmap( |
55 |
|
|
const core::ProblemConstPtr_t& problem, const core::RoadmapPtr_t& roadmap) { |
56 |
|
✗ |
TransitionPlanner* ptr(new TransitionPlanner(problem, roadmap)); |
57 |
|
✗ |
TransitionPlannerPtr_t shPtr(ptr); |
58 |
|
✗ |
ptr->init(shPtr); |
59 |
|
✗ |
return shPtr; |
60 |
|
|
} |
61 |
|
|
|
62 |
|
✗ |
void TransitionPlanner::checkProblemAndForwardParameters() { |
63 |
|
|
// Check that edge has been selected |
64 |
|
|
// Initialize the planner |
65 |
|
✗ |
if (!innerProblem_->constraints() || |
66 |
|
✗ |
!innerProblem_->constraints()->configProjector()) |
67 |
|
✗ |
throw std::logic_error( |
68 |
|
|
"TransitionPlanner::startSolve: inner problem has" |
69 |
|
|
" no constraints. You probably forgot to select " |
70 |
|
✗ |
"the transition."); |
71 |
|
|
// Check that the initial configuration has been initialized |
72 |
|
✗ |
if (innerProblem_->initConfig().size() != |
73 |
|
✗ |
innerProblem_->robot()->configSize()) { |
74 |
|
✗ |
std::ostringstream os; |
75 |
|
✗ |
os << "TransitionPlanner::startSolve: initial configuration size (" |
76 |
|
✗ |
<< innerProblem_->initConfig().size() |
77 |
|
✗ |
<< ") differs from robot configuration size ( " |
78 |
|
✗ |
<< innerProblem_->robot()->configSize() << "). Did you initialize it ?"; |
79 |
|
✗ |
throw std::logic_error(os.str().c_str()); |
80 |
|
|
} |
81 |
|
|
// Forward maximal number of iterations to inner planner |
82 |
|
✗ |
innerPlanner_->maxIterations(this->maxIterations()); |
83 |
|
|
// Forward timeout to inner planner |
84 |
|
✗ |
innerPlanner_->timeOut(this->timeOut()); |
85 |
|
|
} |
86 |
|
|
|
87 |
|
✗ |
void TransitionPlanner::startSolve() { |
88 |
|
✗ |
checkProblemAndForwardParameters(); |
89 |
|
✗ |
innerProblem_->constraints()->configProjector()->rightHandSideFromConfig( |
90 |
|
✗ |
innerProblem_->initConfig()); |
91 |
|
|
// Call parent implementation |
92 |
|
✗ |
core::PathPlanner::startSolve(); |
93 |
|
|
} |
94 |
|
|
|
95 |
|
✗ |
void TransitionPlanner::oneStep() { innerPlanner_->oneStep(); } |
96 |
|
|
|
97 |
|
✗ |
core::PathVectorPtr_t TransitionPlanner::planPath(const Configuration_t qInit, |
98 |
|
|
matrixIn_t qGoals, |
99 |
|
|
bool resetRoadmap) { |
100 |
|
|
ConfigProjectorPtr_t configProjector( |
101 |
|
✗ |
innerProblem_->constraints()->configProjector()); |
102 |
|
✗ |
if (configProjector) { |
103 |
|
✗ |
configProjector->rightHandSideFromConfig(qInit); |
104 |
|
|
} |
105 |
|
✗ |
Configuration_t q(qInit); |
106 |
|
✗ |
innerProblem_->initConfig(q); |
107 |
|
✗ |
innerProblem_->resetGoalConfigs(); |
108 |
|
✗ |
for (size_type r = 0; r < qGoals.rows(); ++r) { |
109 |
|
✗ |
Configuration_t q(qGoals.row(r)); |
110 |
|
✗ |
if (!configProjector->isSatisfied(q)) { |
111 |
|
✗ |
std::ostringstream os; |
112 |
|
|
os << "hpp::manipulation::TransitionPlanner::computePath: " |
113 |
|
✗ |
<< "goal configuration at rank " << r |
114 |
|
✗ |
<< " does not satisfy the leaf constraint."; |
115 |
|
✗ |
throw std::logic_error(os.str().c_str()); |
116 |
|
|
} |
117 |
|
✗ |
innerProblem_->addGoalConfig(q); |
118 |
|
|
} |
119 |
|
✗ |
if (resetRoadmap) { |
120 |
|
✗ |
roadmap()->clear(); |
121 |
|
|
} |
122 |
|
✗ |
checkProblemAndForwardParameters(); |
123 |
|
✗ |
PathVectorPtr_t path = innerPlanner_->solve(); |
124 |
|
✗ |
path = optimizePath(path); |
125 |
|
✗ |
return path; |
126 |
|
|
} |
127 |
|
|
|
128 |
|
✗ |
core::PathPtr_t TransitionPlanner::directPath(ConfigurationIn_t q1, |
129 |
|
|
ConfigurationIn_t q2, |
130 |
|
|
bool validate, bool& success, |
131 |
|
|
std::string& status) { |
132 |
|
✗ |
core::PathPtr_t res(innerProblem_->steeringMethod()->steer(q1, q2)); |
133 |
|
✗ |
if (!res) { |
134 |
|
✗ |
success = false; |
135 |
|
✗ |
status = std::string("Steering method failed"); |
136 |
|
✗ |
return res; |
137 |
|
|
} |
138 |
|
✗ |
status = std::string(""); |
139 |
|
✗ |
core::PathProjectorPtr_t pathProjector(innerProblem_->pathProjector()); |
140 |
|
✗ |
bool success1 = true, success2 = true; |
141 |
|
✗ |
core::PathPtr_t projectedPath = res; |
142 |
|
✗ |
if (pathProjector) { |
143 |
|
✗ |
success1 = pathProjector->apply(res, projectedPath); |
144 |
|
✗ |
if (!success1) { |
145 |
|
✗ |
status += std::string("Failed to project the path. "); |
146 |
|
|
} |
147 |
|
|
} |
148 |
|
✗ |
core::PathPtr_t validPart = projectedPath; |
149 |
|
✗ |
core::PathValidationPtr_t pathValidation(innerProblem_->pathValidation()); |
150 |
|
✗ |
if (pathValidation && validate) { |
151 |
|
✗ |
core::PathValidationReportPtr_t report; |
152 |
|
|
success2 = |
153 |
|
✗ |
pathValidation->validate(projectedPath, false, validPart, report); |
154 |
|
✗ |
if (!success2) { |
155 |
|
✗ |
status += std::string("Failed to validate the path. "); |
156 |
|
|
} |
157 |
|
|
} |
158 |
|
✗ |
success = success1 && success2; |
159 |
|
✗ |
return validPart; |
160 |
|
|
} |
161 |
|
|
|
162 |
|
✗ |
bool TransitionPlanner::validateConfiguration( |
163 |
|
|
ConfigurationIn_t q, std::size_t id, |
164 |
|
|
core::ValidationReportPtr_t& report) const { |
165 |
|
✗ |
graph::EdgePtr_t edge(getEdgeOrThrow(id)); |
166 |
|
✗ |
return edge->pathValidation()->validate(q, report); |
167 |
|
|
} |
168 |
|
|
|
169 |
|
✗ |
core::PathVectorPtr_t TransitionPlanner::optimizePath(const PathPtr_t& path) { |
170 |
|
✗ |
PathVectorPtr_t pv(HPP_DYNAMIC_PTR_CAST(PathVector, path)); |
171 |
|
✗ |
if (!pv) { |
172 |
|
✗ |
pv = core::PathVector::create(path->outputSize(), |
173 |
|
✗ |
path->outputDerivativeSize()); |
174 |
|
✗ |
pv->appendPath(path); |
175 |
|
|
} |
176 |
|
✗ |
for (auto po : pathOptimizers_) { |
177 |
|
✗ |
pv = po->optimize(pv); |
178 |
|
|
} |
179 |
|
✗ |
return pv; |
180 |
|
|
} |
181 |
|
|
|
182 |
|
✗ |
core::PathVectorPtr_t TransitionPlanner::timeParameterization( |
183 |
|
|
const PathVectorPtr_t& path) { |
184 |
|
✗ |
return timeParameterization_->optimize(path); |
185 |
|
|
} |
186 |
|
|
|
187 |
|
✗ |
void TransitionPlanner::setEdge(std::size_t id) { |
188 |
|
✗ |
graph::EdgePtr_t edge(getEdgeOrThrow(id)); |
189 |
|
✗ |
innerProblem_->constraints(edge->pathConstraint()); |
190 |
|
✗ |
innerProblem_->pathValidation(edge->pathValidation()); |
191 |
|
✗ |
innerProblem_->steeringMethod(edge->steeringMethod()); |
192 |
|
|
} |
193 |
|
|
|
194 |
|
✗ |
void TransitionPlanner::setReedsAndSheppSteeringMethod(double turningRadius) { |
195 |
|
✗ |
core::JointPtr_t root(innerProblem_->robot()->rootJoint()); |
196 |
|
✗ |
core::SteeringMethodPtr_t sm(core::steeringMethod::ReedsShepp::create( |
197 |
|
✗ |
innerProblem_, turningRadius, root, root)); |
198 |
|
✗ |
core::DistancePtr_t dist(core::distance::ReedsShepp::create(innerProblem_)); |
199 |
|
✗ |
innerProblem_->steeringMethod(sm); |
200 |
|
✗ |
innerProblem_->distance(dist); |
201 |
|
|
timeParameterization_ = |
202 |
|
✗ |
core::pathOptimization::RSTimeParameterization::create(innerProblem_); |
203 |
|
|
} |
204 |
|
|
|
205 |
|
✗ |
void TransitionPlanner::pathProjector(const PathProjectorPtr_t pathProjector) { |
206 |
|
✗ |
innerProblem_->pathProjector(pathProjector); |
207 |
|
|
} |
208 |
|
|
|
209 |
|
✗ |
void TransitionPlanner::clearPathOptimizers() { pathOptimizers_.clear(); } |
210 |
|
|
|
211 |
|
|
/// Add a path optimizer |
212 |
|
✗ |
void TransitionPlanner::addPathOptimizer( |
213 |
|
|
const core::PathOptimizerPtr_t& pathOptimizer) { |
214 |
|
✗ |
pathOptimizers_.push_back(pathOptimizer); |
215 |
|
|
} |
216 |
|
|
|
217 |
|
✗ |
void TransitionPlanner::setParameter(const std::string& key, |
218 |
|
|
const core::Parameter& value) { |
219 |
|
✗ |
innerProblem_->setParameter(key, value); |
220 |
|
|
} |
221 |
|
|
|
222 |
|
✗ |
TransitionPlanner::TransitionPlanner(const core::ProblemConstPtr_t& problem, |
223 |
|
✗ |
const core::RoadmapPtr_t& roadmap) |
224 |
|
✗ |
: PathPlanner(problem, roadmap) { |
225 |
|
✗ |
ProblemConstPtr_t p(HPP_DYNAMIC_PTR_CAST(const Problem, problem)); |
226 |
|
✗ |
if (!p) |
227 |
|
✗ |
throw std::invalid_argument( |
228 |
|
✗ |
"The problem should be of type hpp::manipulation::Problem."); |
229 |
|
|
// create the inner problem |
230 |
|
✗ |
innerProblem_ = core::Problem::create(p->robot()); |
231 |
|
|
// Pass parameters from manipulation problem |
232 |
|
|
std::vector<std::string> keys( |
233 |
|
✗ |
p->parameters.getKeys<std::vector<std::string> >()); |
234 |
|
✗ |
for (auto k : keys) { |
235 |
|
✗ |
innerProblem_->setParameter(k, p->parameters.get(k)); |
236 |
|
|
} |
237 |
|
|
// Initialize config validations |
238 |
|
✗ |
innerProblem_->clearConfigValidations(); |
239 |
|
✗ |
innerProblem_->configValidations()->add( |
240 |
|
✗ |
hpp::core::CollisionValidation::create(p->robot())); |
241 |
|
✗ |
innerProblem_->configValidations()->add( |
242 |
|
✗ |
hpp::core::JointBoundValidation::create(p->robot())); |
243 |
|
|
// Add obstacles to inner problem |
244 |
|
✗ |
innerProblem_->collisionObstacles(p->collisionObstacles()); |
245 |
|
|
// Create default path planner |
246 |
|
✗ |
innerPlanner_ = hpp::core::pathPlanner::BiRrtStar::createWithRoadmap( |
247 |
|
✗ |
innerProblem_, roadmap); |
248 |
|
|
// Create default time parameterization |
249 |
|
|
timeParameterization_ = |
250 |
|
✗ |
core::pathOptimization::SimpleTimeParameterization::create(innerProblem_); |
251 |
|
|
} |
252 |
|
|
|
253 |
|
✗ |
void TransitionPlanner::init(TransitionPlannerWkPtr_t weak) { |
254 |
|
✗ |
core::PathPlanner::init(weak); |
255 |
|
✗ |
weakPtr_ = weak; |
256 |
|
|
} |
257 |
|
|
|
258 |
|
✗ |
graph::EdgePtr_t TransitionPlanner::getEdgeOrThrow(std::size_t id) const { |
259 |
|
✗ |
ProblemConstPtr_t p(HPP_DYNAMIC_PTR_CAST(const Problem, problem())); |
260 |
|
✗ |
assert(p); |
261 |
|
✗ |
graph::GraphComponentPtr_t comp(p->constraintGraph()->get(id).lock()); |
262 |
|
✗ |
graph::EdgePtr_t edge(HPP_DYNAMIC_PTR_CAST(graph::Edge, comp)); |
263 |
|
✗ |
if (!edge) { |
264 |
|
✗ |
std::ostringstream os; |
265 |
|
✗ |
os << "hpp::manipulation::pathPlanner::TransitionPlanner::setEdge: index " |
266 |
|
✗ |
<< id << " does not correspond to any edge of the constraint graph."; |
267 |
|
✗ |
throw std::logic_error(os.str().c_str()); |
268 |
|
|
} |
269 |
|
✗ |
return edge; |
270 |
|
|
} |
271 |
|
|
|
272 |
|
|
} // namespace pathPlanner |
273 |
|
|
} // namespace manipulation |
274 |
|
|
} // namespace hpp |
275 |
|
|
|