trajectory_collection
Classes | Typedefs | Enumerations | Functions
TrajColl Namespace Reference

Classes

class  BangBangInterpolator
 Interpolator with bang-bang control. More...
 
struct  BoundaryConstraint
 Boundary constraint. More...
 
class  Constant
 Constant function. More...
 
class  CubicHermiteSpline
 Cubic Hermite spline. More...
 
class  CubicInterpolator
 Cubic interpolator. More...
 
class  CubicSpline
 Cubic spline. More...
 
class  Func
 Mathematical function. More...
 
class  Interpolator
 Interpolator of a sequence of waypoints. More...
 
class  PiecewiseFunc
 Piecewise function. More...
 
class  Polynomial
 Polynomial function. More...
 

Typedefs

template<class T >
using LinearPolynomial = Polynomial< T, 1 >
 Linear polynomial function. More...
 
template<class T >
using QuadraticPolynomial = Polynomial< T, 2 >
 Quadratic polynomial function. More...
 
template<class T >
using CubicPolynomial = Polynomial< T, 3 >
 Cubic polynomial function. More...
 

Enumerations

enum  BoundaryConstraintType { BoundaryConstraintType::Velocity = 0, BoundaryConstraintType::Acceleration }
 Type of boundary constraint. More...
 

Functions

template<class T >
interpolate (const T &start, const T &end, double ratio)
 Calculate the value interpolating from start to end. More...
 
template<>
Eigen::Quaterniond interpolate (const Eigen::Quaterniond &start, const Eigen::Quaterniond &end, double ratio)
 Calculate the Quaternion interpolating from start to end. More...
 
template<>
Eigen::Matrix3d interpolate (const Eigen::Matrix3d &start, const Eigen::Matrix3d &end, double ratio)
 Calculate the 3D matrix interpolating from start to end. More...
 
template<>
sva::PTransformd interpolate (const sva::PTransformd &start, const sva::PTransformd &end, double ratio)
 Calculate the pose interpolating from start to end. More...
 
template<class T , class U = T>
interpolateDerivative (const T &start, const T &end, double, int order=1)
 Calculate the derivative value interpolating from start to end. More...
 
template<>
double interpolateDerivative (const double &start, const double &end, double, int order)
 Calculate the derivative of scalar value interpolating from start to end. More...
 
template<>
Eigen::Vector3d interpolateDerivative (const Eigen::Quaterniond &start, const Eigen::Quaterniond &end, double, int order)
 Calculate the derivative of Quaternion interpolating from start to end. More...
 
template<>
Eigen::Vector3d interpolateDerivative (const Eigen::Matrix3d &start, const Eigen::Matrix3d &end, double, int order)
 Calculate the derivative of 3D matrix interpolating from start to end. More...
 
template<>
sva::MotionVecd interpolateDerivative (const sva::PTransformd &start, const sva::PTransformd &end, double, int order)
 Calculate the derivative of pose interpolating from start to end. More...
 
template<>
sva::ForceVecd interpolateDerivative (const sva::ForceVecd &start, const sva::ForceVecd &end, double, int order)
 Calculate the derivative of wrench interpolating from start to end. More...
 

Typedef Documentation

◆ CubicPolynomial

template<class T >
using TrajColl::CubicPolynomial = typedef Polynomial<T, 3>

Cubic polynomial function.

Definition at line 260 of file Func.h.

◆ LinearPolynomial

template<class T >
using TrajColl::LinearPolynomial = typedef Polynomial<T, 1>

Linear polynomial function.

Definition at line 252 of file Func.h.

◆ QuadraticPolynomial

template<class T >
using TrajColl::QuadraticPolynomial = typedef Polynomial<T, 2>

Quadratic polynomial function.

Definition at line 256 of file Func.h.

Enumeration Type Documentation

◆ BoundaryConstraintType

Type of boundary constraint.

Enumerator
Velocity 

Velocity constraint.

Acceleration 

Acceleration constraint.

Definition at line 10 of file CubicSpline.h.

Function Documentation

◆ interpolate() [1/4]

template<>
Eigen::Matrix3d TrajColl::interpolate ( const Eigen::Matrix3d &  start,
const Eigen::Matrix3d &  end,
double  ratio 
)
inline

Calculate the 3D matrix interpolating from start to end.

Parameters
startstart value
endend value
ratiointerpolation ratio

Definition at line 36 of file ElementInterpolation.h.

◆ interpolate() [2/4]

template<>
Eigen::Quaterniond TrajColl::interpolate ( const Eigen::Quaterniond &  start,
const Eigen::Quaterniond &  end,
double  ratio 
)
inline

Calculate the Quaternion interpolating from start to end.

Parameters
startstart value
endend value
ratiointerpolation ratio

Definition at line 25 of file ElementInterpolation.h.

◆ interpolate() [3/4]

template<>
sva::PTransformd TrajColl::interpolate ( const sva::PTransformd &  start,
const sva::PTransformd &  end,
double  ratio 
)
inline

Calculate the pose interpolating from start to end.

Parameters
startstart value
endend value
ratiointerpolation ratio

Definition at line 47 of file ElementInterpolation.h.

◆ interpolate() [4/4]

template<class T >
T TrajColl::interpolate ( const T &  start,
const T &  end,
double  ratio 
)
inline

Calculate the value interpolating from start to end.

Template Parameters
Tvalue type
Parameters
startstart value
endend value
ratiointerpolation ratio

Definition at line 14 of file ElementInterpolation.h.

◆ interpolateDerivative() [1/6]

template<>
double TrajColl::interpolateDerivative ( const double &  start,
const double &  end,
double  ,
int  order 
)
inline

Calculate the derivative of scalar value interpolating from start to end.

Parameters
startstart value
endend value
ratiointerpolation ratio
orderderivative order

Definition at line 85 of file ElementInterpolation.h.

◆ interpolateDerivative() [2/6]

template<>
Eigen::Vector3d TrajColl::interpolateDerivative ( const Eigen::Matrix3d &  start,
const Eigen::Matrix3d &  end,
double  ,
int  order 
)
inline

Calculate the derivative of 3D matrix interpolating from start to end.

Parameters
startstart value
endend value
ratiointerpolation ratio
orderderivative order

Definition at line 130 of file ElementInterpolation.h.

◆ interpolateDerivative() [3/6]

template<>
Eigen::Vector3d TrajColl::interpolateDerivative ( const Eigen::Quaterniond &  start,
const Eigen::Quaterniond &  end,
double  ,
int  order 
)
inline

Calculate the derivative of Quaternion interpolating from start to end.

Parameters
startstart value
endend value
ratiointerpolation ratio
orderderivative order

Definition at line 107 of file ElementInterpolation.h.

◆ interpolateDerivative() [4/6]

template<>
sva::ForceVecd TrajColl::interpolateDerivative ( const sva::ForceVecd &  start,
const sva::ForceVecd &  end,
double  ,
int  order 
)
inline

Calculate the derivative of wrench interpolating from start to end.

Parameters
startstart value
endend value
ratiointerpolation ratio
orderderivative order

Definition at line 175 of file ElementInterpolation.h.

◆ interpolateDerivative() [5/6]

template<>
sva::MotionVecd TrajColl::interpolateDerivative ( const sva::PTransformd &  start,
const sva::PTransformd &  end,
double  ,
int  order 
)
inline

Calculate the derivative of pose interpolating from start to end.

Parameters
startstart value
endend value
ratiointerpolation ratio
orderderivative order

Definition at line 153 of file ElementInterpolation.h.

◆ interpolateDerivative() [6/6]

template<class T , class U = T>
U TrajColl::interpolateDerivative ( const T &  start,
const T &  end,
double  ,
int  order = 1 
)
inline

Calculate the derivative value interpolating from start to end.

Template Parameters
Tvalue type
Uderivative type
Parameters
startstart value
endend value
ratiointerpolation ratio
orderderivative order

Definition at line 61 of file ElementInterpolation.h.