ThunderRetrieveRepair.h
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2013, University of Colorado, Boulder
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 the Univ of CO, Boulder 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: Dave Coleman */
36
37#ifndef OMPL_TOOLS_THUNDER_THUNDER_RETRIEVE_REPAIR_
38#define OMPL_TOOLS_THUNDER_THUNDER_RETRIEVE_REPAIR_
39
40#include <ompl/geometric/planners/PlannerIncludes.h>
41#include <ompl/geometric/PathGeometric.h>
42#include <ompl/geometric/PathSimplifier.h>
43#include <ompl/datastructures/NearestNeighbors.h>
44
45namespace ompl
46{
47 namespace tools
48 {
49 OMPL_CLASS_FORWARD(ThunderDB);
50 }
51
52 namespace geometric
53 {
55
56 OMPL_CLASS_FORWARD(ThunderRetrieveRepair);
58
77 {
78 public:
80 ThunderRetrieveRepair(const base::SpaceInformationPtr &si, tools::ThunderDBPtr experienceDB);
81
82 ~ThunderRetrieveRepair() override;
83
86 void getPlannerData(base::PlannerData &data) const override;
87
92 const std::vector<PathGeometric> &getLastRecalledNearestPaths() const;
93
98 std::size_t getLastRecalledNearestPathChosen() const;
99
104 const PathGeometric &getChosenRecallPath() const;
105
107 void getRepairPlannerDatas(std::vector<base::PlannerDataPtr> &data) const;
108
110
111 void clear() override;
112
116 void setExperienceDB(const tools::ThunderDBPtr &experienceDB);
117
119 void setRepairPlanner(const base::PlannerPtr &planner);
120
121 void setup() override;
122
128 bool repairPath(const base::PlannerTerminationCondition &ptc, PathGeometric &primaryPath);
129
137 bool replan(const base::State *start, const base::State *goal, PathGeometric &newPathSegment,
139
141 int getNearestK() const
142 {
143 return nearestK_;
144 }
145
147 void setNearestK(int nearestK)
148 {
149 nearestK_ = nearestK;
150 }
151
153 void enableSmoothing(bool enable)
154 {
155 smoothingEnabled_ = enable;
156 }
157
158 protected:
166 std::size_t checkMotionScore(const base::State *s1, const base::State *s2) const;
167
169 void freeMemory();
170
172 tools::ThunderDBPtr experienceDB_;
173
175 std::vector<PathGeometric> nearestPaths_;
176
179
181 base::PlannerPtr repairPlanner_;
182
184 base::ProblemDefinitionPtr repairProblemDef_;
185
187 std::vector<base::PlannerDataPtr> repairPlannerDatas_;
188
191
194
197 };
198
199 } // namespace geometric
200} // namespace ompl
201
202#endif
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...
Definition: PlannerData.h:175
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
Base class for a planner.
Definition: Planner.h:223
Definition of an abstract state.
Definition: State.h:50
Definition of a geometric path.
Definition: PathGeometric.h:66
A shared pointer wrapper for ompl::geometric::PathSimplifier.
The Thunder Framework's Retrieve-Repair component.
void setExperienceDB(const tools::ThunderDBPtr &experienceDB)
Pass a pointer of the database from the thunder framework.
int nearestK_
Number of 'k' close solutions to choose from database for further filtering.
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
const std::vector< PathGeometric > & getLastRecalledNearestPaths() const
Get debug information about the top recalled paths that were chosen for further filtering.
int getNearestK() const
Getter for number of 'k' close solutions to choose from database for further filtering.
std::size_t getLastRecalledNearestPathChosen() const
Get debug information about the top recalled paths that were chosen for further filtering.
bool repairPath(const base::PlannerTerminationCondition &ptc, PathGeometric &primaryPath)
Repairs a path to be valid in the current planning environment.
bool replan(const base::State *start, const base::State *goal, PathGeometric &newPathSegment, const base::PlannerTerminationCondition &ptc)
Use our secondary planner to find a valid path between start and goal, and return that path.
std::size_t nearestPathsChosenID_
the ID within nearestPaths_ of the path that was chosen for repair
void setNearestK(int nearestK)
Setter for number of 'k' close solutions to choose from database for further filtering.
void enableSmoothing(bool enable)
Optionally smooth retrieved and repaired paths from database.
bool smoothingEnabled_
Optionally smooth retrieved and repaired paths from database.
base::PlannerPtr repairPlanner_
A secondary planner for replanning.
std::vector< PathGeometric > nearestPaths_
Recall the nearest paths and store this in planner data for introspection later.
base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override
Function that can solve the motion planning problem. This function can be called multiple times on th...
std::size_t checkMotionScore(const base::State *s1, const base::State *s2) const
Count the number of states along the discretized path that are in collision Note: This is kind of an ...
std::vector< base::PlannerDataPtr > repairPlannerDatas_
Debug the repair planner by saving its planner data each time it is used.
void getPlannerData(base::PlannerData &data) const override
Get information about the exploration data structure the planning from scratch motion planner used.
void freeMemory()
Free the memory allocated by this planner.
ThunderRetrieveRepair(const base::SpaceInformationPtr &si, tools::ThunderDBPtr experienceDB)
Constructor.
base::ProblemDefinitionPtr repairProblemDef_
A secondary problem definition for the repair planner to use.
void clear() override
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
tools::ThunderDBPtr experienceDB_
The database of motions to search through.
void setRepairPlanner(const base::PlannerPtr &planner)
Set the planner that will be used for repairing invalid paths recalled from experience.
void getRepairPlannerDatas(std::vector< base::PlannerDataPtr > &data) const
Get information about the exploration data structure the repair motion planner used each call.
const PathGeometric & getChosenRecallPath() const
Get the chosen path used from database for repair.
PathSimplifierPtr path_simplifier_
The instance of the path simplifier.
Main namespace. Contains everything in this library.
A class to store the exit status of Planner::solve()
Definition: PlannerStatus.h:49