LightningRetrieveRepair.h
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2014, 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_GEOMETRIC_PLANNERS_EXPERIENCE_LIGHTNING_RETRIEVE_REPAIR_
38 #define OMPL_GEOMETRIC_PLANNERS_EXPERIENCE_LIGHTNING_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 
45 namespace ompl
46 {
47  namespace tools
48  {
49  OMPL_CLASS_FORWARD(LightningDB);
50  }
51 
52  namespace geometric
53  {
55 
56  OMPL_CLASS_FORWARD(LightningRetrieveRepair);
58 
76  class LightningRetrieveRepair : public base::Planner
77  {
78  public:
80  LightningRetrieveRepair(const base::SpaceInformationPtr &si, tools::LightningDBPtr experienceDB);
81 
82  ~LightningRetrieveRepair() override;
83 
86  void getPlannerData(base::PlannerData &data) const override;
87 
92  const std::vector<base::PlannerDataPtr> &getLastRecalledNearestPaths() const;
93 
98  std::size_t getLastRecalledNearestPathChosen() const;
99 
104  base::PlannerDataPtr getChosenRecallPath() const;
105 
107  void getRepairPlannerDatas(std::vector<base::PlannerDataPtr> &data) const;
108 
110 
111  void clear() override;
112 
114  void setLightningDB(const tools::LightningDBPtr &experienceDB);
115 
117  void setRepairPlanner(const base::PlannerPtr &planner);
118 
119  void setup() override;
120 
128 
136  bool replan(const base::State *start, const base::State *goal, geometric::PathGeometric &newPathSegment,
138 
142  int getNumNearestSolutions() const
143  {
144  return nearestK_;
145  }
146 
150  void setNumNearestSolutions(int nearestK)
151  {
152  nearestK_ = nearestK;
153  }
154 
155  protected:
163  std::size_t checkMotionScore(const base::State *s1, const base::State *s2) const;
164 
170  bool findBestPath(const base::State *startState, const base::State *goalState,
171  base::PlannerDataPtr &chosenPath);
172 
174  tools::LightningDBPtr experienceDB_;
175 
177  std::vector<base::PlannerDataPtr> nearestPaths_;
178 
180  std::size_t nearestPathsChosenID_;
181 
183  base::PlannerPtr repairPlanner_;
184 
186  base::ProblemDefinitionPtr repairProblemDef_;
187 
189  std::vector<base::PlannerDataPtr> repairPlannerDatas_;
190 
192  geometric::PathSimplifierPtr psk_;
193 
195  int nearestK_;
196  };
197  }
198 }
199 
200 #endif
void setLightningDB(const tools::LightningDBPtr &experienceDB)
Pass a pointer of the database from the lightning framework.
std::size_t getLastRecalledNearestPathChosen() const
Get debug information about the top recalled paths that were chosen for further filtering.
void setRepairPlanner(const base::PlannerPtr &planner)
Set the planner that will be used for repairing invalid paths recalled from experience.
bool findBestPath(const base::State *startState, const base::State *goalState, base::PlannerDataPtr &chosenPath)
Filters the top n paths in nearestPaths_ to the top 1, based on state validity with current environme...
void getPlannerData(base::PlannerData &data) const override
Get information about the exploration data structure the planning from scratch motion planner used.
std::size_t nearestPathsChosenID_
the ID within nearestPaths_ of the path that was chosen for repair
geometric::PathSimplifierPtr psk_
The instance of the path simplifier.
Definition of an abstract state.
Definition: State.h:113
base::PlannerPtr repairPlanner_
A secondary planner for replanning.
base::PlannerDataPtr getChosenRecallPath() const
Get the chosen path used from database for repair.
std::vector< base::PlannerDataPtr > repairPlannerDatas_
Debug the repair planner by saving its planner data each time it is used.
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 > nearestPaths_
Recall the nearest paths and store this in planner data for introspection later.
int nearestK_
Number of 'k' close solutions to choose from database for further filtering.
void setNumNearestSolutions(int nearestK)
Setter for number of 'k' close solutions to choose from database for further filtering.
Definition of a geometric path.
Definition: PathGeometric.h:97
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
tools::LightningDBPtr experienceDB_
The database of motions to search through.
A class to store the exit status of Planner::solve()
const std::vector< base::PlannerDataPtr > & getLastRecalledNearestPaths() const
Get debug information about the top recalled paths that were chosen for further filtering.
bool repairPath(const base::PlannerTerminationCondition &ptc, geometric::PathGeometric &primaryPath)
Repairs a path to be valid in the current planning environment.
void getRepairPlannerDatas(std::vector< base::PlannerDataPtr > &data) const
Get information about the exploration data structure the repair motion planner used each call.
bool replan(const base::State *start, const base::State *goal, geometric::PathGeometric &newPathSegment, const base::PlannerTerminationCondition &ptc)
Use our secondary planner to find a valid path between start and goal, and return that path.
LightningRetrieveRepair(const base::SpaceInformationPtr &si, tools::LightningDBPtr experienceDB)
Constructor.
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
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...
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...
int getNumNearestSolutions() const
Getter for number of 'k' close solutions to choose from database for further filtering.
Main namespace. Contains everything in this library.
Definition: AppBase.h:21