Math classes and function useful in robot applications. More...
Namespaces | |
eigen3 | |
graph | |
Classes | |
class | AdditivelySeparableScalarField3 |
The AdditivelySeparableScalarField3 class constructs a scalar field F in R^3 as a sum of scalar functions i.e. F(x, y, z) = k (p(x) + q(y) + r(z)). More... | |
class | Angle |
The Angle class is used to simplify and clarify the use of radians and degrees measurements. A default constructed Angle instance has a value of zero radians/degrees. More... | |
class | AxisAlignedBox |
Mathematical representation of a box that is aligned along an X,Y,Z axis. More... | |
class | BiQuad |
Bi-quad filter base class. More... | |
class | BiQuadVector3 |
BiQuad vector3 filter. More... | |
class | Box |
A representation of a box. All units are in meters. More... | |
class | Capsule |
A representation of a capsule or sphere-capped cylinder. More... | |
class | Color |
Defines a color using a red (R), green (G), blue (B), and alpha (A) component. Each color component is in the range [0..1]. More... | |
class | Cylinder |
A representation of a cylinder. More... | |
class | DiffDriveOdometry |
Computes odometry values based on a set of kinematic properties and wheel speeds for a diff-drive vehicle. More... | |
class | Ellipsoid |
A representation of a general ellipsoid. More... | |
class | Filter |
Filter base class. More... | |
class | Frustum |
Mathematical representation of a frustum and related functions. This is also known as a view frustum. More... | |
class | GaussMarkovProcess |
Implementation of a stationary gauss-markov process, also known as a Ornstein Ulenbeck process. More... | |
class | Inertial |
The Inertial object provides a representation for the mass and inertia matrix of a body B. The components of the inertia matrix are expressed in what we call the "inertial" frame Bi of the body, i.e. the frame in which these inertia components are measured. The inertial frame Bi must be located at the center of mass of the body, but not necessarily aligned with the body’s frame. In addition, this class allows users to specify a frame F for these inertial properties by specifying the pose X_FBi of the inertial frame Bi in the inertial object frame F. More... | |
class | Interval |
The Interval class represents a range of real numbers. Intervals may be open (a, b), left-closed [a, b), right-closed (a, b], or fully closed [a, b]. More... | |
class | Kmeans |
K-Means clustering algorithm. Given a set of observations, k-means partitions the observations into k sets so as to minimize the within-cluster sum of squares. Description based on http://en.wikipedia.org/wiki/K-means_clustering. More... | |
class | Line2 |
A two dimensional line segment. The line is defined by a start and end point. More... | |
class | Line3 |
A three dimensional line segment. The line is defined by a start and end point. More... | |
class | MassMatrix3 |
A class for inertial information about a rigid body consisting of the scalar mass and a 3x3 symmetric moment of inertia matrix stored as two Vector3's. More... | |
class | Material |
Contains information about a single material. More... | |
class | Matrix3 |
A 3x3 matrix class. More... | |
class | Matrix4 |
A 4x4 matrix class. More... | |
class | Matrix6 |
A 6x6 matrix class. More... | |
class | MecanumDriveOdometry |
Computes odometry values based on a set of kinematic properties and wheel speeds for a Mecanum-drive vehicle. More... | |
class | MovingWindowFilter |
Base class for MovingWindowFilter. This replaces the version of MovingWindowFilter in the Ignition Common library. More... | |
class | OnePole |
A one-pole DSP filter. More... | |
class | OnePoleQuaternion |
One-pole quaternion filter. More... | |
class | OnePoleVector3 |
One-pole vector3 filter. More... | |
class | OrientedBox |
Mathematical representation of a box which can be arbitrarily positioned and rotated. More... | |
class | PID |
Generic PID controller class. Generic proportional-integral-derivative controller class that keeps track of PID-error states and control inputs given the state of a system and a user specified target state. It includes a user-adjustable command offset term (feed-forward). More... | |
class | PiecewiseScalarField3 |
The PiecewiseScalarField3 class constructs a scalar field F in R^3 as a union of scalar fields Pn, defined over regions Rn i.e. piecewise. More... | |
class | Plane |
A plane and related functions. More... | |
class | Polynomial3 |
The Polynomial3 class represents a cubic polynomial with real coefficients p(x) = c0 x^3 + c1 x^2 + c2 x + c3. More... | |
class | Pose3 |
Encapsulates a position and rotation in three space. More... | |
class | Quaternion |
A quaternion class. More... | |
class | Rand |
Random number generator class. More... | |
class | Region3 |
The Region3 class represents the cartesian product of intervals Ix ✕ Iy ✕ Iz, one per axis, yielding an axis-aligned region of R^3 space. It can be thought of as an intersection of halfspaces. Regions may be open or closed in their boundaries, if any. More... | |
class | RollingMean |
A class that computes the mean over a series of data points. The window size determines the maximum number of data points. The oldest value is popped off when the window size is reached and a new value is pushed in. More... | |
class | RotationSpline |
Spline for rotations. More... | |
class | SemanticVersion |
Version comparison class based on Semantic Versioning 2.0.0 http://semver.org/ Compares versions and converts versions from string. More... | |
class | SignalMaxAbsoluteValue |
Computing the maximum of the absolute value of a discretely sampled signal. Also known as the maximum norm, infinity norm, or supremum norm. More... | |
class | SignalMaximum |
Computing the maximum value of a discretely sampled signal. More... | |
class | SignalMean |
Computing the mean value of a discretely sampled signal. More... | |
class | SignalMinimum |
Computing the minimum value of a discretely sampled signal. More... | |
class | SignalRootMeanSquare |
Computing the square root of the mean squared value of a discretely sampled signal. More... | |
class | SignalStatistic |
Statistical properties of a discrete time scalar signal. More... | |
class | SignalStats |
Collection of statistics for a scalar signal. More... | |
class | SignalVariance |
Computing the incremental variance of a discretely sampled signal. More... | |
class | SpeedLimiter |
Class to limit velocity, acceleration and jerk. More... | |
class | Sphere |
A representation of a sphere. More... | |
class | SphericalCoordinates |
Convert spherical coordinates for planetary surfaces. More... | |
class | Spline |
Splines. More... | |
class | Stopwatch |
The Stopwatch keeps track of time spent in the run state, accessed through ElapsedRunTime(), and time spent in the stop state, accessed through ElapsedStopTime(). Elapsed run time starts accumulating after the first call to Start(). Elapsed stop time starts accumulation after Start() has been called followed by Stop(). The stopwatch can be reset with the Reset() function. More... | |
class | Temperature |
A class that stores temperature information, and allows conversion between different units. More... | |
class | Triangle |
Triangle class and related functions. More... | |
class | Triangle3 |
A 3-dimensional triangle and related functions. More... | |
class | Vector2 |
Two dimensional (x, y) vector. More... | |
class | Vector3 |
The Vector3 class represents the generic vector containing 3 elements. Since it's commonly used to keep coordinate system related information, its elements are labeled by x, y, z. More... | |
class | Vector3Stats |
Collection of statistics for a Vector3 signal. More... | |
class | Vector4 |
T Generic x, y, z, w vector. More... | |
Typedefs | |
template<typename ScalarFunctionT > | |
using | AdditivelySeparableScalarField3d = AdditivelySeparableScalarField3< ScalarFunctionT, double > |
template<typename ScalarFunctionT > | |
using | AdditivelySeparableScalarField3f = AdditivelySeparableScalarField3< ScalarFunctionT, float > |
typedef Box< double > | Boxd |
Box with double precision. More... | |
typedef Box< float > | Boxf |
Box with float precision. More... | |
typedef Box< int > | Boxi |
Box with integer precision. More... | |
typedef Capsule< double > | Capsuled |
Capsule with double precision. More... | |
typedef Capsule< float > | Capsulef |
Capsule with float precision. More... | |
typedef Capsule< int > | Capsulei |
Capsule with integer precision. More... | |
using | clock = std::chrono::steady_clock |
typedef Cylinder< double > | Cylinderd |
Cylinder with double precision. More... | |
typedef Cylinder< float > | Cylinderf |
Cylinder with float precision. More... | |
typedef Cylinder< int > | Cylinderi |
Cylinder with integer precision. More... | |
typedef std::chrono::duration< uint64_t, std::ratio< 86400 > > | days |
This will exist in C++-20. More... | |
typedef Ellipsoid< double > | Ellipsoidd |
Ellipsoid with double precision. More... | |
typedef Ellipsoid< float > | Ellipsoidf |
Ellipsoid with float precision. More... | |
typedef Ellipsoid< int > | Ellipsoidi |
Ellipsoid with integer precision. More... | |
typedef std::mt19937 | GeneratorType |
typedef Inertial< double > | Inertiald |
typedef Inertial< float > | Inertialf |
template<typename T > | |
using | IntersectionPoints = std::set< Vector3< T >, WellOrderedVectors< T > > |
This is the type used for deduplicating and returning the set of intersections. More... | |
using | Intervald = Interval< double > |
using | Intervalf = Interval< float > |
typedef Line2< double > | Line2d |
typedef Line2< float > | Line2f |
typedef Line2< int > | Line2i |
typedef Line3< double > | Line3d |
typedef Line3< float > | Line3f |
typedef Line3< int > | Line3i |
typedef MassMatrix3< double > | MassMatrix3d |
typedef MassMatrix3< float > | MassMatrix3f |
typedef Matrix3< double > | Matrix3d |
typedef Matrix3< float > | Matrix3f |
typedef Matrix3< int > | Matrix3i |
typedef Matrix4< double > | Matrix4d |
typedef Matrix4< float > | Matrix4f |
typedef Matrix4< int > | Matrix4i |
typedef Matrix6< double > | Matrix6d |
typedef Matrix6< float > | Matrix6f |
typedef Matrix6< int > | Matrix6i |
typedef std::normal_distribution< double > | NormalRealDist |
typedef OrientedBox< double > | OrientedBoxd |
typedef OrientedBox< float > | OrientedBoxf |
typedef OrientedBox< int > | OrientedBoxi |
using | PairInput = uint32_t |
using | PairOutput = uint64_t |
template<typename ScalarField3T > | |
using | PiecewiseScalarField3d = PiecewiseScalarField3< ScalarField3T, double > |
template<typename ScalarField3T > | |
using | PiecewiseScalarField3f = PiecewiseScalarField3< ScalarField3T, float > |
typedef Plane< double > | Planed |
typedef Plane< float > | Planef |
typedef Plane< int > | Planei |
using | Polynomial3d = Polynomial3< double > |
using | Polynomial3f = Polynomial3< float > |
typedef Pose3< double > | Pose3d |
typedef Pose3< float > | Pose3f |
typedef Pose3< int > | Pose3i |
typedef Quaternion< double > | Quaterniond |
typedef Quaternion< float > | Quaternionf |
typedef Quaternion< int > | Quaternioni |
using | Region3d = Region3< double > |
using | Region3f = Region3< float > |
typedef Sphere< double > | Sphered |
Sphere with double precision. More... | |
typedef Sphere< float > | Spheref |
Sphere with float precision. More... | |
typedef Sphere< int > | Spherei |
Sphere with integer precision. More... | |
typedef Triangle3< double > | Triangle3d |
Double specialization of the Triangle class. More... | |
typedef Triangle3< float > | Triangle3f |
Float specialization of the Triangle class. More... | |
typedef Triangle3< int > | Triangle3i |
Integer specialization of the Triangle class. More... | |
typedef Triangle< double > | Triangled |
Double specialization of the Triangle class. More... | |
typedef Triangle< float > | Trianglef |
Float specialization of the Triangle class. More... | |
typedef Triangle< int > | Trianglei |
Integer specialization of the Triangle class. More... | |
typedef std::uniform_int_distribution< int32_t > | UniformIntDist |
typedef std::uniform_real_distribution< double > | UniformRealDist |
typedef Vector2< double > | Vector2d |
typedef Vector2< float > | Vector2f |
typedef Vector2< int > | Vector2i |
typedef Vector3< double > | Vector3d |
typedef Vector3< float > | Vector3f |
typedef Vector3< int > | Vector3i |
typedef Vector4< double > | Vector4d |
typedef Vector4< float > | Vector4f |
typedef Vector4< int > | Vector4i |
Enumerations | |
enum | MaterialType { STYROFOAM = 0, PINE, WOOD, OAK, PLASTIC, CONCRETE, ALUMINUM, STEEL_ALLOY, STEEL_STAINLESS, IRON, BRASS, COPPER, TUNGSTEN, UNKNOWN_MATERIAL } |
This enum lists the supported material types. A value can be used to create a Material instance. Source: https://en.wikipedia.org/wiki/Density. More... | |
Functions | |
template<> | |
void | appendToStream (std::ostream &_out, int _number) |
Append a number to a stream, specialized for int. More... | |
template<typename T > | |
void | appendToStream (std::ostream &_out, T _number) |
Append a number to a stream. Makes sure "-0" is returned as "0". More... | |
template<class... Durations, class DurationIn > | |
std::tuple< Durations... > | breakDownDurations (DurationIn d) |
break down durations NOTE: the template arguments must be properly ordered according to magnitude and there can be no duplicates. This function uses the braces initializer to split all the templated duration. The initializer will be called recursievely due the ... More... | |
template<typename T > | |
T | clamp (T _v, T _min, T _max) |
Simple clamping function. More... | |
std::pair< int64_t, int64_t > | durationToSecNsec (const std::chrono::steady_clock::duration &_dur) |
Convert a std::chrono::steady_clock::duration to a seconds and nanoseconds pair. More... | |
std::string | durationToString (const std::chrono::steady_clock::duration &_duration) |
Convert a std::chrono::steady_clock::duration to a string. More... | |
template<typename T > | |
bool | equal (const T &_a, const T &_b, const T &_epsilon=T(1e-6)) |
check if two values are equal, within a tolerance More... | |
double | fixnan (double _v) |
Fix a nan value. More... | |
float | fixnan (float _v) |
Fix a nan value. More... | |
template<typename T > | |
bool | greaterOrNearEqual (const T &_a, const T &_b, const T &_epsilon=1e-6) |
inequality test, within a tolerance More... | |
bool | isEven (const int _v) |
Check if parameter is even. More... | |
bool | isEven (const unsigned int _v) |
Check if parameter is even. More... | |
bool | isnan (double _v) |
check if a double is NaN More... | |
bool | isnan (float _v) |
check if a float is NaN More... | |
bool | isOdd (const int _v) |
Check if parameter is odd. More... | |
bool | isOdd (const unsigned int _v) |
Check if parameter is odd. More... | |
bool | isPowerOfTwo (unsigned int _x) |
Is this a power of 2? More... | |
bool | isTimeString (const std::string &_timeString) |
Check if the given string represents a time. An example time string is "0 00:00:00.000", which has the format "DAYS HOURS:MINUTES:SECONDS.MILLISECONDS". More... | |
template<typename T > | |
bool | lessOrNearEqual (const T &_a, const T &_b, const T &_epsilon=1e-6) |
inequality test, within a tolerance More... | |
template<typename T > | |
T | max (const std::vector< T > &_values) |
get the maximum value of vector of values More... | |
template<typename T > | |
T | mean (const std::vector< T > &_values) |
get mean of vector of values More... | |
template<typename T > | |
T | min (const std::vector< T > &_values) |
get the minimum value of vector of values More... | |
PairOutput | Pair (const PairInput _a, const PairInput _b) |
A pairing function that maps two values to a unique third value. This is an implement of Szudzik's function. More... | |
double | parseFloat (const std::string &_input) |
parse string into float More... | |
int | parseInt (const std::string &_input) |
parse string into an integer More... | |
template<typename T > | |
T | precision (const T &_a, const unsigned int &_precision) |
get value at a specified precision More... | |
int | roundUpMultiple (int _num, int _multiple) |
Round a number up to the nearest multiple. For example, if the input number is 12 and the multiple is 10, the result is 20. If the input number is negative, then the nearest multiple will be greater than or equal to the input number. For example, if the input number is -9 and the multiple is 2 then the output is -8. More... | |
unsigned int | roundUpPowerOfTwo (unsigned int _x) |
Get the smallest power of two that is greater or equal to a given value. More... | |
std::chrono::steady_clock::duration | secNsecToDuration (const uint64_t &_sec, const uint64_t &_nanosec) |
Convert seconds and nanoseconds to std::chrono::steady_clock::duration. More... | |
std::chrono::steady_clock::time_point | secNsecToTimePoint (const uint64_t &_sec, const uint64_t &_nanosec) |
Convert seconds and nanoseconds to std::chrono::steady_clock::time_point. More... | |
template<typename T > | |
int | sgn (T _value) |
The signum function. More... | |
template<typename T > | |
int | signum (T _value) |
The signum function. More... | |
template<typename T > | |
void | sort2 (T &_a, T &_b) |
Sort two numbers, such that _a <= _b. More... | |
template<typename T > | |
void | sort3 (T &_a, T &_b, T &_c) |
Sort three numbers, such that _a <= _b <= _c. More... | |
bool | splitTimeBasedOnTimeRegex (const std::string &_timeString, uint64_t &numberDays, uint64_t &numberHours, uint64_t &numberMinutes, uint64_t &numberSeconds, uint64_t &numberMilliseconds) |
Split a std::chrono::steady_clock::duration to a string. More... | |
std::chrono::steady_clock::duration | stringToDuration (const std::string &_timeString) |
Convert a string to a std::chrono::steady_clock::duration. More... | |
std::chrono::steady_clock::time_point | stringToTimePoint (const std::string &_timeString) |
Convert a string to a std::chrono::steady_clock::time_point. More... | |
std::pair< int64_t, int64_t > | timePointToSecNsec (const std::chrono::steady_clock::time_point &_time) |
Convert a std::chrono::steady_clock::time_point to a seconds and nanoseconds pair. More... | |
std::string | timePointToString (const std::chrono::steady_clock::time_point &_point) |
Convert a std::chrono::steady_clock::time_point to a string. More... | |
std::tuple< PairInput, PairInput > | Unpair (const PairOutput _key) |
The reverse of the Pair function. Accepts a key, produced from the Pair function, and returns a tuple consisting of the two non-negative integer values used to create the _key. More... | |
template<typename T > | |
T | variance (const std::vector< T > &_values) |
get variance of vector of values More... | |
Variables | |
static const double | DPRCT_INF_D = INF_D |
static const float | DPRCT_INF_F = INF_F |
static const int16_t | DPRCT_INF_I16 = INF_I16 |
static const int32_t | DPRCT_INF_I32 = INF_I32 |
static const int64_t | DPRCT_INF_I64 = INF_I64 |
static const uint16_t | DPRCT_INF_UI16 = INF_UI16 |
static const uint32_t | DPRCT_INF_UI32 = INF_UI32 |
static const uint64_t | DPRCT_INF_UI64 = INF_UI64 |
static const double | DPRCT_LOW_D = LOW_D |
static const float | DPRCT_LOW_F = LOW_F |
static const int16_t | DPRCT_LOW_I16 = LOW_I16 |
static const int32_t | DPRCT_LOW_I32 = LOW_I32 |
static const int64_t | DPRCT_LOW_I64 = LOW_I64 |
static const uint16_t | DPRCT_LOW_UI16 = LOW_UI16 |
static const uint32_t | DPRCT_LOW_UI32 = LOW_UI32 |
static const uint64_t | DPRCT_LOW_UI64 = LOW_UI64 |
static const double | DPRCT_MAX_D = MAX_D |
static const float | DPRCT_MAX_F = MAX_F |
static const int16_t | DPRCT_MAX_I16 = MAX_I16 |
static const int32_t | DPRCT_MAX_I32 = MAX_I32 |
static const int64_t | DPRCT_MAX_I64 = MAX_I64 |
static const uint16_t | DPRCT_MAX_UI16 = MAX_UI16 |
static const uint32_t | DPRCT_MAX_UI32 = MAX_UI32 |
static const uint64_t | DPRCT_MAX_UI64 = MAX_UI64 |
static const double | DPRCT_MIN_D = MIN_D |
static const float | DPRCT_MIN_F = MIN_F |
static const int16_t | DPRCT_MIN_I16 = MIN_I16 |
static const int32_t | DPRCT_MIN_I32 = MIN_I32 |
static const int64_t | DPRCT_MIN_I64 = MIN_I64 |
static const uint16_t | DPRCT_MIN_UI16 = MIN_UI16 |
static const uint32_t | DPRCT_MIN_UI32 = MIN_UI32 |
static const uint64_t | DPRCT_MIN_UI64 = MIN_UI64 |
static const size_t | IGN_EIGHT_SIZE_T = 8u |
size_t type with a value of 8 More... | |
static const size_t | IGN_FIVE_SIZE_T = 5u |
size_t type with a value of 5 More... | |
static const size_t | IGN_FOUR_SIZE_T = 4u |
size_t type with a value of 4 More... | |
static const size_t | IGN_NINE_SIZE_T = 9u |
size_t type with a value of 9 More... | |
static const size_t | IGN_ONE_SIZE_T = 1u |
size_t type with a value of 1 More... | |
static const size_t | IGN_SEVEN_SIZE_T = 7u |
size_t type with a value of 7 More... | |
static const size_t | IGN_SIX_SIZE_T = 6u |
size_t type with a value of 6 More... | |
static const size_t | IGN_THREE_SIZE_T = 3u |
size_t type with a value of 3 More... | |
static const size_t | IGN_TWO_SIZE_T = 2u |
size_t type with a value of 2 More... | |
static const size_t | IGN_ZERO_SIZE_T = 0u |
size_t type with a value of 0 More... | |
static const double | INF_D = std::numeric_limits<double>::infinity() |
Double positive infinite value. More... | |
static const float | INF_F = std::numeric_limits<float>::infinity() |
float positive infinite value More... | |
static const int16_t | INF_I16 = std::numeric_limits<int16_t>::infinity() |
16-bit unsigned integer positive infinite value More... | |
static const int32_t | INF_I32 = std::numeric_limits<int32_t>::infinity() |
32-bit unsigned integer positive infinite value More... | |
static const int64_t | INF_I64 = std::numeric_limits<int64_t>::infinity() |
64-bit unsigned integer positive infinite value More... | |
static const uint16_t | INF_UI16 = std::numeric_limits<uint16_t>::infinity() |
16-bit unsigned integer positive infinite value More... | |
static const uint32_t | INF_UI32 = std::numeric_limits<uint32_t>::infinity() |
32-bit unsigned integer positive infinite value More... | |
static const uint64_t | INF_UI64 = std::numeric_limits<uint64_t>::infinity() |
64-bit unsigned integer positive infinite value More... | |
static const double | LOW_D = std::numeric_limits<double>::lowest() |
Double low value, equivalent to -MAX_D. More... | |
static const float | LOW_F = std::numeric_limits<float>::lowest() |
Float low value, equivalent to -MAX_F. More... | |
static const int16_t | LOW_I16 = std::numeric_limits<int16_t>::lowest() |
16bit unsigned integer lowest value. This is equivalent to IGN_INT16_MIN, and is defined here for completeness. More... | |
static const int32_t | LOW_I32 = std::numeric_limits<int32_t>::lowest() |
32bit unsigned integer lowest value. This is equivalent to IGN_INT32_MIN, and is defined here for completeness. More... | |
static const int64_t | LOW_I64 = std::numeric_limits<int64_t>::lowest() |
64bit unsigned integer lowest value. This is equivalent to IGN_INT64_MIN, and is defined here for completeness. More... | |
static const uint16_t | LOW_UI16 = std::numeric_limits<uint16_t>::lowest() |
16bit unsigned integer lowest value. This is equivalent to IGN_UINT16_MIN, and is defined here for completeness. More... | |
static const uint32_t | LOW_UI32 = std::numeric_limits<uint32_t>::lowest() |
32bit unsigned integer lowest value. This is equivalent to IGN_UINT32_MIN, and is defined here for completeness. More... | |
static const uint64_t | LOW_UI64 = std::numeric_limits<uint64_t>::lowest() |
64bit unsigned integer lowest value. This is equivalent to IGN_UINT64_MIN, and is defined here for completeness. More... | |
static const double | MAX_D = std::numeric_limits<double>::max() |
Double maximum value. This value will be similar to 1.79769e+308. More... | |
static const float | MAX_F = std::numeric_limits<float>::max() |
Float maximum value. This value will be similar to 3.40282e+38. More... | |
static const int16_t | MAX_I16 = std::numeric_limits<int16_t>::max() |
16bit unsigned integer maximum value More... | |
static const int32_t | MAX_I32 = std::numeric_limits<int32_t>::max() |
32bit unsigned integer maximum value More... | |
static const int64_t | MAX_I64 = std::numeric_limits<int64_t>::max() |
64bit unsigned integer maximum value More... | |
static const uint16_t | MAX_UI16 = std::numeric_limits<uint16_t>::max() |
16bit unsigned integer maximum value More... | |
static const uint32_t | MAX_UI32 = std::numeric_limits<uint32_t>::max() |
32bit unsigned integer maximum value More... | |
static const uint64_t | MAX_UI64 = std::numeric_limits<uint64_t>::max() |
64bit unsigned integer maximum value More... | |
static const double | MIN_D = std::numeric_limits<double>::min() |
Double min value. This value will be similar to 2.22507e-308. More... | |
static const float | MIN_F = std::numeric_limits<float>::min() |
Float minimum value. This value will be similar to 1.17549e-38. More... | |
static const int16_t | MIN_I16 = std::numeric_limits<int16_t>::min() |
16bit unsigned integer minimum value More... | |
static const int32_t | MIN_I32 = std::numeric_limits<int32_t>::min() |
32bit unsigned integer minimum value More... | |
static const int64_t | MIN_I64 = std::numeric_limits<int64_t>::min() |
64bit unsigned integer minimum value More... | |
static const uint16_t | MIN_UI16 = std::numeric_limits<uint16_t>::min() |
16bit unsigned integer minimum value More... | |
static const uint32_t | MIN_UI32 = std::numeric_limits<uint32_t>::min() |
32bit unsigned integer minimum value More... | |
static const uint64_t | MIN_UI64 = std::numeric_limits<uint64_t>::min() |
64bit unsigned integer minimum value More... | |
static const double | NAN_D = std::numeric_limits<double>::quiet_NaN() |
Returns the representation of a quiet not a number (NAN) More... | |
static const float | NAN_F = std::numeric_limits<float>::quiet_NaN() |
Returns the representation of a quiet not a number (NAN) More... | |
static const int | NAN_I = std::numeric_limits<int>::quiet_NaN() |
Returns the representation of a quiet not a number (NAN) More... | |
static const std::regex | time_regex ("^([0-9]+ ){0,1}" "(?:([1-9]:|[0-1][0-9]:|2[0-3]:){0,1}" "([0-9]:|[0-5][0-9]:)){0,1}" "(?:([0-9]|[0-5][0-9]){0,1}" "(\\.[0-9]{1,3}){0,1})$") |
Detailed Description
Math classes and function useful in robot applications.
Typedef Documentation
◆ AdditivelySeparableScalarField3d
using AdditivelySeparableScalarField3d = AdditivelySeparableScalarField3<ScalarFunctionT, double> |
◆ AdditivelySeparableScalarField3f
using AdditivelySeparableScalarField3f = AdditivelySeparableScalarField3<ScalarFunctionT, float> |
◆ Boxd
◆ Boxf
◆ Boxi
◆ Capsuled
◆ Capsulef
◆ Capsulei
◆ clock
typedef std::chrono::steady_clock clock |
◆ Cylinderd
◆ Cylinderf
◆ Cylinderi
◆ days
typedef std::chrono::duration<uint64_t, std::ratio<86400> > days |
This will exist in C++-20.
◆ Ellipsoidd
Ellipsoid< double > Ellipsoidd |
Ellipsoid with double precision.
◆ Ellipsoidf
Ellipsoid< float > Ellipsoidf |
Ellipsoid with float precision.
◆ Ellipsoidi
Ellipsoid< int > Ellipsoidi |
Ellipsoid with integer precision.
◆ GeneratorType
typedef std::mt19937 GeneratorType |
◆ Inertiald
◆ Inertialf
◆ IntersectionPoints
using IntersectionPoints = std::set<Vector3<T>, WellOrderedVectors<T> > |
This is the type used for deduplicating and returning the set of intersections.
◆ Intervald
◆ Intervalf
◆ Line2d
◆ Line2f
◆ Line2i
◆ Line3d
◆ Line3f
◆ Line3i
◆ MassMatrix3d
typedef MassMatrix3<double> MassMatrix3d |
◆ MassMatrix3f
typedef MassMatrix3<float> MassMatrix3f |
◆ Matrix3d
◆ Matrix3f
◆ Matrix3i
◆ Matrix4d
◆ Matrix4f
◆ Matrix4i
◆ Matrix6d
◆ Matrix6f
◆ Matrix6i
◆ NormalRealDist
typedef std::normal_distribution<double> NormalRealDist |
◆ OrientedBoxd
typedef OrientedBox<double> OrientedBoxd |
◆ OrientedBoxf
typedef OrientedBox<float> OrientedBoxf |
◆ OrientedBoxi
typedef OrientedBox<int> OrientedBoxi |
◆ PairInput
using PairInput = uint32_t |
◆ PairOutput
using PairOutput = uint64_t |
◆ PiecewiseScalarField3d
using PiecewiseScalarField3d = PiecewiseScalarField3<ScalarField3T, double> |
◆ PiecewiseScalarField3f
using PiecewiseScalarField3f = PiecewiseScalarField3<ScalarField3T, float> |
◆ Planed
◆ Planef
◆ Planei
◆ Polynomial3d
using Polynomial3d = Polynomial3<double> |
◆ Polynomial3f
using Polynomial3f = Polynomial3<float> |
◆ Pose3d
◆ Pose3f
◆ Pose3i
◆ Quaterniond
typedef Quaternion<double> Quaterniond |
◆ Quaternionf
typedef Quaternion<float> Quaternionf |
◆ Quaternioni
typedef Quaternion<int> Quaternioni |
◆ Region3d
◆ Region3f
◆ Sphered
◆ Spheref
◆ Spherei
◆ Triangle3d
typedef Triangle3<double> Triangle3d |
Double specialization of the Triangle class.
◆ Triangle3f
typedef Triangle3<float> Triangle3f |
Float specialization of the Triangle class.
◆ Triangle3i
typedef Triangle3<int> Triangle3i |
Integer specialization of the Triangle class.
◆ Triangled
◆ Trianglef
◆ Trianglei
◆ UniformIntDist
typedef std::uniform_int_distribution<int32_t> UniformIntDist |
◆ UniformRealDist
typedef std::uniform_real_distribution<double> UniformRealDist |
◆ Vector2d
◆ Vector2f
◆ Vector2i
◆ Vector3d
◆ Vector3f
◆ Vector3i
◆ Vector4d
◆ Vector4f
◆ Vector4i
Enumeration Type Documentation
◆ MaterialType
|
strong |
This enum lists the supported material types. A value can be used to create a Material instance. Source: https://en.wikipedia.org/wiki/Density.
- See also
- Material
Function Documentation
◆ appendToStream() [1/2]
|
inline |
Append a number to a stream, specialized for int.
- Parameters
-
[out] _out Output stream. [in] _number Number to append.
◆ appendToStream() [2/2]
|
inline |
Append a number to a stream. Makes sure "-0" is returned as "0".
- Parameters
-
[out] _out Output stream. [in] _number Number to append.
References std::fpclassify().
◆ breakDownDurations()
std::tuple<Durations...> ignition::math::breakDownDurations | ( | DurationIn | d | ) |
break down durations NOTE: the template arguments must be properly ordered according to magnitude and there can be no duplicates. This function uses the braces initializer to split all the templated duration. The initializer will be called recursievely due the ...
- Parameters
-
[in] d Duration to break down
- Returns
- A tuple based on the durations specified
Referenced by durationToString(), and timePointToString().
◆ clamp()
|
inline |
Simple clamping function.
- Parameters
-
[in] _v value [in] _min minimum [in] _max maximum
References std::max(), and std::min().
Referenced by Matrix3< T >::Col(), Line3< T >::Distance(), Matrix6< T >::operator()(), Matrix3< T >::operator()(), Matrix4< T >::operator()(), Triangle< T >::operator[](), Triangle3< T >::operator[](), Line2< T >::operator[](), Line3< T >::operator[](), Vector2< T >::operator[](), Vector4< T >::operator[](), Vector3< Precision >::operator[](), Triangle< T >::Set(), and Triangle3< T >::Set().
◆ durationToSecNsec()
|
inline |
Convert a std::chrono::steady_clock::duration to a seconds and nanoseconds pair.
- Parameters
-
[in] _dur The duration to convert.
- Returns
- A pair where the first element is the number of seconds and the second is the number of nanoseconds.
◆ durationToString()
|
inline |
Convert a std::chrono::steady_clock::duration to a string.
- Parameters
-
[in] _duration The std::chrono::steady_clock::duration to convert.
- Returns
- A string formatted with the duration
References breakDownDurations(), std::fixed(), std::setfill(), std::setprecision(), and std::setw().
◆ equal()
|
inline |
check if two values are equal, within a tolerance
- Parameters
-
[in] _a the first value [in] _b the second value [in] _epsilon the tolerance
References IGN_FP_VOLATILE.
Referenced by Line2< T >::Collinear(), Quaternion< Precision >::Correct(), Quaternion< Precision >::Equal(), Line2< T >::Intersect(), Triangle3< T >::Intersects(), Matrix4< T >::IsAffine(), Line2< T >::Parallel(), and Line2< T >::Slope().
◆ fixnan() [1/2]
|
inline |
Fix a nan value.
- Parameters
-
[in] _v Value to correct.
- Returns
- 0 if _v is NaN, _v otherwise.
References std::isinf(), and isnan().
◆ fixnan() [2/2]
|
inline |
Fix a nan value.
- Parameters
-
[in] _v Value to correct.
- Returns
- 0 if _v is NaN, _v otherwise.
References std::isinf(), and isnan().
◆ greaterOrNearEqual()
|
inline |
inequality test, within a tolerance
- Parameters
-
[in] _a the first value [in] _b the second value [in] _epsilon the tolerance
◆ isEven() [1/2]
|
inline |
Check if parameter is even.
- Parameters
-
[in] _v Value to check.
- Returns
- True if _v is even.
◆ isEven() [2/2]
|
inline |
Check if parameter is even.
- Parameters
-
[in] _v Value to check.
- Returns
- True if _v is even.
◆ isnan() [1/2]
|
inline |
check if a double is NaN
- Parameters
-
[in] _v the value
- Returns
- true if _v is not a number, false otherwise
References std::isnan().
◆ isnan() [2/2]
|
inline |
check if a float is NaN
- Parameters
-
[in] _v the value
- Returns
- true if _v is not a number, false otherwise
References std::isnan().
Referenced by Polynomial3< T >::Evaluate(), and fixnan().
◆ isOdd() [1/2]
|
inline |
Check if parameter is odd.
- Parameters
-
[in] _v Value to check.
- Returns
- True if _v is odd.
◆ isOdd() [2/2]
|
inline |
Check if parameter is odd.
- Parameters
-
[in] _v Value to check.
- Returns
- True if _v is odd.
◆ isPowerOfTwo()
|
inline |
Is this a power of 2?
- Parameters
-
[in] _x the number
- Returns
- true if _x is a power of 2, false otherwise
Referenced by roundUpPowerOfTwo().
◆ isTimeString()
|
inline |
Check if the given string represents a time. An example time string is "0 00:00:00.000", which has the format "DAYS HOURS:MINUTES:SECONDS.MILLISECONDS".
- Returns
- True if the regex was able to split the string otherwise False
References string::empty(), string::erase(), string::length(), std::regex_search(), smatch::size(), std::stoi(), and time_regex.
◆ lessOrNearEqual()
|
inline |
inequality test, within a tolerance
- Parameters
-
[in] _a the first value [in] _b the second value [in] _epsilon the tolerance
◆ max()
|
inline |
get the maximum value of vector of values
- Parameters
-
[in] _values the vector of values
- Returns
- maximum
References numeric_limits::min(), and vector< T >::size().
◆ mean()
|
inline |
get mean of vector of values
- Parameters
-
[in] _values the vector of values
- Returns
- the mean
References vector< T >::size().
Referenced by ignition::math::eigen3::verticesToOrientedBox().
◆ min()
|
inline |
get the minimum value of vector of values
- Parameters
-
[in] _values the vector of values
- Returns
- minimum
References numeric_limits::max(), and vector< T >::size().
◆ Pair()
PairOutput ignition::math::Pair | ( | const PairInput | _a, |
const PairInput | _b | ||
) |
A pairing function that maps two values to a unique third value. This is an implement of Szudzik's function.
- Parameters
-
[in] _a First value, must be a non-negative integer. On Windows this value is uint16_t. On Linux/OSX this value is uint32_t. [in] _b Second value, must be a non-negative integer. On Windows this value is uint16_t. On Linux/OSX this value is uint32_t.
- Returns
- A unique non-negative integer value. On Windows the return value is uint32_t. On Linux/OSX the return value is uint64_t
- See also
- Unpair
◆ parseFloat()
|
inline |
parse string into float
- Parameters
-
_input the string
- Returns
- a floating point number (can be NaN) or 0 with a message in the error stream
References string::empty(), string::find_first_not_of(), NAN_D, and std::stod().
◆ parseInt()
|
inline |
parse string into an integer
- Parameters
-
[in] _input the string
- Returns
- an integer, 0 or 0 and a message in the error stream
References string::empty(), string::find_first_not_of(), NAN_I, and std::stoi().
◆ precision()
|
inline |
get value at a specified precision
- Parameters
-
[in] _a the number [in] _precision the precision
- Returns
- the value for the specified precision
References std::pow(), and std::round().
Referenced by Vector3< Precision >::Round(), and Quaternion< Precision >::Round().
◆ roundUpMultiple()
|
inline |
Round a number up to the nearest multiple. For example, if the input number is 12 and the multiple is 10, the result is 20. If the input number is negative, then the nearest multiple will be greater than or equal to the input number. For example, if the input number is -9 and the multiple is 2 then the output is -8.
- Parameters
-
[in] _num Input number to round up. [in] _multiple The multiple. If the multiple is <= zero, then the input number is returned.
- Returns
- The nearest multiple of _multiple that is greater than or equal to _num.
◆ roundUpPowerOfTwo()
|
inline |
Get the smallest power of two that is greater or equal to a given value.
- Parameters
-
[in] _x the number
- Returns
- the same value if _x is already a power of two. Otherwise, it returns the smallest power of two that is greater than _x
References isPowerOfTwo().
◆ secNsecToDuration()
|
inline |
Convert seconds and nanoseconds to std::chrono::steady_clock::duration.
- Parameters
-
[in] _sec The seconds to convert. [in] _nanosec The nanoseconds to convert.
- Returns
- A std::chrono::steady_clock::duration based on the number of seconds and the number of nanoseconds.
◆ secNsecToTimePoint()
|
inline |
Convert seconds and nanoseconds to std::chrono::steady_clock::time_point.
- Parameters
-
[in] _sec The seconds to convert. [in] _nanosec The nanoseconds to convert.
- Returns
- A std::chrono::steady_clock::time_point based on the number of seconds and the number of nanoseconds.
References std::chrono::duration_cast().
Referenced by stringToTimePoint(), and timePointToString().
◆ sgn()
|
inline |
The signum function.
Returns 0 for zero values, -1 for negative values, +1 for positive values.
- Parameters
-
[in] _value The value.
- Returns
- The signum of the value.
Referenced by signum().
◆ signum()
|
inline |
The signum function.
Returns 0 for zero values, -1 for negative values, +1 for positive values.
- Parameters
-
[in] _value The value.
- Returns
- The signum of the value.
References sgn().
◆ sort2()
|
inline |
Sort two numbers, such that _a <= _b.
- Parameters
-
[out] _a the first number [out] _b the second number
References std::swap().
Referenced by sort3().
◆ sort3()
|
inline |
Sort three numbers, such that _a <= _b <= _c.
- Parameters
-
[out] _a the first number [out] _b the second number [out] _c the third number
References sort2().
Referenced by MassMatrix3< T >::PrincipalMoments().
◆ splitTimeBasedOnTimeRegex()
|
inline |
Split a std::chrono::steady_clock::duration to a string.
- Parameters
-
[in] _timeString The string to convert in general format [out] numberDays number of days in the string [out] numberHours number of hours in the string [out] numberMinutes number of minutes in the string [out] numberSeconds number of seconds in the string [out] numberMilliseconds number of milliseconds in the string
- Returns
- True if the regex was able to split the string otherwise False
References string::empty(), string::erase(), string::length(), std::regex_search(), smatch::size(), std::stoi(), and time_regex.
Referenced by stringToDuration(), and stringToTimePoint().
◆ stringToDuration()
|
inline |
Convert a string to a std::chrono::steady_clock::duration.
- Parameters
-
[in] _timeString The string to convert in general format "dd hh:mm:ss.nnn" where n is millisecond value
- Returns
- A std::chrono::steady_clock::duration containing the string's time value. If it isn't possible to convert, the duration will be zero.
This will exist in C++-20
References string::empty(), and splitTimeBasedOnTimeRegex().
◆ stringToTimePoint()
|
inline |
Convert a string to a std::chrono::steady_clock::time_point.
- Parameters
-
[in] _timeString The string to convert in general format "dd hh:mm:ss.nnn" where n is millisecond value
- Returns
- A std::chrono::steady_clock::time_point containing the string's time value. If it isn't possible to convert, the time will be negative 1 second.
This will exist in C++-20
References string::empty(), secNsecToTimePoint(), and splitTimeBasedOnTimeRegex().
◆ timePointToSecNsec()
|
inline |
Convert a std::chrono::steady_clock::time_point to a seconds and nanoseconds pair.
- Parameters
-
[in] _time The time point to convert.
- Returns
- A pair where the first element is the number of seconds and the second is the number of nanoseconds.
References std::chrono::duration_cast().
◆ timePointToString()
|
inline |
Convert a std::chrono::steady_clock::time_point to a string.
- Parameters
-
[in] _point The std::chrono::steady_clock::time_point to convert.
- Returns
- A string formatted with the time_point
References breakDownDurations(), std::fixed(), secNsecToTimePoint(), std::setfill(), std::setprecision(), and std::setw().
◆ Unpair()
std::tuple<PairInput, PairInput> ignition::math::Unpair | ( | const PairOutput | _key | ) |
The reverse of the Pair function. Accepts a key, produced from the Pair function, and returns a tuple consisting of the two non-negative integer values used to create the _key.
- Parameters
-
[in] _key A non-negative integer generated from the Pair function. On Windows this value is uint32_t. On Linux/OSX, this value is uint64_t.
- Returns
- A tuple that consists of the two non-negative integers that will generate _key when used with the Pair function. On Windows the tuple contains two uint16_t values. On Linux/OSX the tuple contains two uint32_t values.
- See also
- Pair
◆ variance()
|
inline |
get variance of vector of values
- Parameters
-
[in] _values the vector of values
- Returns
- the squared deviation
References vector< T >::size().
Variable Documentation
◆ DPRCT_INF_D
|
static |
◆ DPRCT_INF_F
|
static |
◆ DPRCT_INF_I16
|
static |
◆ DPRCT_INF_I32
|
static |
◆ DPRCT_INF_I64
|
static |
◆ DPRCT_INF_UI16
|
static |
◆ DPRCT_INF_UI32
|
static |
◆ DPRCT_INF_UI64
|
static |
◆ DPRCT_LOW_D
|
static |
◆ DPRCT_LOW_F
|
static |
◆ DPRCT_LOW_I16
|
static |
◆ DPRCT_LOW_I32
|
static |
◆ DPRCT_LOW_I64
|
static |
◆ DPRCT_LOW_UI16
|
static |
◆ DPRCT_LOW_UI32
|
static |
◆ DPRCT_LOW_UI64
|
static |
◆ DPRCT_MAX_D
|
static |
◆ DPRCT_MAX_F
|
static |
◆ DPRCT_MAX_I16
|
static |
◆ DPRCT_MAX_I32
|
static |
◆ DPRCT_MAX_I64
|
static |
◆ DPRCT_MAX_UI16
|
static |
◆ DPRCT_MAX_UI32
|
static |
◆ DPRCT_MAX_UI64
|
static |
◆ DPRCT_MIN_D
|
static |
◆ DPRCT_MIN_F
|
static |
◆ DPRCT_MIN_I16
|
static |
◆ DPRCT_MIN_I32
|
static |
◆ DPRCT_MIN_I64
|
static |
◆ DPRCT_MIN_UI16
|
static |
◆ DPRCT_MIN_UI32
|
static |
◆ DPRCT_MIN_UI64
|
static |
◆ IGN_EIGHT_SIZE_T
|
static |
size_t type with a value of 8
◆ IGN_FIVE_SIZE_T
|
static |
size_t type with a value of 5
Referenced by Matrix6< T >::operator()().
◆ IGN_FOUR_SIZE_T
|
static |
size_t type with a value of 4
◆ IGN_NINE_SIZE_T
|
static |
size_t type with a value of 9
◆ IGN_ONE_SIZE_T
|
static |
size_t type with a value of 1
Referenced by Line2< T >::operator[](), Line3< T >::operator[](), and Vector2< T >::operator[]().
◆ IGN_SEVEN_SIZE_T
|
static |
size_t type with a value of 7
◆ IGN_SIX_SIZE_T
|
static |
size_t type with a value of 6
◆ IGN_THREE_SIZE_T
|
static |
size_t type with a value of 3
Referenced by Matrix4< T >::operator()(), and Vector4< T >::operator[]().
◆ IGN_TWO_SIZE_T
|
static |
size_t type with a value of 2
Referenced by Matrix3< T >::operator()(), Triangle< T >::operator[](), Triangle3< T >::operator[](), and Vector3< Precision >::operator[]().
◆ IGN_ZERO_SIZE_T
|
static |
size_t type with a value of 0
Referenced by Matrix6< T >::operator()(), Matrix3< T >::operator()(), Matrix4< T >::operator()(), Triangle< T >::operator[](), Triangle3< T >::operator[](), Line2< T >::operator[](), Line3< T >::operator[](), Vector2< T >::operator[](), Vector4< T >::operator[](), and Vector3< Precision >::operator[]().
◆ INF_D
|
static |
Double positive infinite value.
◆ INF_F
|
static |
float positive infinite value
◆ INF_I16
|
static |
16-bit unsigned integer positive infinite value
◆ INF_I32
|
static |
32-bit unsigned integer positive infinite value
Referenced by ignition::math::eigen3::verticesToOrientedBox().
◆ INF_I64
|
static |
64-bit unsigned integer positive infinite value
◆ INF_UI16
|
static |
16-bit unsigned integer positive infinite value
◆ INF_UI32
|
static |
32-bit unsigned integer positive infinite value
◆ INF_UI64
|
static |
64-bit unsigned integer positive infinite value
◆ LOW_D
|
static |
Double low value, equivalent to -MAX_D.
◆ LOW_F
|
static |
Float low value, equivalent to -MAX_F.
◆ LOW_I16
|
static |
16bit unsigned integer lowest value. This is equivalent to IGN_INT16_MIN, and is defined here for completeness.
◆ LOW_I32
|
static |
32bit unsigned integer lowest value. This is equivalent to IGN_INT32_MIN, and is defined here for completeness.
◆ LOW_I64
|
static |
64bit unsigned integer lowest value. This is equivalent to IGN_INT64_MIN, and is defined here for completeness.
◆ LOW_UI16
|
static |
16bit unsigned integer lowest value. This is equivalent to IGN_UINT16_MIN, and is defined here for completeness.
◆ LOW_UI32
|
static |
32bit unsigned integer lowest value. This is equivalent to IGN_UINT32_MIN, and is defined here for completeness.
◆ LOW_UI64
|
static |
64bit unsigned integer lowest value. This is equivalent to IGN_UINT64_MIN, and is defined here for completeness.
◆ MAX_D
|
static |
Double maximum value. This value will be similar to 1.79769e+308.
Referenced by ignition::math::graph::Dijkstra().
◆ MAX_F
|
static |
Float maximum value. This value will be similar to 3.40282e+38.
◆ MAX_I16
|
static |
16bit unsigned integer maximum value
◆ MAX_I32
|
static |
32bit unsigned integer maximum value
◆ MAX_I64
|
static |
64bit unsigned integer maximum value
◆ MAX_UI16
|
static |
16bit unsigned integer maximum value
◆ MAX_UI32
|
static |
32bit unsigned integer maximum value
◆ MAX_UI64
|
static |
64bit unsigned integer maximum value
◆ MIN_D
|
static |
Double min value. This value will be similar to 2.22507e-308.
Referenced by Quaternion< Precision >::Integrate().
◆ MIN_F
|
static |
Float minimum value. This value will be similar to 1.17549e-38.
◆ MIN_I16
|
static |
16bit unsigned integer minimum value
◆ MIN_I32
|
static |
32bit unsigned integer minimum value
◆ MIN_I64
|
static |
64bit unsigned integer minimum value
◆ MIN_UI16
|
static |
16bit unsigned integer minimum value
◆ MIN_UI32
|
static |
32bit unsigned integer minimum value
◆ MIN_UI64
|
static |
64bit unsigned integer minimum value
◆ NAN_D
|
static |
Returns the representation of a quiet not a number (NAN)
Referenced by parseFloat(), and Line2< T >::Slope().
◆ NAN_F
|
static |
Returns the representation of a quiet not a number (NAN)
◆ NAN_I
|
static |
Returns the representation of a quiet not a number (NAN)
Referenced by parseInt().
◆ time_regex
|
static |
Referenced by isTimeString(), and splitTimeBasedOnTimeRegex().