KrisLibrary  1.0.0
Classes
MotionPlanning

Classes to assist in motion planning. More...

Classes

class  HaltingCondition
 A termination condition for a planner. Supports max iteration count, time limit, absolute cost, and cost improvement conditions. More...
 
class  MotionPlannerInterface
 An abstract class for a sample-based motion planner. More...
 
class  ControlSpace
 Encodes the dynamics of a system, including the dynamics function f(x,u), control bounds, and available steering functions. More...
 
class  ReversibleControlSpace
 
class  SteeringFunction
 A function in a ControlSpace that attempts to connect two states with a sequence of one or more controls. More...
 
class  IntegratedControlSet
 A cartesian-product control space in which groups of states are controlled by individual control spaces. More...
 
class  CSet
 A subset of a CSpace, which establishes a constraint for a configuration to be feasible. More...
 
class  BoxSet
 
class  AxisRangeSet
 
class  CSpace
 Motion planning configuration space base class. The configuration space implements an interpolation space with obstacles. To implement obstacles, the user will create some CSets (or predicates) and add them via the AddConstraint method. More...
 
class  GeodesicCSpace
 
class  GeodesicCSpaceAdaptor
 
class  CartesianCSpace
 
class  BoxCSpace
 
class  MultiCSpace
 
class  DensityEstimatorBase
 A base class for density estimators. Each point in an N dimensional space is attached to some data pointer. Density in the space is measured by the Density() function, and only matters in a relative sense. More...
 
class  GridDensityEstimator
 A grid-based (n-d projected histogram) density estimator. More...
 
class  MultiGridDensityEstimator
 A multiple-grid based density estimator that attempts to avoid data fragmentation by collecting histograms on multiple axes and fusing them together. More...
 
class  KernelDensityEstimator
 a Kernel Density Estimation density estimator. More...
 
class  EdgePlanner
 Abstract base class for an edge planner / edge checker (i.e., local planner). More...
 
class  EdgeChecker
 An EdgePlanner that just checks a given interpolator or straight line path between two configurations. More...
 
class  EpsilonEdgeChecker
 Edge checker that divides the path until epsilon resolution is reached. More...
 
class  ObstacleDistanceEdgeChecker
 Edge checker that divides the path until the segment distance is below CSpace.ObstacleDistance() More...
 
class  BisectionEpsilonEdgePlanner
 
class  PathEdgeChecker
 An edge checker that checks a sequence of edges. More...
 
class  MultiEdgePlanner
 An edge planners that plans a stacked list of edges. More...
 
class  IncrementalizedEdgePlanner
 An incremental edge planner that calls a non-incremental edge planner. This adapts one-shot edge planners to be used in lazy motion planners. More...
 
class  GeneralizedCubicBezierCurve
 A generalized Bezier curve that uses the CSpace's Interpolate routine to generate the smooth interpolation. More...
 
class  GeneralizedCubicBezierSpline
 A Bezier spline with segment durations. More...
 
class  Interpolator
 A base class for all 1D interpolators. More...
 
class  ReverseInterpolator
 An interpolator that reverses another one. More...
 
class  LinearInterpolator
 An interpolator that goes between two Configs. More...
 
class  GeodesicInterpolator
 An interpolator that uses a GeodesicSpace's Interpolate function. More...
 
class  CSpaceInterpolator
 An interpolator that uses a CSpace's Interpolate function. More...
 
class  TimeRemappedInterpolator
 An interpolator that remaps a time interval of another interpolator. Maps the parameter range [pstart,pend] (by default [0,1]) to the range [a,b] on the base interpolator. More...
 
class  PathInterpolator
 An interpolator that concatenates a list of other interpolators. The interpolators may have nonuniform duration. More...
 
class  MultiInterpolator
 A cartesian product of interpolators. More...
 
class  KinodynamicSpace
 A class used for kinodynamic planning. Combines a CSpace defining the state space, as well as a ControlSpace. More...
 
class  IntegratedKinodynamicSpace
 A class that produces a KinodynamicCSpace from a dynamics function subclassed from IntegratedControlSpace. Collision checking is performed at the integration resolution given in the dynamics function. More...
 
class  RandomBiasSteeringFunction
 A simple approximate steering function that simply draws several samples and picks the closest one in terms of CSpace distance. More...
 
class  RandomBiasReverseSteeringFunction
 A simple approximate steering function that simply draws several samples and picks the closest one in terms of CSpace distance. More...
 
class  RoadmapPlanner
 A base roadmap planner class. More...
 
class  TreeRoadmapPlanner
 A base class to be used for tree-based roadmap planners. More...
 
class  PerturbationTreePlanner
 A tree-based randomized planner that extends the roadmap by sampling the neighborhood of existing samples. More...
 
class  RRTPlanner
 A basic RRT (Rapidly-Exploring Random Tree) planner. More...
 
class  BidirectionalRRTPlanner
 A single-query RRT (Rapidly-Exploring Random Tree) planner. More...
 
class  MultiModalCSpace< Mode >
 Multi-modal configuration space base class. More...
 
class  ObjectiveFunctionalBase
 A base class for objective functionals of the form J[x,u] = sum_0^N-1 L(xi,ui) dt + Phi(xN) More...
 
class  IntegratorObjectiveFunctional
 A cost functional of the form J[x,u] = int_0^T L(x(t),u(t)) dt + Phi(x(T)) More...
 
class  LengthObjective
 An objective that measures path length. More...
 
class  TimeObjective
 An objective that measures path execution time. Accumulated time is assumed to be part of the state, specifically the element indexed by timeIndex. More...
 
class  MilestonePath
 A sequence of locally planned paths between milestones. More...
 
class  PRTPlanner
 The PRT (Probabilistic Roadmap of Trees) planner. More...
 
class  SBLPlanner
 The SBL motion planner. More...
 
class  SBLTree
 A tree of configurations to be used in the SBL motion planner. More...
 
class  SBLTreeWithIndex
 An SBLTree with a node index. More...
 
class  SBLTreeWithGrid
 An SBL motion planner that uses a SBLSubdivision to pick the next node to expand, and nodes to connect. More...
 
class  SpaceTimeCSpace
 A cspace that prepends a time variable to the given CSpace. This is best used with perturbation-sampling planners, and/or SpaceTimeIntegratedKinodynamicCSpace. More...
 
class  SpaceTimeIntegratedKinodynamicSpace
 This KinodynamicCSpace prefixes time onto the state of the given CSpace instance and automatically increments the time state variable as the dynamics are integrated forward. More...
 

Detailed Description

Classes to assist in motion planning.