| Line |
Branch |
Exec |
Source |
| 1 |
|
|
// |
| 2 |
|
|
// Copyright (c) 2014 CNRS |
| 3 |
|
|
// Authors: Florent Lamiraux |
| 4 |
|
|
// |
| 5 |
|
|
// This file is part of hpp_tutorial |
| 6 |
|
|
// hpp_tutorial is free software: you can redistribute it |
| 7 |
|
|
// and/or modify it under the terms of the GNU Lesser General Public |
| 8 |
|
|
// License as published by the Free Software Foundation, either version |
| 9 |
|
|
// 3 of the License, or (at your option) any later version. |
| 10 |
|
|
// |
| 11 |
|
|
// hpp_tutorial is distributed in the hope that it will be |
| 12 |
|
|
// useful, but WITHOUT ANY WARRANTY; without even the implied warranty |
| 13 |
|
|
// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU |
| 14 |
|
|
// General Lesser Public License for more details. You should have |
| 15 |
|
|
// received a copy of the GNU Lesser General Public License along with |
| 16 |
|
|
// hpp_tutorial If not, see |
| 17 |
|
|
// <http://www.gnu.org/licenses/>. |
| 18 |
|
|
|
| 19 |
|
|
#include <hpp/core/config-validations.hh> |
| 20 |
|
|
#include <hpp/core/configuration-shooter/uniform.hh> |
| 21 |
|
|
#include <hpp/core/connected-component.hh> |
| 22 |
|
|
#include <hpp/core/constraint-set.hh> |
| 23 |
|
|
#include <hpp/core/path-planner.hh> |
| 24 |
|
|
#include <hpp/core/path-validation.hh> |
| 25 |
|
|
#include <hpp/core/plugin.hh> |
| 26 |
|
|
#include <hpp/core/problem-solver.hh> |
| 27 |
|
|
#include <hpp/core/problem.hh> |
| 28 |
|
|
#include <hpp/core/roadmap.hh> |
| 29 |
|
|
#include <hpp/core/steering-method.hh> |
| 30 |
|
|
#include <hpp/util/pointer.hh> |
| 31 |
|
|
|
| 32 |
|
|
namespace hpp { |
| 33 |
|
|
namespace tutorial { |
| 34 |
|
|
// forward declaration of class Planner |
| 35 |
|
|
HPP_PREDEF_CLASS(Planner); |
| 36 |
|
|
// Planner objects are manipulated only via shared pointers |
| 37 |
|
|
typedef shared_ptr<Planner> PlannerPtr_t; |
| 38 |
|
|
typedef core::value_type value_type; |
| 39 |
|
|
|
| 40 |
|
|
/// Example of path planner |
| 41 |
|
|
class Planner : public core::PathPlanner { |
| 42 |
|
|
public: |
| 43 |
|
|
/// Create an instance and return a shared pointer to the instance |
| 44 |
|
✗ |
static PlannerPtr_t create(const core::ProblemConstPtr_t& problem, |
| 45 |
|
|
const core::RoadmapPtr_t& roadmap) { |
| 46 |
|
✗ |
Planner* ptr = new Planner(problem, roadmap); |
| 47 |
|
✗ |
PlannerPtr_t shPtr(ptr); |
| 48 |
|
✗ |
ptr->init(shPtr); |
| 49 |
|
✗ |
return shPtr; |
| 50 |
|
|
} |
| 51 |
|
|
|
| 52 |
|
|
/// One step of extension. |
| 53 |
|
|
/// |
| 54 |
|
|
/// This method implements one step of your algorithm. The method |
| 55 |
|
|
/// will be called iteratively until one goal configuration is accessible |
| 56 |
|
|
/// from the initial configuration. |
| 57 |
|
|
/// |
| 58 |
|
|
/// We will see how to implement a basic PRM algorithm. |
| 59 |
|
✗ |
virtual void oneStep() { |
| 60 |
|
|
using core::NodePtr_t; |
| 61 |
|
|
using core::PathPtr_t; |
| 62 |
|
|
// Retrieve the robot the problem has been defined for. |
| 63 |
|
✗ |
pinocchio::DevicePtr_t robot(problem()->robot()); |
| 64 |
|
|
// Retrieve the path validation algorithm associated to the problem |
| 65 |
|
✗ |
core::PathValidationPtr_t pathValidation(problem()->pathValidation()); |
| 66 |
|
|
// Retrieve configuration validation methods associated to the problem |
| 67 |
|
|
core::ConfigValidationsPtr_t configValidations( |
| 68 |
|
✗ |
problem()->configValidations()); |
| 69 |
|
|
// Retrieve the steering method |
| 70 |
|
✗ |
core::SteeringMethodPtr_t sm(problem()->steeringMethod()); |
| 71 |
|
|
// Retrieve the constraints the robot is subject to |
| 72 |
|
✗ |
core::ConstraintSetPtr_t constraints(problem()->constraints()); |
| 73 |
|
|
// Retrieve roadmap of the path planner |
| 74 |
|
✗ |
core::RoadmapPtr_t r(roadmap()); |
| 75 |
|
|
// shoot a valid random configuration |
| 76 |
|
✗ |
core::Configuration_t qrand(robot->configSize()); |
| 77 |
|
|
// Report of configuration validation: unused here |
| 78 |
|
✗ |
core::ValidationReportPtr_t validationReport; |
| 79 |
|
|
do { |
| 80 |
|
✗ |
shooter_->shoot(qrand); |
| 81 |
|
✗ |
} while (!configValidations->validate(qrand, validationReport)); |
| 82 |
|
|
// Add qrand as a new node |
| 83 |
|
✗ |
NodePtr_t newNode = r->addNode(qrand); |
| 84 |
|
|
// try to connect the random configuration to each connected component |
| 85 |
|
|
// of the roadmap. |
| 86 |
|
|
|
| 87 |
|
|
// Modifying the connected components of the graph while making a loop |
| 88 |
|
|
// over all of them is not correct. We therefore record the edges to |
| 89 |
|
|
// to insert and add them after the loop. |
| 90 |
|
|
typedef std::tuple<NodePtr_t, NodePtr_t, PathPtr_t> DelayedEdge_t; |
| 91 |
|
|
typedef std::vector<DelayedEdge_t> DelayedEdges_t; |
| 92 |
|
✗ |
DelayedEdges_t delayedEdges; |
| 93 |
|
✗ |
for (auto cc : r->connectedComponents()) { |
| 94 |
|
|
// except its own connected component of course |
| 95 |
|
✗ |
if (cc != newNode->connectedComponent()) { |
| 96 |
|
|
value_type d; |
| 97 |
|
|
// Get nearest node to qrand in connected component |
| 98 |
|
✗ |
NodePtr_t nearest = r->nearestNode(qrand, cc, d); |
| 99 |
|
✗ |
core::Configuration_t qnear = nearest->configuration(); |
| 100 |
|
|
// Create local path between qnear and qrand |
| 101 |
|
✗ |
PathPtr_t localPath = (*sm)(qnear, qrand); |
| 102 |
|
|
// validate local path |
| 103 |
|
✗ |
PathPtr_t validPart; |
| 104 |
|
|
// report on path validation: unused here |
| 105 |
|
✗ |
core::PathValidationReportPtr_t report; |
| 106 |
|
✗ |
if (pathValidation->validate(localPath, false, validPart, report)) { |
| 107 |
|
|
// Create node and edges with qrand and the local path |
| 108 |
|
✗ |
delayedEdges.push_back(DelayedEdge_t(nearest, newNode, localPath)); |
| 109 |
|
|
} |
| 110 |
|
|
} |
| 111 |
|
|
} |
| 112 |
|
✗ |
for (auto de : delayedEdges) { |
| 113 |
|
✗ |
r->addEdge(std::get<0>(de), std::get<1>(de), std::get<2>(de)); |
| 114 |
|
✗ |
r->addEdge(std::get<1>(de), std::get<0>(de), std::get<2>(de)->reverse()); |
| 115 |
|
|
} |
| 116 |
|
|
} |
| 117 |
|
|
|
| 118 |
|
|
protected: |
| 119 |
|
|
/// Protected constructor |
| 120 |
|
|
/// Users need to call Planner::create in order to create instances. |
| 121 |
|
✗ |
Planner(const core::ProblemConstPtr_t& problem, |
| 122 |
|
|
const core::RoadmapPtr_t& roadmap) |
| 123 |
|
✗ |
: core::PathPlanner(problem, roadmap), |
| 124 |
|
✗ |
shooter_( |
| 125 |
|
✗ |
core::configurationShooter::Uniform::create(problem->robot())) {} |
| 126 |
|
|
/// Store weak pointer to itself |
| 127 |
|
✗ |
void init(const PlannerWkPtr_t& weak) { |
| 128 |
|
✗ |
core::PathPlanner::init(weak); |
| 129 |
|
✗ |
weakPtr_ = weak; |
| 130 |
|
|
} |
| 131 |
|
|
|
| 132 |
|
|
private: |
| 133 |
|
|
/// Configuration shooter to uniformly shoot random configurations |
| 134 |
|
|
core::configurationShooter::UniformPtr_t shooter_; |
| 135 |
|
|
/// weak pointer to itself |
| 136 |
|
|
PlannerWkPtr_t weakPtr_; |
| 137 |
|
|
}; // class Planner |
| 138 |
|
|
|
| 139 |
|
|
class Plugin : public core::ProblemSolverPlugin { |
| 140 |
|
|
public: |
| 141 |
|
✗ |
Plugin() : ProblemSolverPlugin("TutorialPlugin", "0.0") {} |
| 142 |
|
|
|
| 143 |
|
|
protected: |
| 144 |
|
✗ |
virtual bool impl_initialize(core::ProblemSolverPtr_t ps) { |
| 145 |
|
✗ |
ps->pathPlanners.add("TutorialPRM", Planner::create); |
| 146 |
|
✗ |
return true; |
| 147 |
|
|
} |
| 148 |
|
|
}; // class Plugin |
| 149 |
|
|
} // namespace tutorial |
| 150 |
|
|
} // namespace hpp |
| 151 |
|
|
|
| 152 |
|
✗ |
HPP_CORE_DEFINE_PLUGIN(hpp::tutorial::Plugin) |
| 153 |
|
|
|