ompl::geometric Namespace Reference

This namespace contains code that is specific to planning under geometric constraints. More...

Classes

class  BasicPRM
 Probabilistic RoadMap planner. More...
class  BKPIECE1
 Bi-directional KPIECE with one level of discretization. More...
class  Discretization
 One-level discretization used for KPIECE. More...
class  EST
 Expansive Space Trees. More...
class  GAIK
 Inverse Kinematics with Genetic Algorithms. More...
class  HCIK
 Inverse Kinematics with Hill Climbing. More...
class  KPIECE1
 Kinematic Planning by Interior-Exterior Cell Exploration. More...
class  LazyRRT
 Lazy RRT. More...
class  LBKPIECE1
 Lazy Bi-directional KPIECE with one level of discretization. More...
class  PathGeometric
 Definition of a geometric path. More...
class  PathSimplifier
 This class contains routines that attempt to simplify geometric paths. More...
class  PathSimplifierPtr
 A boost shared pointer wrapper for ompl::geometric::PathSimplifier. More...
class  pRRT
 Parallel RRT. More...
class  pSBL
 Parallel Single-query Bi-directional Lazy collision checking planner. More...
class  RRT
 Rapidly-exploring Random Trees. More...
class  RRTConnect
 RRT-Connect (RRTConnect). More...
class  SBL
 Single-Query Bi-Directional Probabilistic Roadmap Planner with Lazy Collision Checking. More...
class  SimpleSetup
 Create the set of classes typically needed to solve a geometric problem. More...

Functions

void checkMotionLength (const base::Planner *planner, double &length)
 Check if motion length is strictly positive. If not, set it to a default value.
void checkProjectionEvaluator (const base::Planner *planner, base::ProjectionEvaluatorPtr &proj)
 Check if projection evaluator is defined properly. If not, attempt to use default.
 ClassForward (PathSimplifier)
 Forward declaration of ompl::geometric::PathSimplifier.
base::PlannerPtr getDefaultPlanner (const base::GoalPtr &goal)
 Given a goal specification, decide on a planner for that goal.

Detailed Description

This namespace contains code that is specific to planning under geometric constraints.


Function Documentation

void ompl::geometric::checkMotionLength ( const base::Planner *  planner,
double &  length 
)

Check if motion length is strictly positive. If not, set it to a default value.

void ompl::geometric::checkProjectionEvaluator ( const base::Planner *  planner,
base::ProjectionEvaluatorPtr &  proj 
)

Check if projection evaluator is defined properly. If not, attempt to use default.

ompl::geometric::ClassForward ( PathSimplifier   ) 

Forward declaration of ompl::geometric::PathSimplifier.

base::PlannerPtr ompl::geometric::getDefaultPlanner ( const base::GoalPtr &  goal  ) 

Given a goal specification, decide on a planner for that goal.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


ompl
Author(s): Ioan Sucan/isucan@rice.edu, Mark Moll/mmoll@rice.edu, Lydia Kavraki/kavraki@rice.edu
autogenerated on Fri Jan 11 09:34:02 2013