Loading...
Searching...
No Matches
AOXRRTConnect.h
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
Definition RandomNumbers.h:57
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition Cost.h:48
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
Definition PlannerTerminationCondition.h:64
virtual void clear()
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...
Definition Planner.cpp:118
void setup() override
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...
Definition AOXRRTConnect.cpp:62
void setRange(double distance)
Set the range the planner is supposed to use.
Definition AOXRRTConnect.h:105
void setNearestNeighbors()
Set a different nearest neighbors datastructure.
Definition AOXRRTConnect.h:118
long int maxResampleAttempts_
Maximum allowed cost resampling iterations before moving on.
Definition AOXRRTConnect.h:245
Motion * findNeighbour(Motion *sampled_motion, float rootDist, TreeData &tree)
Find a valid neighbour with asymmetric distance funtion via iteration.
Definition AOXRRTConnect.cpp:166
double aoxDistanceFunction(const Motion *a, const Motion *b) const
Compute AOX distance between motions.
Definition AOXRRTConnect.h:205
std::size_t maxInternalSamplesIncrement
Increment by which maxSamples is increased.
Definition AOXRRTConnect.h:257
std::size_t maxInternalVertices
Maximum allowed total vertices in trees before the search is restarted.
Definition AOXRRTConnect.h:248
std::pair< base::State *, base::State * > connectionPoint_
The pair of states in each tree connected during planning. Used for PlannerData computation.
Definition AOXRRTConnect.h:278
std::size_t maxInternalVerticesIncrement
Increment by which maxVertices is increased.
Definition AOXRRTConnect.h:251
std::size_t maxInternalSamples
Maximum samples tried before the search is restarted.
Definition AOXRRTConnect.h:254
bool startTree_
A flag that toggles between expanding the start tree (true) or goal tree (false).
Definition AOXRRTConnect.h:239
bool internalResetCondition()
Check if the inner loop planner met its condition to terminate.
Definition AOXRRTConnect.h:129
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...
Definition AOXRRTConnect.cpp:302
double euclideanDistanceFunction(const Motion *a, const Motion *b) const
Compute euclidian distance between motions.
Definition AOXRRTConnect.h:199
std::shared_ptr< NearestNeighbors< Motion * > > TreeData
A nearest-neighbor datastructure representing a tree of motions.
Definition AOXRRTConnect.h:174
GrowState growTree(TreeData &tree, TreeGrowingInfo &tgi, Motion *rmotion)
Grow a tree towards a random state.
Definition AOXRRTConnect.cpp:195
base::PlannerTerminationCondition _ptc
Outer loop termination condition for AORRTC.
Definition AOXRRTConnect.h:269
double maxDistance_
The maximum length of a motion to be added to a tree.
Definition AOXRRTConnect.h:242
This namespace contains code that is specific to planning under geometric constraints.
Definition GeneticSearch.h:48
Main namespace. Contains everything in this library.
Definition MultiLevelPlanarManipulatorDemo.cpp:66
A class to store the exit status of Planner::solve().
Definition PlannerStatus.h:49
Information attached to growing a tree of motions (used internally).
Definition AOXRRTConnect.h:178