Embedded control libraries. More...
Namespaces | |
| namespace | blueprints |
Blueprints and factories classes used to generate blueprints. | |
| namespace | geometry |
Classes | |
| class | Angle |
| Parent template definition for angles. More... | |
| class | Angle< T, enable_if< is_float< T > >::type > |
| Interface for angular measurements. More... | |
| class | BluePrintFactory< CubicPolynomial > |
| Blueprint factory for cubic polynomials. More... | |
| class | BluePrintFactory< CubicSpline > |
| Blueprint factory for cubic splines. More... | |
| class | BluePrintFactory< LinearFunction > |
| Blueprint factory for linear functions. More... | |
| class | BluePrintFactory< Polynomial< N > > |
| Primary template for the Polynomial blueprint factories. More... | |
| class | BluePrintFactory< QuinticPolynomial > |
| Blueprint factory for quintic polynomials. More... | |
| class | BluePrintFactory< TensionFunction > |
| Blueprint factory for tension functions. More... | |
| class | BluePrintFactory< TensionSpline > |
| Blueprint factory for tension splines. More... | |
| class | CartesianPoint |
| Generic container storing a cartesian point of dimension N. More... | |
| class | CartesianPoint< T, 2 > |
| Specialisation for a cartesian point of dimension 2. More... | |
| class | CartesianPoint< T, 3 > |
| Specialisation for a cartesian point of dimension 3. More... | |
| class | CubicSpline |
| Storage container for a cubic spline interpolation. More... | |
| class | Division |
| Primary template functor for polynomial division. More... | |
| class | Division< CubicPolynomial > |
| Synthetic division between cubic and a factor. More... | |
| class | Division< QuadraticPolynomial > |
| Synthetic division between quadratic and a factor. More... | |
| class | ecl_traits< Pose2D< Float, RotationAngleStorage, Enable > > |
| Traits for the pose2D class with scalar angle storage. More... | |
| class | ecl_traits< Pose2D< Float, RotationMatrixStorage, Enable > > |
| Traits for the pose2D class with rotation matrix storage. More... | |
| class | ecl_traits< Pose2D< Float, Storage, Enable > > |
| Parent template for ecl traits of the pose classes. More... | |
| class | FunctionMath |
| Used as a parent to load function math into function classes. More... | |
| class | FunctionMath< CubicPolynomial > |
| Specialises the function math loader for cubics. More... | |
| class | FunctionMath< LinearFunction > |
| Specialises the function math loader for linear functions. More... | |
| class | FunctionMath< QuadraticPolynomial > |
| Specialises the function math loader for quadratics. More... | |
| class | GenericSplineFunction |
| This is a parent class for generic spline functions. More... | |
| class | HomogeneousPoint |
| Dummy parent class for Homogenous points. More... | |
| class | HomogeneousPoint< T, typename ecl::enable_if< ecl::is_float< T > >::type > |
| Container storing a homogenous point. More... | |
| class | Intersection |
| Primary template functor for the intersection of like functions. More... | |
| class | Intersection< LinearFunction > |
| Intersection of two linear functions. More... | |
| class | Maximum |
| Primary template functor for the maximum of a continuous function. More... | |
| class | Maximum< CubicPolynomial > |
| Mathematical maximum on a compact interval for cubic polynomials. More... | |
| class | Maximum< LinearFunction > |
| Mathematical maximum on a compact interval for linear functions. More... | |
| class | Minimum |
| Primary template functor for the minimum of a continuous function. More... | |
| class | Minimum< CubicPolynomial > |
| Mathematical minimum on a compact interval for cubic polynomials. More... | |
| class | Minimum< LinearFunction > |
| Mathematical minimum on a compact interval for linear functions. More... | |
| class | PascalsTriangle |
| Holds the coefficients for pascal's triangle up to row N. More... | |
| class | PascalsTriangle< 3 > |
| Holds the coefficients of pascal's triangle up to n = 3. More... | |
| class | PascalsTriangle< 5 > |
| Holds the coefficients of pascal's triangle up to n = 5. More... | |
| class | Polynomial |
| Representation of a polynomial function of n-th degree. More... | |
| class | Polynomial< 0 > |
| Specialisation for the zero-th order polynomial. More... | |
| class | Pose2D |
| Parent template definition for Pose2D. More... | |
| class | Pose2D< Float, Storage, enable_if< is_float< Float > >::type > |
| Representation for a 2D pose (3 degrees of freedom). More... | |
| class | Pose3D |
| Parent template definition for Pose3D. More... | |
| class | Pose3D< Float, enable_if< is_float< Float > >::type > |
| Representation for a 3D pose (6 degrees of freedom). More... | |
| class | Roots |
| Primary template functor for the roots of a function (x-axis intercepts). More... | |
| class | Roots< CubicPolynomial > |
| X axis intercepts for cubic polynomials. More... | |
| class | Roots< LinearFunction > |
| X axis intercepts for linear functions. More... | |
| class | Roots< QuadraticPolynomial > |
| X axis intercepts for quadratics. More... | |
| class | SmoothLinearSpline |
| Storage container for a smoothed linear spline interpolation. More... | |
| class | SplineFunction |
| Template wrapper for a generic spline function. More... | |
| class | TensionFunction |
| Representation of a tension function. More... | |
| class | TensionSpline |
| Storage container for a tension spline interpolation. More... | |
Typedefs | |
| typedef CartesianPoint< double, 2 > | CartesianPoint2d |
| Eigen style convenience handle for x, y, z triples in double format. | |
| typedef CartesianPoint< float, 2 > | CartesianPoint2f |
| Eigen style convenience handle for x, y, z triples in float format. | |
| typedef CartesianPoint< int, 2 > | CartesianPoint2i |
| Eigen style convenience handle for x, y, z triples in integer format. | |
| typedef CartesianPoint< double, 3 > | CartesianPoint3d |
| Eigen style convenience handle for x, y, z triples in double format. | |
| typedef CartesianPoint< float, 3 > | CartesianPoint3f |
| Eigen style convenience handle for x, y, z triples in float format. | |
| typedef CartesianPoint< int, 3 > | CartesianPoint3i |
| Eigen style convenience handle for x, y, z triples in integer format. | |
| typedef Polynomial< 3 > | CubicPolynomial |
| Mathematical term for 3rd order polynomials. | |
| typedef HomogeneousPoint< double > | HomogeneousPointd |
| Eigen style convenience handle for homogeneous points in double format. | |
| typedef HomogeneousPoint< float > | HomogeneousPointf |
| Eigen style convenience handle for homogeneous points in float format. | |
| typedef Polynomial< 1 > | LinearFunction |
| Mathematical term for 1st order polynomials. | |
| typedef Polynomial< 2 > | QuadraticPolynomial |
| Mathematical term for 2nd order polynomials. | |
| typedef Polynomial< 5 > | QuinticPolynomial |
| Mathematical term for 5th order polynomials. | |
Enumerations | |
| enum | Pose2DStorageType { RotationAngleStorage, RotationMatrixStorage, RotationAngleStorage, RotationMatrixStorage } |
Used by the traits to select the storage type for Pose2D classes. More... | |
| enum | Pose2DStorageType { RotationAngleStorage, RotationMatrixStorage, RotationAngleStorage, RotationMatrixStorage } |
Used by the traits to select the storage type for Pose2D classes. More... | |
Functions | |
| template<typename T > | |
| ECL_PUBLIC T | degrees_to_radians (const T °rees, typename enable_if< ecl::is_float< T > >::type *dummy=0) |
| Converts degrees to radians and returns the result. | |
| template<typename OutputStream > | |
| OutputStream & | operator<< (OutputStream &ostream, const TensionSpline &tension_spline) |
| template<typename OutputStream > | |
| OutputStream & | operator<< (OutputStream &ostream, const TensionFunction &function) |
| Streaming output insertion operator for tension functions. | |
| template<typename OutputStream > | |
| OutputStream & | operator<< (OutputStream &ostream, const SmoothLinearSpline &smooth_linear_spline) |
| template<typename OutputStream , typename Float_ > | |
| OutputStream & | operator<< (OutputStream &ostream, const Pose3D< Float_ > &pose) |
| Insertion operator for output streams. | |
| template<typename OutputStream , typename Float_ , enum Pose2DStorageType Storage_> | |
| OutputStream & | operator<< (OutputStream &ostream, const Pose2D< Float_, Storage_ > &pose) |
| Insertion operator for output streams. | |
| template<typename OutputStream , unsigned int Degree> | |
| OutputStream & | operator<< (OutputStream &ostream, const Polynomial< Degree > &polynomial) |
| template<typename OutputStream > | |
| OutputStream & | operator<< (OutputStream &ostream, const PascalsTriangle< 5 > &triangle) |
| Insertion operator for streaming output from pascal's triangle of degree 5. | |
| template<typename OutputStream > | |
| OutputStream & | operator<< (OutputStream &ostream, const PascalsTriangle< 3 > &triangle) |
| Insertion operator for streaming output from pascal's triangle of degree 3. | |
| template<typename OutputStream , int PowerN> | |
| OutputStream & | operator<< (OutputStream &ostream, const PascalsTriangle< PowerN > &triangle) |
| Streaming output insertion operator for for pascal triangles. | |
| template<typename OutputStream , typename Type > | |
| OutputStream & | operator<< (OutputStream &ostream, const HomogeneousPoint< Type > &point) |
| template<typename OutputStream > | |
| OutputStream & | operator<< (OutputStream &ostream, const CubicSpline &cubic_spline) |
| template<typename OutputStream , typename Type > | |
| OutputStream & | operator<< (OutputStream &ostream, const CartesianPoint< Type, 2 > &point) |
| template<typename OutputStream , typename Type > | |
| OutputStream & | operator<< (OutputStream &ostream, const CartesianPoint< Type, 3 > &point) |
| template<typename T > | |
| ECL_PUBLIC T | radians_to_degrees (const T &radians, typename enable_if< ecl::is_float< T > >::type *dummy=0) |
| Converts radians to degrees and returns the result. | |
| ECL_PUBLIC double | wrap_angle (const double &angle) |
| Return the wrapped the angle on -pi,pi (double types). | |
| ECL_PUBLIC const double & | wrap_angle (double &angle) |
| Wrap the angle on -pi,pi (double types). | |
| ECL_PUBLIC float | wrap_angle (const float &angle) |
| Return the wrapped the angle on -pi,pi (float types). | |
| ECL_PUBLIC const float & | wrap_angle (float &angle) |
| Wrap the angle on -pi,pi (float types). | |
Embedded control libraries.
Various core libraries useful for embedded control systems.
| typedef CartesianPoint<double,2> ecl::CartesianPoint2d |
Eigen style convenience handle for x, y, z triples in double format.
Definition at line 494 of file cartesian_point.hpp.
| typedef CartesianPoint<float,2> ecl::CartesianPoint2f |
Eigen style convenience handle for x, y, z triples in float format.
Definition at line 495 of file cartesian_point.hpp.
| typedef CartesianPoint<int,2> ecl::CartesianPoint2i |
Eigen style convenience handle for x, y, z triples in integer format.
Definition at line 496 of file cartesian_point.hpp.
| typedef CartesianPoint<double,3> ecl::CartesianPoint3d |
Eigen style convenience handle for x, y, z triples in double format.
Definition at line 259 of file cartesian_point.hpp.
| typedef CartesianPoint<float,3> ecl::CartesianPoint3f |
Eigen style convenience handle for x, y, z triples in float format.
Definition at line 260 of file cartesian_point.hpp.
| typedef CartesianPoint<int,3> ecl::CartesianPoint3i |
Eigen style convenience handle for x, y, z triples in integer format.
Definition at line 261 of file cartesian_point.hpp.
| typedef Polynomial<3> ecl::CubicPolynomial |
Mathematical term for 3rd order polynomials.
Definition at line 360 of file polynomial.hpp.
| typedef HomogeneousPoint<double> ecl::HomogeneousPointd |
Eigen style convenience handle for homogeneous points in double format.
Definition at line 178 of file homogeneous_point.hpp.
| typedef HomogeneousPoint<float> ecl::HomogeneousPointf |
Eigen style convenience handle for homogeneous points in float format.
Definition at line 177 of file homogeneous_point.hpp.
| typedef Polynomial<1> ecl::LinearFunction |
Mathematical term for 1st order polynomials.
Definition at line 358 of file polynomial.hpp.
| typedef Polynomial<2> ecl::QuadraticPolynomial |
Mathematical term for 2nd order polynomials.
Definition at line 359 of file polynomial.hpp.
| typedef Polynomial<5> ecl::QuinticPolynomial |
Mathematical term for 5th order polynomials.
Definition at line 361 of file polynomial.hpp.
Used by the traits to select the storage type for Pose2D classes.
| RotationAngleStorage |
RotationAngleStorage. |
| RotationMatrixStorage |
RotationMatrixStorage. |
| RotationAngleStorage |
RotationAngleStorage. |
| RotationMatrixStorage |
RotationMatrixStorage. |
Definition at line 43 of file pose2d_eigen3.hpp.
Used by the traits to select the storage type for Pose2D classes.
| RotationAngleStorage |
RotationAngleStorage. |
| RotationMatrixStorage |
RotationMatrixStorage. |
| RotationAngleStorage |
RotationAngleStorage. |
| RotationMatrixStorage |
RotationMatrixStorage. |
Definition at line 43 of file pose2d_eigen2.hpp.
| ECL_PUBLIC T ecl::degrees_to_radians | ( | const T & | degrees, | |
| typename enable_if< ecl::is_float< T > >::type * | dummy = 0 | |||
| ) | [inline] |
| OutputStream& ecl::operator<< | ( | OutputStream & | ostream, | |
| const TensionSpline & | tension_spline | |||
| ) | [inline] |
Streaming output insertion operator for tension splines. This lists in algebraic form the sequence of tension functions constituting the spline.
| OutputStream | : the type of stream being used. |
| ostream | : the output stream being used. | |
| tension_spline | : the tension spline. |
Definition at line 209 of file tension_spline.hpp.
| OutputStream& ecl::operator<< | ( | OutputStream & | ostream, | |
| const TensionFunction & | function | |||
| ) | [inline] |
Streaming output insertion operator for tension functions.
Streaming output insertion operator for tension functions.
| OutputStream | : the type of stream being used. |
| ostream | : the output stream being used. | |
| function | : the tension function. |
Definition at line 223 of file tension_function.hpp.
| OutputStream& ecl::operator<< | ( | OutputStream & | ostream, | |
| const SmoothLinearSpline & | smooth_linear_spline | |||
| ) | [inline] |
Streaming output insertion operator for smoothed linear splines. This simply lists the spline segments and corners (linear functions and quintic polynomials) in algebraic form.
| OutputStream | : the type of stream being used. |
| ostream | : the output stream being used. | |
| smooth_linear_spline | : the tension spline. |
Definition at line 168 of file smooth_linear_spline.hpp.
| OutputStream & ecl::operator<< | ( | OutputStream & | ostream, | |
| const Pose3D< Float_ > & | pose | |||
| ) | [inline] |
Insertion operator for output streams.
Note that the output heading angle is formatted in degrees.
| ostream | : stream satisfying the ecl stream concept. | |
| pose | : the inserted pose. |
Definition at line 304 of file pose3d_eigen3.hpp.
| OutputStream & ecl::operator<< | ( | OutputStream & | ostream, | |
| const Pose2D< Float_, Storage_ > & | pose | |||
| ) | [inline] |
Insertion operator for output streams.
Note that the output heading angle is formatted in degrees.
| ostream | : stream satisfying the ecl stream concept. | |
| pose | : the inserted pose. |
Definition at line 455 of file pose2d_eigen3.hpp.
| OutputStream& ecl::operator<< | ( | OutputStream & | ostream, | |
| const Polynomial< Degree > & | polynomial | |||
| ) | [inline] |
Streaming output insertion operator for polynomials.
| OutputStream | : the type of stream being used. | |
| Degree | : the order of the polynomial being inserted. |
| ostream | : the output stream being used. | |
| polynomial | : the polynomial |
Definition at line 422 of file polynomial.hpp.
| OutputStream& ecl::operator<< | ( | OutputStream & | ostream, | |
| const PascalsTriangle< 5 > & | triangle | |||
| ) | [inline] |
Insertion operator for streaming output from pascal's triangle of degree 5.
Insertion operator for streaming output from pascal's triangle.
| ostream | : the output stream being used. | |
| triangle | : the pascal triangle object. |
Definition at line 323 of file pascals_triangle.hpp.
| OutputStream& ecl::operator<< | ( | OutputStream & | ostream, | |
| const PascalsTriangle< 3 > & | triangle | |||
| ) | [inline] |
Insertion operator for streaming output from pascal's triangle of degree 3.
Insertion operator for streaming output from pascal's triangle.
| ostream | : the stream to send the output to. | |
| triangle | : the pascal triangle object. |
Definition at line 297 of file pascals_triangle.hpp.
| OutputStream& ecl::operator<< | ( | OutputStream & | ostream, | |
| const PascalsTriangle< PowerN > & | triangle | |||
| ) | [inline] |
Streaming output insertion operator for for pascal triangles.
Streaming output insertion operator for for pascal triangles.
| OutputStream | : the type of stream being used. | |
| PowerN | : the order of the pascal's triangle being inserted. |
| ostream | : the stream to send the output to. | |
| triangle | : the pascal triangle object. |
Definition at line 271 of file pascals_triangle.hpp.
| OutputStream& ecl::operator<< | ( | OutputStream & | ostream, | |
| const HomogeneousPoint< Type > & | point | |||
| ) | [inline] |
Insertion operator for sending the point to an output stream. This is raw, and has no formatting.
| ostream | : the output stream. | |
| point | : the point to be inserted. |
Definition at line 191 of file homogeneous_point.hpp.
| OutputStream& ecl::operator<< | ( | OutputStream & | ostream, | |
| const CubicSpline & | cubic_spline | |||
| ) | [inline] |
Streaming output insertion operator for cubic splines.
| OutputStream | : the type of stream being used. |
| ostream | : the output stream being used. | |
| cubic_spline | : the cubic spline. |
Definition at line 238 of file cubic_spline.hpp.
| OutputStream& ecl::operator<< | ( | OutputStream & | ostream, | |
| const CartesianPoint< Type, 2 > & | point | |||
| ) | [inline] |
Insertion operator for sending the array to an output stream. This is raw, and has no formatting.
| ostream | : the output stream. | |
| point | : the point to be inserted. |
Definition at line 509 of file cartesian_point.hpp.
| OutputStream& ecl::operator<< | ( | OutputStream & | ostream, | |
| const CartesianPoint< Type, 3 > & | point | |||
| ) | [inline] |
Insertion operator for sending the point to an output stream. This is raw, and has no formatting.
| ostream | : the output stream. | |
| point | : the point to be inserted. |
Definition at line 274 of file cartesian_point.hpp.
| ECL_PUBLIC T ecl::radians_to_degrees | ( | const T & | radians, | |
| typename enable_if< ecl::is_float< T > >::type * | dummy = 0 | |||
| ) | [inline] |
| double ecl::wrap_angle | ( | const double & | angle | ) |
Return the wrapped the angle on -pi,pi (double types).
This uses the double versions of the math functions to wrap the angle on -pi, pi. This is the slow version which creates a copy and returns it.
| angle | : the angle to be wrapped. |
| const double & ecl::wrap_angle | ( | double & | angle | ) |
| float ecl::wrap_angle | ( | const float & | angle | ) |
Return the wrapped the angle on -pi,pi (float types).
This uses the float versions of the math functions to wrap the angle on -pi, pi. This is the slow version which creates a copy and returns it.
| angle | : the angle to be wrapped. |
| const float & ecl::wrap_angle | ( | float & | angle | ) |