Embedded control libraries. More...
Namespaces | |
| blueprints | |
| Blueprints and factories classes used to generate blueprints. | |
| concepts | |
| containers | |
| formatters | |
| geometry | |
| interfaces | |
| odometry | |
Typedefs | |
| typedef CartesianPoint< double, 2 > | CartesianPoint2d |
| Eigen style convenience handle for x, y, z triples in double format. More... | |
| typedef CartesianPoint< float, 2 > | CartesianPoint2f |
| Eigen style convenience handle for x, y, z triples in float format. More... | |
| typedef CartesianPoint< int, 2 > | CartesianPoint2i |
| Eigen style convenience handle for x, y, z triples in integer format. More... | |
| typedef CartesianPoint< double, 3 > | CartesianPoint3d |
| Eigen style convenience handle for x, y, z triples in double format. More... | |
| typedef CartesianPoint< float, 3 > | CartesianPoint3f |
| Eigen style convenience handle for x, y, z triples in float format. More... | |
| typedef CartesianPoint< int, 3 > | CartesianPoint3i |
| Eigen style convenience handle for x, y, z triples in integer format. More... | |
| typedef Polynomial< 3 > | CubicPolynomial |
| Mathematical term for 3rd order polynomials. More... | |
| typedef Bool< false > | False |
| typedef HomogeneousPoint< double > | HomogeneousPointd |
| Eigen style convenience handle for homogeneous points in double format. More... | |
| typedef HomogeneousPoint< float > | HomogeneousPointf |
| Eigen style convenience handle for homogeneous points in float format. More... | |
| typedef Polynomial< 1 > | LinearFunction |
| Mathematical term for 1st order polynomials. More... | |
| typedef Polynomial< 2 > | QuadraticPolynomial |
| Mathematical term for 2nd order polynomials. More... | |
| typedef Polynomial< 5 > | QuinticPolynomial |
| Mathematical term for 5th order polynomials. More... | |
| typedef Bool< true > | True |
| typedef void(* | VoidFunction) () |
Enumerations | |
| enum | Alignment |
| enum | Bits |
| enum | ErrorFlag |
| enum | FloatBase |
| enum | IntegralBase |
| enum | Pose2DStorageType { RotationAngleStorage, RotationMatrixStorage } |
| Used by the traits to select the storage type for Pose2D classes. More... | |
| enum | StorageType |
Functions | |
| T * | addressOf (T &v) |
| ReferenceWrapper< T const > | cref (T const &wrapped_object) |
| Scalar | cube_root (const Scalar &x) |
| template<typename T > | |
| ecl_geometry_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. More... | |
| T | euclidean_norm (const T &x1, const T &x2) |
| T | euclidean_norm (const T &x1, const T &x2, const T &x3) |
| NullaryFreeFunction< R > | generateFunctionObject (R(*function)()) |
| UnaryFreeFunction< A, R > | generateFunctionObject (R(*function)(A)) |
| BoundUnaryFreeFunction< A, R > | generateFunctionObject (R(*function)(A), const I &a) |
| BoundUnaryFreeFunction< A, R > | generateFunctionObject (R(*function)(A), I &a) |
| NullaryMemberFunction< C, R > | generateFunctionObject (R(C::*function)()) |
| BoundNullaryMemberFunction< C, R > | generateFunctionObject (R(C::*function)(), C &c) |
| UnaryMemberFunction< C, A, R > | generateFunctionObject (R(C::*function)(A)) |
| PartiallyBoundUnaryMemberFunction< C, A, R > | generateFunctionObject (R(C::*function)(A), C &c) |
| BoundUnaryMemberFunction< C, A, R > | generateFunctionObject (R(C::*function)(A), C &c, const I &a) |
| BoundUnaryMemberFunction< C, A, R > | generateFunctionObject (R(C::*function)(A), C &c, I &a) |
| bool | is_big_endian () |
| bool | is_char_signed () |
| bool | isApprox (const Scalar &x, const OtherScalar &y, typename numeric_limits< Scalar >::Precision precision=numeric_limits< Scalar >::dummy_precision) |
| bool | isApproxOrLessThan (const Scalar &x, const OtherScalar &y, typename numeric_limits< Scalar >::Precision precision=numeric_limits< Scalar >::dummy_precision) |
| int | nsign (const Scalar &x) |
| OutputStream & | operator<< (OutputStream &ostream, const Array< ElementType, ArraySize > &array) |
| OutputStream & | operator<< (OutputStream &ostream, const Array< ElementType, DynamicStorage > &array) |
| 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 OutputStream > | |
| OutputStream & | operator<< (OutputStream &ostream, const CubicSpline &cubic_spline) |
| template<typename OutputStream , typename Type > | |
| OutputStream & | operator<< (OutputStream &ostream, const HomogeneousPoint< Type > &point) |
| template<typename OutputStream , typename Float_ , enum Pose2DStorageType Storage_> | |
| OutputStream & | operator<< (OutputStream &ostream, const LegacyPose2D< Float_, Storage_ > &pose) |
| Insertion operator for output streams. More... | |
| template<typename OutputStream , typename Float_ > | |
| OutputStream & | operator<< (OutputStream &ostream, const LegacyPose3D< Float_ > &pose) |
| Insertion operator for output streams. More... | |
| template<typename OutputStream > | |
| OutputStream & | operator<< (OutputStream &ostream, const PascalsTriangle< 3 > &triangle) |
| Insertion operator for streaming output from pascal's triangle of degree 3. More... | |
| template<typename OutputStream > | |
| OutputStream & | operator<< (OutputStream &ostream, const PascalsTriangle< 5 > &triangle) |
| Insertion operator for streaming output from pascal's triangle of degree 5. More... | |
| template<typename OutputStream , int PowerN> | |
| OutputStream & | operator<< (OutputStream &ostream, const PascalsTriangle< PowerN > &triangle) |
| Streaming output insertion operator for for pascal triangles. More... | |
| template<typename OutputStream , unsigned int Degree> | |
| OutputStream & | operator<< (OutputStream &ostream, const Polynomial< Degree > &polynomial) |
| template<typename OutputStream > | |
| OutputStream & | operator<< (OutputStream &ostream, const SmoothLinearSpline &smooth_linear_spline) |
| OutputStream & | operator<< (OutputStream &ostream, const Stencil< ArrayType > &stencil) |
| template<typename OutputStream > | |
| OutputStream & | operator<< (OutputStream &ostream, const TensionFunction &function) |
| Streaming output insertion operator for tension functions. More... | |
| template<typename OutputStream > | |
| OutputStream & | operator<< (OutputStream &ostream, const TensionSpline &tension_spline) |
| OutputStream & | operator<< (OutputStream &ostream, const Void void_object) |
| OutputStream & | operator<< (OutputStream &ostream, Format< std::string > &formatter) |
| int | psign (const Scalar &x) |
| template<typename T > | |
| ecl_geometry_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. More... | |
| ReferenceWrapper< T > | ref (T &wrapped_object) |
| int | sign (const Scalar &x) |
| ecl_geometry_PUBLIC double | wrap_angle (const double &angle) |
| Return the wrapped the angle on -pi,pi (double types). More... | |
| ecl_geometry_PUBLIC float | wrap_angle (const float &angle) |
| Return the wrapped the angle on -pi,pi (float types). More... | |
| const ecl_geometry_PUBLIC double & | wrap_angle (double &angle) |
| Wrap the angle on -pi,pi (double types). More... | |
| const ecl_geometry_PUBLIC float & | wrap_angle (float &angle) |
| Wrap the angle on -pi,pi (float types). More... | |
Variables | |
| ArgNotSupportedError | |
| Bin | |
| Bit0 | |
| Bit1 | |
| Bit10 | |
| Bit11 | |
| Bit12 | |
| Bit13 | |
| Bit14 | |
| Bit15 | |
| Bit16 | |
| Bit2 | |
| Bit3 | |
| Bit4 | |
| Bit5 | |
| Bit6 | |
| Bit7 | |
| Bit8 | |
| Bit9 | |
| BlockingError | |
| BusyError | |
| CentreAlign | |
| CloseError | |
| ConfigurationError | |
| ConnectionError | |
| ConnectionRefusedError | |
| ConstructorError | |
| ConversionError | |
| Dec | |
| DestructorError | |
| DynamicStorage | |
| Fixed | |
| FixedStorage | |
| Hex | |
| InterruptedError | |
| InvalidArgError | |
| InvalidInputError | |
| InvalidObjectError | |
| IsLockedError | |
| LeftAlign | |
| MemoryError | |
| NoAlign | |
| NoError | |
| NotFoundError | |
| NotInitialisedError | |
| NotSupportedError | |
| OpenError | |
| OutOfRangeError | |
| OutOfResourcesError | |
| PermissionsError | |
| const double | pi |
| const double | pi_2 |
| const float | pi_2_f |
| const double | pi_4 |
| const float | pi_4_f |
| const float | pi_f |
| PosixError | |
| RaiiError | |
| ReadError | |
| RightAlign | |
| Sci | |
| SystemFailureError | |
| TimeOutError | |
| const double | two_pi |
| const float | two_pi_f |
| UnknownError | |
| UsageError | |
| WriteError | |
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 505 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 506 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 507 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 270 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 271 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 272 of file cartesian_point.hpp.
| typedef Polynomial<3> ecl::CubicPolynomial |
Mathematical term for 3rd order polynomials.
Definition at line 395 of file polynomial.hpp.
| typedef HomogeneousPoint<double> ecl::HomogeneousPointd |
Eigen style convenience handle for homogeneous points in double format.
Definition at line 194 of file homogeneous_point.hpp.
| typedef HomogeneousPoint<float> ecl::HomogeneousPointf |
Eigen style convenience handle for homogeneous points in float format.
Definition at line 193 of file homogeneous_point.hpp.
| typedef Polynomial<1> ecl::LinearFunction |
Mathematical term for 1st order polynomials.
Definition at line 393 of file polynomial.hpp.
| typedef Polynomial<2> ecl::QuadraticPolynomial |
Mathematical term for 2nd order polynomials.
Definition at line 394 of file polynomial.hpp.
| typedef Polynomial<5> ecl::QuinticPolynomial |
Mathematical term for 5th order polynomials.
Definition at line 396 of file polynomial.hpp.
Used by the traits to select the storage type for Pose2D classes.
| Enumerator | |
|---|---|
| RotationAngleStorage | RotationAngleStorage. |
| RotationMatrixStorage | RotationMatrixStorage. |
Definition at line 47 of file legacy_pose2d.hpp.
| ecl_geometry_PUBLIC T ecl::degrees_to_radians | ( | const T & | degrees, |
| typename enable_if< ecl::is_float< T > >::type * | dummy = 0 |
||
| ) |
| OutputStream& ecl::operator<< | ( | OutputStream & | ostream, |
| const CartesianPoint< Type, 2 > & | point | ||
| ) |
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 520 of file cartesian_point.hpp.
| OutputStream& ecl::operator<< | ( | OutputStream & | ostream, |
| const CartesianPoint< Type, 3 > & | point | ||
| ) |
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 285 of file cartesian_point.hpp.
| OutputStream& ecl::operator<< | ( | OutputStream & | ostream, |
| const CubicSpline & | cubic_spline | ||
| ) |
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 252 of file cubic_spline.hpp.
| OutputStream& ecl::operator<< | ( | OutputStream & | ostream, |
| const HomogeneousPoint< Type > & | point | ||
| ) |
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 207 of file homogeneous_point.hpp.
| OutputStream& ecl::operator<< | ( | OutputStream & | ostream, |
| const LegacyPose2D< Float_, Storage_ > & | pose | ||
| ) |
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 477 of file legacy_pose2d.hpp.
| OutputStream& ecl::operator<< | ( | OutputStream & | ostream, |
| const LegacyPose3D< Float_ > & | pose | ||
| ) |
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 315 of file legacy_pose3d.hpp.
| OutputStream& ecl::operator<< | ( | OutputStream & | ostream, |
| const PascalsTriangle< 3 > & | triangle | ||
| ) |
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 303 of file pascals_triangle.hpp.
| OutputStream& ecl::operator<< | ( | OutputStream & | ostream, |
| const PascalsTriangle< 5 > & | triangle | ||
| ) |
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 329 of file pascals_triangle.hpp.
| OutputStream& ecl::operator<< | ( | OutputStream & | ostream, |
| const PascalsTriangle< PowerN > & | triangle | ||
| ) |
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 277 of file pascals_triangle.hpp.
| OutputStream& ecl::operator<< | ( | OutputStream & | ostream, |
| const Polynomial< Degree > & | polynomial | ||
| ) |
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 457 of file polynomial.hpp.
| OutputStream& ecl::operator<< | ( | OutputStream & | ostream, |
| const SmoothLinearSpline & | smooth_linear_spline | ||
| ) |
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 182 of file smooth_linear_spline.hpp.
| OutputStream& ecl::operator<< | ( | OutputStream & | ostream, |
| const TensionFunction & | function | ||
| ) |
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 229 of file tension_function.hpp.
| OutputStream& ecl::operator<< | ( | OutputStream & | ostream, |
| const TensionSpline & | tension_spline | ||
| ) |
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 228 of file tension_spline.hpp.
| ecl_geometry_PUBLIC T ecl::radians_to_degrees | ( | const T & | radians, |
| typename enable_if< ecl::is_float< T > >::type * | dummy = 0 |
||
| ) |
| 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. |
| 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 double & ecl::wrap_angle | ( | double & | angle | ) |
| const float & ecl::wrap_angle | ( | float & | angle | ) |