Class LTLPlanner
Defined in File LTLPlanner.h
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public ompl::base::Planner
(Class Planner)
Class Documentation
-
class LTLPlanner : public ompl::base::Planner
A planner for generating system trajectories to satisfy a logical specification given by an automaton, the propositions of which are defined over a decomposition of the system’s state space.
- Todo:
cite papers
ompl::base::Planner Interface
-
virtual void setup() override
Initializes LTLPlanner data structures.
-
virtual void clear() override
Clears all datastructures belonging to this LTLPlanner.
-
virtual base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override
Continues solving until a solution is found or a given planner termination condition is met. Returns true if a solution was found.
Public Functions
-
LTLPlanner(const LTLSpaceInformationPtr &si, ProductGraphPtr a, double exploreTime = 0.5)
Create an LTLPlanner with a given space and product graph. Accepts an optional third parameter to control how much time is spent promoting low-level tree exploration along a given high-level lead.
-
~LTLPlanner() override
Clears all memory belonging to this LTLPlanner .
-
void getTree(std::vector<base::State*> &tree) const
Helper debug method to access this planner’s underlying tree of states.
-
std::vector<ProductGraph::State*> getHighLevelPath(const std::vector<base::State*> &path, ProductGraph::State *start = nullptr) const
Helper debug method to return the sequence of high-level product graph states corresponding to a sequence of low-level continous system states, beginning from an optional initial high-level state.
Protected Functions
-
virtual double updateWeight(ProductGraph::State *as)
Updates and returns the weight of an abstraction state.
-
virtual void initAbstractInfo(ProductGraph::State *as)
Initializes the info object for a new high-level state.
-
virtual void buildAvail(const std::vector<ProductGraph::State*> &lead)
Compute a set of high-level states along a lead to be considered for expansion.
-
virtual bool explore(const std::vector<ProductGraph::State*> &lead, Motion *&soln, double duration)
Expand the tree of motions along a given lead for a given duration of time. Returns true if a solution was found, in which case the endpoint of the solution trajectory will be stored in the given Motion pointer. Otherwise, returns false.
-
virtual double abstractEdgeWeight(ProductGraph::State *a, ProductGraph::State *b) const
Returns the weight of an edge between two given high-level states, which we compute as the product of the reciprocals of the weights of the two states.
Protected Attributes
-
base::StateSamplerPtr sampler_
State sampler.
-
ControlSamplerPtr controlSampler_
Control sampler.
-
const LTLSpaceInformation *ltlsi_
Handle to the control::SpaceInformation object.
-
ProductGraphPtr abstraction_
The high level abstaction used to grow the tree structure.
-
PDF<ProductGraph::State*> availDist_
Used to sample nonempty regions in which to promote expansion.
-
ProductGraph::State *prodStart_ = {nullptr}
Start state in product graph.
-
double exploreTime_
Time to spend exploring each lead.
-
std::unordered_map<ProductGraph::State*, ProductGraphStateInfo> abstractInfo_
Map of abstraction states to their details.
-
struct Motion
Representation of a motion.
A motion contains pointers to its state, its parent motion, and the control that was applied to get from its parent to its state.
Public Functions
-
Motion(const SpaceInformation *si)
Constructor that allocates memory for the state and the control, given a space.
-
virtual ~Motion()
Motion destructor does not clear memory. Deletions should be performed by the LTLPlanner.
Public Members
-
unsigned int steps = {0}
The number of steps for which the control is applied.
-
ProductGraph::State *abstractState = {nullptr}
The high-level state to which this motion belongs.
-
Motion(const SpaceInformation *si)
-
struct ProductGraphStateInfo
A structure to hold measurement information for a high-level state, as well as the set of tree motions belonging to that high-level state. Exactly one ProductGraphStateInfo will exist for each ProductGraph::State.
Public Functions
-
ProductGraphStateInfo() = default
Creates an info object with no measurements and no tree motions.
-
ProductGraphStateInfo() = default