Classes | |
class | DistanceCheckerBase |
A base class for a distance checker. ObstacleDistance returns the radius of a L-z norm guaranteed to be collision-free. ObstacleDistanceNorm returns the value of z. More... | |
class | DynamicPath |
A bounded-velocity, bounded-acceleration trajectory consisting of parabolic ramps. More... | |
class | FeasibilityCheckerBase |
A base class for a feasibility checker. More... | |
class | ParabolicRamp |
class | ParabolicRamp1D |
Stores optimal trajectores for an acceleration and velocity-bounded 1D system. More... | |
class | ParabolicRampND |
Solves for optimal trajectores for a velocity-bounded ND system. More... | |
class | PLPRamp |
class | PPRamp |
class | RampFeasibilityChecker |
A class that encapsulates feaibility checking of a ParabolicRampND. More... | |
struct | RampSection |
class | RandomNumberGeneratorBase |
A custom random number generator that can be provided to DynamicPath::Shortcut() More... | |
class | Timer |
Typedefs | |
typedef double | Real |
typedef timeval | TimerCounterType |
typedef std::vector< double > | Vector |
Functions | |
Real | Abs (Real x) |
Real | BrakeAccel (Real x, Real v, Real xbound) |
Real | BrakeTime (Real x, Real v, Real xbound) |
bool | CheckRamp (const ParabolicRampND &ramp, FeasibilityCheckerBase *feas, DistanceCheckerBase *distance, int maxiters) |
Checks whether the ramp is feasible using exact checking. | |
bool | CheckRamp (const ParabolicRampND &ramp, FeasibilityCheckerBase *space, Real tol) |
void | CombineRamps (const std::vector< std::vector< ParabolicRamp1D > > &ramps, std::vector< ParabolicRampND > &ndramps) |
Combines an array of 1-d ramp sequences into a sequence of N-d ramps. | |
bool | FuzzyEquals (Real x, Real y, Real tol) |
bool | FuzzyZero (Real x, Real tol) |
bool | InBounds (const Vector &x, const Vector &bmin, const Vector &bmax) |
bool | IsFinite (Real x) |
bool | IsInf (Real x) |
Real | LInfDistance (const Vector &a, const Vector &b) |
bool | LoadRamp (FILE *f, Real &x0, Real &dx0, Real &x1, Real &dx1, Real &a, Real &v, Real &t) |
bool | LoadRamp (const char *fn, Real &x0, Real &dx0, Real &x1, Real &dx1, Real &a, Real &v, Real &t) |
Real | Max (Real x, Real y) |
Real | MaxBBLInfDistance (const Vector &x, const Vector &bmin, const Vector &bmax) |
Real | Min (Real x, Real y) |
int | quadratic (Real a, Real b, Real c, Real &x1, Real &x2) |
Real | Rand () |
bool | SaveRamp (const char *fn, Real x0, Real dx0, Real x1, Real dx1, Real a, Real v, Real t) |
Real | Sign (Real x) |
bool | SolveMinAccelBounded (Real x0, Real v0, Real x1, Real v1, Real endTime, Real vmax, Real xmin, Real xmax, std::vector< ParabolicRamp1D > &ramps) |
bool | SolveMinAccelBounded (const Vector &x0, const Vector &v0, const Vector &x1, const Vector &v1, Real endTime, const Vector &vmax, const Vector &xmin, const Vector &xmax, std::vector< std::vector< ParabolicRamp1D > > &ramps) |
bool | SolveMinAccelBounded (const Vector &x0, const Vector &v0, const Vector &x1, const Vector &v1, Real endTime, const Vector &vmax, const Vector &xmin, const Vector &xmax, vector< vector< ParabolicRamp1D > > &ramps) |
bool | SolveMinTime (const Vector &x0, const Vector &dx0, const Vector &x1, const Vector &dx1, const Vector &accMax, const Vector &velMax, const Vector &xMin, const Vector &xMax, DynamicPath &out) |
bool | SolveMinTimeBounded (Real x0, Real v0, Real x1, Real v1, Real amax, Real vmax, Real xmin, Real xmax, ParabolicRamp1D &ramp) |
Real | SolveMinTimeBounded (const Vector &x0, const Vector &v0, const Vector &x1, const Vector &v1, const Vector &amax, const Vector &vmax, const Vector &xmin, const Vector &xmax, std::vector< std::vector< ParabolicRamp1D > > &ramps) |
Real | SolveMinTimeBounded (const Vector &x0, const Vector &v0, const Vector &x1, const Vector &v1, const Vector &amax, const Vector &vmax, const Vector &xmin, const Vector &xmax, vector< vector< ParabolicRamp1D > > &ramps) |
Real | Sqr (Real x) |
Real | Sqrt (Real x) |
void | Swap (Real &x, Real &y) |
void | TestRamps (const char *fn) |
Variables | |
static const Real | EpsilonA = 1e-6 |
tolerance for acceleration equality | |
static const Real | EpsilonT = 1e-6 |
tolerance for time equality | |
static const Real | EpsilonV = 1e-5 |
tolerance for velocity equality | |
static const Real | EpsilonX = 1e-5 |
tolerance for position equality | |
static const bool | gErrorGetchar = true |
whether or not to pause on serious errors | |
static const bool | gErrorSave = true |
whether or not errors are logged to disk | |
static bool | gMinAccelQuiet = false |
static bool | gMinTime2Quiet = false |
static bool | gSuppressSavingRamps = false |
static const int | gValidityCheckLevel = 2 |
static const int | gVerbose = 2 |
static const Real | Inf = 1e300 |
typedef double ParabolicRamp::Real |
typedef timeval ParabolicRamp::TimerCounterType |
typedef std::vector<double> ParabolicRamp::Vector |
Real ParabolicRamp::Abs | ( | Real | x | ) | [inline] |
Real ParabolicRamp::BrakeAccel | ( | Real | x, |
Real | v, | ||
Real | xbound | ||
) | [inline] |
Definition at line 2272 of file ParabolicRamp.cpp.
Real ParabolicRamp::BrakeTime | ( | Real | x, |
Real | v, | ||
Real | xbound | ||
) | [inline] |
Definition at line 2267 of file ParabolicRamp.cpp.
bool ParabolicRamp::CheckRamp | ( | const ParabolicRampND & | ramp, |
FeasibilityCheckerBase * | feas, | ||
DistanceCheckerBase * | distance, | ||
int | maxiters | ||
) |
Checks whether the ramp is feasible using exact checking.
Definition at line 428 of file DynamicPath.cpp.
bool ParabolicRamp::CheckRamp | ( | const ParabolicRampND & | ramp, |
FeasibilityCheckerBase * | space, | ||
Real | tol | ||
) |
Checks whether the ramp is feasible using a piecewise linear approximation with tolerance tol
Definition at line 484 of file DynamicPath.cpp.
void ParabolicRamp::CombineRamps | ( | const std::vector< std::vector< ParabolicRamp1D > > & | ramps, |
std::vector< ParabolicRampND > & | ndramps | ||
) |
Combines an array of 1-d ramp sequences into a sequence of N-d ramps.
Definition at line 2661 of file ParabolicRamp.cpp.
bool ParabolicRamp::FuzzyEquals | ( | Real | x, |
Real | y, | ||
Real | tol | ||
) | [inline] |
bool ParabolicRamp::FuzzyZero | ( | Real | x, |
Real | tol | ||
) | [inline] |
bool ParabolicRamp::InBounds | ( | const Vector & | x, |
const Vector & | bmin, | ||
const Vector & | bmax | ||
) | [inline] |
Definition at line 53 of file DynamicPath.cpp.
bool ParabolicRamp::IsFinite | ( | Real | x | ) | [inline] |
bool ParabolicRamp::IsInf | ( | Real | x | ) | [inline] |
Real ParabolicRamp::LInfDistance | ( | const Vector & | a, |
const Vector & | b | ||
) | [inline] |
Definition at line 44 of file DynamicPath.cpp.
bool ParabolicRamp::LoadRamp | ( | FILE * | f, |
Real & | x0, | ||
Real & | dx0, | ||
Real & | x1, | ||
Real & | dx1, | ||
Real & | a, | ||
Real & | v, | ||
Real & | t | ||
) |
Definition at line 108 of file ParabolicRamp.cpp.
bool ParabolicRamp::LoadRamp | ( | const char * | fn, |
Real & | x0, | ||
Real & | dx0, | ||
Real & | x1, | ||
Real & | dx1, | ||
Real & | a, | ||
Real & | v, | ||
Real & | t | ||
) |
Definition at line 122 of file ParabolicRamp.cpp.
Real ParabolicRamp::Max | ( | Real | x, |
Real | y | ||
) | [inline] |
Real ParabolicRamp::MaxBBLInfDistance | ( | const Vector & | x, |
const Vector & | bmin, | ||
const Vector & | bmax | ||
) | [inline] |
Definition at line 62 of file DynamicPath.cpp.
Real ParabolicRamp::Min | ( | Real | x, |
Real | y | ||
) | [inline] |
int ParabolicRamp::quadratic | ( | Real | a, |
Real | b, | ||
Real | c, | ||
Real & | x1, | ||
Real & | x2 | ||
) |
Definition at line 48 of file ParabolicRamp.cpp.
Real ParabolicRamp::Rand | ( | ) | [inline] |
bool ParabolicRamp::SaveRamp | ( | const char * | fn, |
Real | x0, | ||
Real | dx0, | ||
Real | x1, | ||
Real | dx1, | ||
Real | a, | ||
Real | v, | ||
Real | t | ||
) |
Definition at line 88 of file ParabolicRamp.cpp.
Real ParabolicRamp::Sign | ( | Real | x | ) | [inline] |
bool ParabolicRamp::SolveMinAccelBounded | ( | Real | x0, |
Real | v0, | ||
Real | x1, | ||
Real | v1, | ||
Real | endTime, | ||
Real | vmax, | ||
Real | xmin, | ||
Real | xmax, | ||
std::vector< ParabolicRamp1D > & | ramps | ||
) |
Computes a sequence of up to three ramps connecting (x0,v0) to (x1,v1) in minimum-acceleration fashion with a fixed end time, under the given velocity and x bounds. Returns true if successful.
Definition at line 2279 of file ParabolicRamp.cpp.
bool ParabolicRamp::SolveMinAccelBounded | ( | const Vector & | x0, |
const Vector & | v0, | ||
const Vector & | x1, | ||
const Vector & | v1, | ||
Real | endTime, | ||
const Vector & | vmax, | ||
const Vector & | xmin, | ||
const Vector & | xmax, | ||
std::vector< std::vector< ParabolicRamp1D > > & | ramps | ||
) |
Vector version of above. Returns true if successful.
bool ParabolicRamp::SolveMinAccelBounded | ( | const Vector & | x0, |
const Vector & | v0, | ||
const Vector & | x1, | ||
const Vector & | v1, | ||
Real | endTime, | ||
const Vector & | vmax, | ||
const Vector & | xmin, | ||
const Vector & | xmax, | ||
vector< vector< ParabolicRamp1D > > & | ramps | ||
) |
Definition at line 2627 of file ParabolicRamp.cpp.
bool ParabolicRamp::SolveMinTime | ( | const Vector & | x0, |
const Vector & | dx0, | ||
const Vector & | x1, | ||
const Vector & | dx1, | ||
const Vector & | accMax, | ||
const Vector & | velMax, | ||
const Vector & | xMin, | ||
const Vector & | xMax, | ||
DynamicPath & | out | ||
) | [inline] |
Definition at line 72 of file DynamicPath.cpp.
bool ParabolicRamp::SolveMinTimeBounded | ( | Real | x0, |
Real | v0, | ||
Real | x1, | ||
Real | v1, | ||
Real | amax, | ||
Real | vmax, | ||
Real | xmin, | ||
Real | xmax, | ||
ParabolicRamp1D & | ramp | ||
) |
Computes a min-time ramp from (x0,v0) to (x1,v1) under the given acceleration, velocity, and x bounds. Returns true if successful.
Definition at line 2253 of file ParabolicRamp.cpp.
Real ParabolicRamp::SolveMinTimeBounded | ( | const Vector & | x0, |
const Vector & | v0, | ||
const Vector & | x1, | ||
const Vector & | v1, | ||
const Vector & | amax, | ||
const Vector & | vmax, | ||
const Vector & | xmin, | ||
const Vector & | xmax, | ||
std::vector< std::vector< ParabolicRamp1D > > & | ramps | ||
) |
Vector version of above. Returns the time of the minimum time trajectory, or -1 on failure
Real ParabolicRamp::SolveMinTimeBounded | ( | const Vector & | x0, |
const Vector & | v0, | ||
const Vector & | x1, | ||
const Vector & | v1, | ||
const Vector & | amax, | ||
const Vector & | vmax, | ||
const Vector & | xmin, | ||
const Vector & | xmax, | ||
vector< vector< ParabolicRamp1D > > & | ramps | ||
) |
Definition at line 2509 of file ParabolicRamp.cpp.
Real ParabolicRamp::Sqr | ( | Real | x | ) | [inline] |
Real ParabolicRamp::Sqrt | ( | Real | x | ) | [inline] |
void ParabolicRamp::Swap | ( | Real & | x, |
Real & | y | ||
) | [inline] |
void ParabolicRamp::TestRamps | ( | const char * | fn | ) |
Definition at line 132 of file ParabolicRamp.cpp.
const Real ParabolicRamp::EpsilonA = 1e-6 [static] |
const Real ParabolicRamp::EpsilonT = 1e-6 [static] |
const Real ParabolicRamp::EpsilonV = 1e-5 [static] |
const Real ParabolicRamp::EpsilonX = 1e-5 [static] |
const bool ParabolicRamp::gErrorGetchar = true [static] |
const bool ParabolicRamp::gErrorSave = true [static] |
bool ParabolicRamp::gMinAccelQuiet = false [static] |
Definition at line 42 of file ParabolicRamp.cpp.
bool ParabolicRamp::gMinTime2Quiet = false [static] |
Definition at line 45 of file ParabolicRamp.cpp.
bool ParabolicRamp::gSuppressSavingRamps = false [static] |
Definition at line 39 of file ParabolicRamp.cpp.
const int ParabolicRamp::gValidityCheckLevel = 2 [static] |
const int ParabolicRamp::gVerbose = 2 [static] |
const Real ParabolicRamp::Inf = 1e300 [static] |