Gazebo Math

API Reference

7.4.0
gz::math Namespace Reference

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  InMemorySession
 An in-memory session. Loads the whole dataset in memory and performs queries. More...
 
class  InMemoryTimeVaryingVolumetricGridFactory
 Factory class for constructing an InMemoryTimeVaryingVolumetricGrid. 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 Gazebo 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
 The Pose3 class represents a 3D position and rotation. The position component is a Vector3, and the rotation is a Quaternion. More...
 
class  Quaternion
 A quaternion class that represents 3D rotations and orientations. Four scalar values, [w,x,y,z], are used represent orientations and rotations. 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  TimeVaryingVolumetricGrid
 A grid with interpolation where time can be varied. This class has no implementation to allow for different strategies. More...
 
class  TimeVaryingVolumetricGrid< T, V, InMemorySession< T, P >, P >
 Specialization of TimeVaryingVolumetricGrid which loads the whole of the dataset into memory. To construct this class use InMemoryTimeVaryingVolumetricGridFactory More...
 
class  TimeVaryingVolumetricGridLookupField
 Lookup table for a time-varying volumetric dataset. This is an unimplemented template as the actual methods depend on the underlying structure. The key idea is that one uses a session S to hold a session token. This is so that we don't keep doing O(logn) lookups and instead step along the axis. More...
 
class  TimeVaryingVolumetricGridLookupField< T, V, InMemorySession< T, V > >
 Specialized version of TimeVaryingVolumetricGridLookupField for in-memory lookup. It loads the whole dataset into memory. 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...
 
class  VolumetricGridLookupField
 Lookup table for a volumetric dataset. This class is used to lookup indices for a large dataset that's organized in a grid. This class is not meant to be used with non-grid like data sets. The grid may be sparse or non uniform and missing data points. 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 , typename V = T, typename P = T>
using InMemoryTimeVaryingVolumetricGrid = TimeVaryingVolumetricGrid< T, V, InMemorySession< T, P >, P >
 Alias for Specialization of TimeVaryingVolumetricGrid which loads the whole of the dataset into memory. More...
 
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<double> as Matrix3d. More...
 
typedef Matrix3< float > Matrix3f
 typedef Matrix3<float> as Matrix3f. More...
 
typedef Matrix3< int > Matrix3i
 typedef Matrix3<int> as Matrix3i. More...
 
typedef Matrix4< double > Matrix4d
 
typedef Matrix4< float > Matrix4f
 
typedef Matrix4< int > Matrix4i
 
typedef Matrix6< double > Matrix6d
 
typedef Matrix6< float > Matrix6f
 
typedef Matrix6< int > Matrix6i
 
using MovingWindowFilterd = MovingWindowFilter< double >
 
using MovingWindowFilterf = MovingWindowFilter< float >
 
using MovingWindowFilteri = MovingWindowFilter< int >
 
using MovingWindowFilterVector3d = MovingWindowFilter< Vector3d >
 
using MovingWindowFilterVector3f = MovingWindowFilter< Vector3f >
 
using MovingWindowFilterVector3i = MovingWindowFilter< Vector3i >
 
typedef std::normal_distribution< double > NormalRealDist
 
typedef OrientedBox< double > OrientedBoxd
 
typedef OrientedBox< float > OrientedBoxf
 
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<double> as Pose3d. More...
 
typedef Pose3< float > Pose3f
 typedef Pose3<float> as Pose3f. More...
 
typedef Quaternion< double > Quaterniond
 typedef Quaternion<double> as Quaterniond More...
 
typedef Quaternion< float > Quaternionf
 typedef Quaternion<float> as Quaternionf More...
 
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 >
clamp (T _v, T _min, T _max)
 Simple clamping function that constrains a value to a range defined by a min and max value. This function is equivalent to std::max(std::min(value, max), min). 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 double NaN value. More...
 
float fixnan (float _v)
 Fix a float NaN value. More...
 
template<typename T >
bool greaterOrNearEqual (const T &_a, const T &_b, const T &_epsilon=1e-6)
 Greater than or near test, within a tolerance. More...
 
bool isEven (const int _v)
 Check if an int is even. More...
 
bool isEven (const unsigned int _v)
 Check if an unsigned int 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 an int is odd. More...
 
bool isOdd (const unsigned int _v)
 Check if an unsigned int is odd. More...
 
bool isPowerOfTwo (unsigned int _x)
 Is the parameter 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)
 Less than or near test, within a tolerance. More...
 
template<typename T >
max (const std::vector< T > &_values)
 Get the maximum value of vector of values. More...
 
template<typename T >
mean (const std::vector< T > &_values)
 Get mean value in a vector of values. More...
 
template<typename 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 implementation 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 >
precision (const T &_a, const unsigned int &_precision)
 Get the 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 than 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, PairInputUnpair (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 >
variance (const std::vector< T > &_values)
 Get the variance of a vector of values. More...
 

Variables

static const size_t GZ_EIGHT_SIZE_T = 8u
 size_t type with a value of 8 More...
 
static const size_t GZ_FIVE_SIZE_T = 5u
 size_t type with a value of 5 More...
 
static const size_t GZ_FOUR_SIZE_T = 4u
 size_t type with a value of 4 More...
 
static const size_t GZ_NINE_SIZE_T = 9u
 size_t type with a value of 9 More...
 
static const size_t GZ_ONE_SIZE_T = 1u
 size_t type with a value of 1 More...
 
static const size_t GZ_SEVEN_SIZE_T = 7u
 size_t type with a value of 7 More...
 
static const size_t GZ_SIX_SIZE_T = 6u
 size_t type with a value of 6 More...
 
static const size_t GZ_THREE_SIZE_T = 3u
 size_t type with a value of 3 More...
 
static const size_t GZ_TWO_SIZE_T = 2u
 size_t type with a value of 2 More...
 
static const size_t GZ_ZERO_SIZE_T = 0u
 size_t type with a value of 0 More...
 
constexpr auto IGN_EIGHT_SIZE_T = &GZ_EIGHT_SIZE_T
 
constexpr auto IGN_FIVE_SIZE_T = &GZ_FIVE_SIZE_T
 
constexpr auto IGN_FOUR_SIZE_T = &GZ_FOUR_SIZE_T
 
constexpr auto IGN_NINE_SIZE_T = &GZ_NINE_SIZE_T
 
constexpr auto IGN_ONE_SIZE_T = &GZ_ONE_SIZE_T
 
constexpr auto IGN_SEVEN_SIZE_T = &GZ_SEVEN_SIZE_T
 
constexpr auto IGN_SIX_SIZE_T = &GZ_SIX_SIZE_T
 
constexpr auto IGN_THREE_SIZE_T = &GZ_THREE_SIZE_T
 
constexpr auto IGN_TWO_SIZE_T = &GZ_TWO_SIZE_T
 
constexpr auto IGN_ZERO_SIZE_T = &GZ_ZERO_SIZE_T
 
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 GZ_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 GZ_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 GZ_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 GZ_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 GZ_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 GZ_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...
 

Detailed Description

Math classes and function useful in robot applications.

Typedef Documentation

◆ AdditivelySeparableScalarField3d

◆ AdditivelySeparableScalarField3f

◆ Boxd

Box< double > Boxd

Box with double precision.

◆ Boxf

Box< float > Boxf

Box with float precision.

◆ Boxi

Box< int > Boxi

Box with integer precision.

◆ Capsuled

Capsule< double > Capsuled

Capsule with double precision.

◆ Capsulef

Capsule< float > Capsulef

Capsule with float precision.

◆ Capsulei

Capsule< int > Capsulei

Capsule with integer precision.

◆ clock

◆ Cylinderd

Cylinder< double > Cylinderd

Cylinder with double precision.

◆ Cylinderf

Cylinder< float > Cylinderf

Cylinder with float precision.

◆ Cylinderi

Cylinder with integer precision.

◆ 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 with float precision.

◆ Ellipsoidi

Ellipsoid with integer precision.

◆ GeneratorType

◆ Inertiald

typedef Inertial<double> Inertiald

◆ Inertialf

typedef Inertial<float> Inertialf

◆ InMemoryTimeVaryingVolumetricGrid

Alias for Specialization of TimeVaryingVolumetricGrid which loads the whole of the dataset into memory.

◆ IntersectionPoints

using IntersectionPoints = std::set<Vector3<T>, WellOrderedVectors<T> >

This is the type used for deduplicating and returning the set of intersections.

◆ Intervald

using Intervald = Interval<double>

◆ Intervalf

using Intervalf = Interval<float>

◆ Line2d

typedef Line2<double> Line2d

◆ Line2f

typedef Line2<float> Line2f

◆ Line2i

typedef Line2<int> Line2i

◆ Line3d

typedef Line3<double> Line3d

◆ Line3f

typedef Line3<float> Line3f

◆ Line3i

typedef Line3<int> Line3i

◆ MassMatrix3d

typedef MassMatrix3<double> MassMatrix3d

◆ MassMatrix3f

typedef MassMatrix3<float> MassMatrix3f

◆ Matrix3d

typedef Matrix3<double> Matrix3d

typedef Matrix3<double> as Matrix3d.

◆ Matrix3f

typedef Matrix3<float> Matrix3f

typedef Matrix3<float> as Matrix3f.

◆ Matrix3i

typedef Matrix3<int> Matrix3i

typedef Matrix3<int> as Matrix3i.

◆ Matrix4d

typedef Matrix4<double> Matrix4d

◆ Matrix4f

typedef Matrix4<float> Matrix4f

◆ Matrix4i

typedef Matrix4<int> Matrix4i

◆ Matrix6d

typedef Matrix6<double> Matrix6d

◆ Matrix6f

typedef Matrix6<float> Matrix6f

◆ Matrix6i

typedef Matrix6<int> Matrix6i

◆ MovingWindowFilterd

◆ MovingWindowFilterf

◆ MovingWindowFilteri

◆ MovingWindowFilterVector3d

◆ MovingWindowFilterVector3f

◆ MovingWindowFilterVector3i

◆ NormalRealDist

◆ OrientedBoxd

typedef OrientedBox<double> OrientedBoxd

◆ OrientedBoxf

typedef OrientedBox<float> OrientedBoxf

◆ PairInput

using PairInput = uint32_t

◆ PairOutput

using PairOutput = uint64_t

◆ PiecewiseScalarField3d

using PiecewiseScalarField3d = PiecewiseScalarField3<ScalarField3T, double>

◆ PiecewiseScalarField3f

using PiecewiseScalarField3f = PiecewiseScalarField3<ScalarField3T, float>

◆ Planed

typedef Plane<double> Planed

◆ Planef

typedef Plane<float> Planef

◆ Planei

typedef Plane<int> Planei

◆ Polynomial3d

using Polynomial3d = Polynomial3<double>

◆ Polynomial3f

using Polynomial3f = Polynomial3<float>

◆ Pose3d

typedef Pose3<double> Pose3d

typedef Pose3<double> as Pose3d.

◆ Pose3f

typedef Pose3<float> Pose3f

typedef Pose3<float> as Pose3f.

◆ Quaterniond

typedef Quaternion<double> Quaterniond

typedef Quaternion<double> as Quaterniond

◆ Quaternionf

typedef Quaternion<float> Quaternionf

typedef Quaternion<float> as Quaternionf

◆ Region3d

using Region3d = Region3<double>

◆ Region3f

using Region3f = Region3<float>

◆ Sphered

Sphere< double > Sphered

Sphere with double precision.

◆ Spheref

Sphere< float > Spheref

Sphere with float precision.

◆ Spherei

Sphere< int > Spherei

Sphere with integer precision.

◆ 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

typedef Triangle<double> Triangled

Double specialization of the Triangle class.

◆ Trianglef

typedef Triangle<float> Trianglef

Float specialization of the Triangle class.

◆ Trianglei

typedef Triangle<int> Trianglei

Integer specialization of the Triangle class.

◆ UniformIntDist

◆ UniformRealDist

◆ Vector2d

typedef Vector2<double> Vector2d

◆ Vector2f

typedef Vector2<float> Vector2f

◆ Vector2i

typedef Vector2<int> Vector2i

◆ Vector3d

typedef Vector3<double> Vector3d

◆ Vector3f

typedef Vector3<float> Vector3f

◆ Vector3i

typedef Vector3<int> Vector3i

◆ Vector4d

typedef Vector4<double> Vector4d

◆ Vector4f

typedef Vector4<float> Vector4f

◆ Vector4i

typedef Vector4<int> Vector4i

Enumeration Type Documentation

◆ MaterialType

enum 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
Enumerator
STYROFOAM 

Styrofoam, density = 75.0 kg/m^3 String name = "styrofoam".

PINE 

Pine, density = 373.0 kg/m^3 String name = "pine".

WOOD 

Wood, density = 700.0 kg/m^3 String name = "wood".

OAK 

Oak, density = 710.0 kg/m^3 String name = "oak".

PLASTIC 

Plastic, density = 1175.0 kg/m^3 String name = "plastic".

CONCRETE 

Concrete, density = 2000.0 kg/m^3 String name = "concrete".

ALUMINUM 

Aluminum, density = 2700.0 kg/m^3 String name = "aluminum".

STEEL_ALLOY 

Steel alloy, density = 7600.0 kg/m^3 String name = "steel_alloy".

STEEL_STAINLESS 

Stainless steel, density = 7800.0 kg/m^3 String name = "steel_stainless".

IRON 

Iron, density = 7870.0 kg/m^3 String name = "iron".

BRASS 

Brass, density = 8600.0 kg/m^3 String name = "brass".

COPPER 

Copper, density = 8940.0 kg/m^3 String name = "copper".

TUNGSTEN 

Tungsten, density = 19300.0 kg/m^3 String name = "tungsten".

UNKNOWN_MATERIAL 

Represents an invalid or unknown material.

Function Documentation

◆ appendToStream() [1/2]

void gz::math::appendToStream ( std::ostream _out,
int  _number 
)
inline

Append a number to a stream, specialized for int.

Parameters
[out]_outOutput stream.
[in]_numberNumber to append.

◆ appendToStream() [2/2]

void gz::math::appendToStream ( std::ostream _out,
_number 
)
inline

Append a number to a stream. Makes sure "-0" is returned as "0".

Parameters
[out]_outOutput stream.
[in]_numberNumber to append.

References std::fpclassify().

◆ breakDownDurations()

std::tuple<Durations...> gz::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]dDuration to break down
Returns
A tuple based on the durations specified

◆ clamp()

T gz::math::clamp ( _v,
_min,
_max 
)
inline

Simple clamping function that constrains a value to a range defined by a min and max value. This function is equivalent to std::max(std::min(value, max), min).

Parameters
[in]_vValue to clamp
[in]_minMinimum allowed value.
[in]_maxMaximum allowed value.
Returns
The value _v clamped to the range defined by _min and _max.

References std::max(), and std::min().

Referenced by 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(), Triangle3< T >::Set(), Matrix3< T >::Set(), and Matrix3< T >::SetCol().

◆ durationToSecNsec()

std::pair<int64_t, int64_t> gz::math::durationToSecNsec ( const std::chrono::steady_clock::duration &  _dur)

Convert a std::chrono::steady_clock::duration to a seconds and nanoseconds pair.

Parameters
[in]_durThe duration to convert.
Returns
A pair where the first element is the number of seconds and the second is the number of nanoseconds.

◆ durationToString()

std::string gz::math::durationToString ( const std::chrono::steady_clock::duration &  _duration)

Convert a std::chrono::steady_clock::duration to a string.

Parameters
[in]_durationThe std::chrono::steady_clock::duration to convert.
Returns
A string formatted with the duration

◆ equal()

bool gz::math::equal ( const T &  _a,
const T &  _b,
const T &  _epsilon = T(1e-6) 
)
inline

Check if two values are equal, within a tolerance.

Parameters
[in]_aThe first value.
[in]_bThe second value.
[in]_epsilonThe tolerance
Returns
True if the two values fall within the given tolerance.

References GZ_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]

double gz::math::fixnan ( double  _v)
inline

Fix a double NaN value.

Parameters
[in]_vValue to correct.
Returns
0 if _v is NaN or is infinite, _v otherwise.

References std::isinf(), and isnan().

◆ fixnan() [2/2]

float gz::math::fixnan ( float  _v)
inline

Fix a float NaN value.

Parameters
[in]_vValue to correct.
Returns
0 if _v is NaN or infinite, _v otherwise.

References std::isinf(), and isnan().

◆ greaterOrNearEqual()

bool gz::math::greaterOrNearEqual ( const T &  _a,
const T &  _b,
const T &  _epsilon = 1e-6 
)
inline

Greater than or near test, within a tolerance.

Parameters
[in]_aThe first value.
[in]_bThe second value.
[in]_epsilonThe tolerance.
Returns
True if _a > _b - _epsilon.

◆ isEven() [1/2]

bool gz::math::isEven ( const int  _v)
inline

Check if an int is even.

Parameters
[in]_vValue to check.
Returns
True if _v is even.

◆ isEven() [2/2]

bool gz::math::isEven ( const unsigned int  _v)
inline

Check if an unsigned int is even.

Parameters
[in]_vValue to check.
Returns
True if _v is even.

◆ isnan() [1/2]

bool gz::math::isnan ( double  _v)
inline

Check if a double is NaN.

Parameters
[in]_vThe value to check
Returns
True if _v is not a number, false otherwise.

References std::isnan().

◆ isnan() [2/2]

bool gz::math::isnan ( float  _v)
inline

Check if a float is NaN.

Parameters
[in]_vThe value to check.
Returns
True if _v is not a number, false otherwise.

References std::isnan().

Referenced by Polynomial3< T >::Evaluate(), and fixnan().

◆ isOdd() [1/2]

bool gz::math::isOdd ( const int  _v)
inline

Check if an int is odd.

Parameters
[in]_vValue to check.
Returns
True if _v is odd.

◆ isOdd() [2/2]

bool gz::math::isOdd ( const unsigned int  _v)
inline

Check if an unsigned int is odd.

Parameters
[in]_vValue to check.
Returns
True if _v is odd.

◆ isPowerOfTwo()

bool gz::math::isPowerOfTwo ( unsigned int  _x)
inline

Is the parameter a power of 2?

Parameters
[in]_xThe number to check.
Returns
True if _x is a power of 2, false otherwise.

Referenced by roundUpPowerOfTwo().

◆ isTimeString()

bool gz::math::isTimeString ( const std::string _timeString)
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 splitTimeBasedOnTimeRegex().

◆ lessOrNearEqual()

bool gz::math::lessOrNearEqual ( const T &  _a,
const T &  _b,
const T &  _epsilon = 1e-6 
)
inline

Less than or near test, within a tolerance.

Parameters
[in]_aThe first value.
[in]_bThe second value.
[in]_epsilonThe tolerance.
Returns
True if _a < _b + _tol.

◆ max()

T gz::math::max ( const std::vector< T > &  _values)
inline

Get the maximum value of vector of values.

Parameters
[in]_valuesThe vector of values.
Returns
Maximum value in the vector.

References std::begin(), std::end(), and std::max_element().

Referenced by Vector3< Precision >::MaxAbs().

◆ mean()

T gz::math::mean ( const std::vector< T > &  _values)
inline

Get mean value in a vector of values.

Parameters
[in]_valuesThe vector of values.
Returns
The mean value in the provided vector.

References vector< T >::size().

Referenced by gz::math::eigen3::verticesToOrientedBox().

◆ min()

T gz::math::min ( const std::vector< T > &  _values)
inline

Get the minimum value of vector of values.

Parameters
[in]_valuesThe vector of values.
Returns
Minimum value in the vector.

References std::begin(), std::end(), and std::min_element().

Referenced by Vector3< Precision >::MinAbs().

◆ Pair()

PairOutput gz::math::Pair ( const PairInput  _a,
const PairInput  _b 
)

A pairing function that maps two values to a unique third value. This is an implementation of Szudzik's function.

Parameters
[in]_aFirst value, must be a non-negative integer. On Windows this value is uint16_t. On Linux/OSX this value is uint32_t.
[in]_bSecond 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()

double gz::math::parseFloat ( const std::string _input)

parse string into float.

Parameters
[in]_inputThe string.
Returns
A floating point number (can be NaN) or NAN_D if the _input could not be parsed.

◆ parseInt()

int gz::math::parseInt ( const std::string _input)

Parse string into an integer.

Parameters
[in]_inputThe input string.
Returns
An integer, or NAN_I if unable to parse the input.

◆ precision()

T gz::math::precision ( const T &  _a,
const unsigned int &  _precision 
)
inline

Get the value at a specified precision.

Parameters
[in]_aThe number.
[in]_precisionThe precision.
Returns
The value for the specified precision.

References std::pow(), and std::round().

Referenced by Vector3< Precision >::Round(), and Quaternion< Precision >::Round().

◆ roundUpMultiple()

int gz::math::roundUpMultiple ( int  _num,
int  _multiple 
)
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]_numInput number to round up.
[in]_multipleThe 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()

unsigned int gz::math::roundUpPowerOfTwo ( unsigned int  _x)
inline

Get the smallest power of two that is greater than or equal to a given value.

Parameters
[in]_xThe value which marks the lower bound of the result.
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()

std::chrono::steady_clock::duration gz::math::secNsecToDuration ( const uint64_t &  _sec,
const uint64_t &  _nanosec 
)

Convert seconds and nanoseconds to std::chrono::steady_clock::duration.

Parameters
[in]_secThe seconds to convert.
[in]_nanosecThe nanoseconds to convert.
Returns
A std::chrono::steady_clock::duration based on the number of seconds and the number of nanoseconds.

◆ secNsecToTimePoint()

std::chrono::steady_clock::time_point gz::math::secNsecToTimePoint ( const uint64_t &  _sec,
const uint64_t &  _nanosec 
)

Convert seconds and nanoseconds to std::chrono::steady_clock::time_point.

Parameters
[in]_secThe seconds to convert.
[in]_nanosecThe nanoseconds to convert.
Returns
A std::chrono::steady_clock::time_point based on the number of seconds and the number of nanoseconds.

◆ sgn()

int gz::math::sgn ( _value)
inline

The signum function.

Returns 0 for zero values, -1 for negative values, +1 for positive values.

Parameters
[in]_valueThe value.
Returns
The signum of the value.

Referenced by signum().

◆ signum()

int gz::math::signum ( _value)
inline

The signum function.

Returns 0 for zero values, -1 for negative values, +1 for positive values.

Parameters
[in]_valueThe value.
Returns
The signum of the value.

References sgn().

◆ sort2()

void gz::math::sort2 ( T &  _a,
T &  _b 
)
inline

Sort two numbers, such that _a <= _b.

Parameters
[in,out]_aThe first number. This variable will contain the lower of the two values after this function completes.
[in,out]_bThe second number. This variable will contain the higher of the two values after this function completes.

References std::swap().

Referenced by sort3().

◆ sort3()

void gz::math::sort3 ( T &  _a,
T &  _b,
T &  _c 
)
inline

Sort three numbers, such that _a <= _b <= _c.

Parameters
[in,out]_aThe first number. This variable will contain the lowest of the three values after this function completes.
[in,out]_bThe second number. This variable will contain the middle of the three values after this function completes.
[in,out]_cThe third number. This variable will contain the highest of the three values after this function completes.

References sort2().

Referenced by MassMatrix3< T >::PrincipalMoments().

◆ splitTimeBasedOnTimeRegex()

bool gz::math::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.

Parameters
[in]_timeStringThe string to convert in general format
[out]numberDaysnumber of days in the string
[out]numberHoursnumber of hours in the string
[out]numberMinutesnumber of minutes in the string
[out]numberSecondsnumber of seconds in the string
[out]numberMillisecondsnumber of milliseconds in the string
Returns
True if the regex was able to split the string otherwise False

Referenced by isTimeString().

◆ stringToDuration()

std::chrono::steady_clock::duration gz::math::stringToDuration ( const std::string _timeString)

Convert a string to a std::chrono::steady_clock::duration.

Parameters
[in]_timeStringThe 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.

◆ stringToTimePoint()

std::chrono::steady_clock::time_point gz::math::stringToTimePoint ( const std::string _timeString)

Convert a string to a std::chrono::steady_clock::time_point.

Parameters
[in]_timeStringThe 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.

◆ timePointToSecNsec()

std::pair<int64_t, int64_t> gz::math::timePointToSecNsec ( const std::chrono::steady_clock::time_point &  _time)

Convert a std::chrono::steady_clock::time_point to a seconds and nanoseconds pair.

Parameters
[in]_timeThe time point to convert.
Returns
A pair where the first element is the number of seconds and the second is the number of nanoseconds.

◆ timePointToString()

std::string gz::math::timePointToString ( const std::chrono::steady_clock::time_point &  _point)

Convert a std::chrono::steady_clock::time_point to a string.

Parameters
[in]_pointThe std::chrono::steady_clock::time_point to convert.
Returns
A string formatted with the time_point

◆ Unpair()

std::tuple<PairInput, PairInput> gz::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]_keyA 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()

T gz::math::variance ( const std::vector< T > &  _values)
inline

Get the variance of a vector of values.

Parameters
[in]_valuesThe vector of values.
Returns
The squared deviation of the vector of values.

References vector< T >::size().

Variable Documentation

◆ GZ_EIGHT_SIZE_T

const size_t GZ_EIGHT_SIZE_T = 8u
static

size_t type with a value of 8

◆ GZ_FIVE_SIZE_T

const size_t GZ_FIVE_SIZE_T = 5u
static

size_t type with a value of 5

Referenced by Matrix6< T >::operator()().

◆ GZ_FOUR_SIZE_T

const size_t GZ_FOUR_SIZE_T = 4u
static

size_t type with a value of 4

◆ GZ_NINE_SIZE_T

const size_t GZ_NINE_SIZE_T = 9u
static

size_t type with a value of 9

◆ GZ_ONE_SIZE_T

const size_t GZ_ONE_SIZE_T = 1u
static

size_t type with a value of 1

Referenced by Line2< T >::operator[](), Line3< T >::operator[](), and Vector2< T >::operator[]().

◆ GZ_SEVEN_SIZE_T

const size_t GZ_SEVEN_SIZE_T = 7u
static

size_t type with a value of 7

◆ GZ_SIX_SIZE_T

const size_t GZ_SIX_SIZE_T = 6u
static

size_t type with a value of 6

◆ GZ_THREE_SIZE_T

const size_t GZ_THREE_SIZE_T = 3u
static

size_t type with a value of 3

Referenced by Matrix4< T >::operator()(), and Vector4< T >::operator[]().

◆ GZ_TWO_SIZE_T

const size_t GZ_TWO_SIZE_T = 2u
static

◆ GZ_ZERO_SIZE_T

◆ IGN_EIGHT_SIZE_T

constexpr auto IGN_EIGHT_SIZE_T = &GZ_EIGHT_SIZE_T
constexpr

◆ IGN_FIVE_SIZE_T

constexpr auto IGN_FIVE_SIZE_T = &GZ_FIVE_SIZE_T
constexpr

◆ IGN_FOUR_SIZE_T

constexpr auto IGN_FOUR_SIZE_T = &GZ_FOUR_SIZE_T
constexpr

◆ IGN_NINE_SIZE_T

constexpr auto IGN_NINE_SIZE_T = &GZ_NINE_SIZE_T
constexpr

◆ IGN_ONE_SIZE_T

constexpr auto IGN_ONE_SIZE_T = &GZ_ONE_SIZE_T
constexpr

◆ IGN_SEVEN_SIZE_T

constexpr auto IGN_SEVEN_SIZE_T = &GZ_SEVEN_SIZE_T
constexpr

◆ IGN_SIX_SIZE_T

constexpr auto IGN_SIX_SIZE_T = &GZ_SIX_SIZE_T
constexpr

◆ IGN_THREE_SIZE_T

constexpr auto IGN_THREE_SIZE_T = &GZ_THREE_SIZE_T
constexpr

◆ IGN_TWO_SIZE_T

constexpr auto IGN_TWO_SIZE_T = &GZ_TWO_SIZE_T
constexpr

◆ IGN_ZERO_SIZE_T

constexpr auto IGN_ZERO_SIZE_T = &GZ_ZERO_SIZE_T
constexpr

◆ INF_D

const double INF_D = std::numeric_limits<double>::infinity()
static

Double positive infinite value.

◆ INF_F

const float INF_F = std::numeric_limits<float>::infinity()
static

float positive infinite value

◆ INF_I16

const int16_t INF_I16 = std::numeric_limits<int16_t>::infinity()
static

16-bit unsigned integer positive infinite value

◆ INF_I32

const int32_t INF_I32 = std::numeric_limits<int32_t>::infinity()
static

32-bit unsigned integer positive infinite value

Referenced by gz::math::eigen3::verticesToOrientedBox().

◆ INF_I64

const int64_t INF_I64 = std::numeric_limits<int64_t>::infinity()
static

64-bit unsigned integer positive infinite value

◆ INF_UI16

const uint16_t INF_UI16 = std::numeric_limits<uint16_t>::infinity()
static

16-bit unsigned integer positive infinite value

◆ INF_UI32

const uint32_t INF_UI32 = std::numeric_limits<uint32_t>::infinity()
static

32-bit unsigned integer positive infinite value

◆ INF_UI64

const uint64_t INF_UI64 = std::numeric_limits<uint64_t>::infinity()
static

64-bit unsigned integer positive infinite value

◆ LOW_D

const double LOW_D = std::numeric_limits<double>::lowest()
static

Double low value, equivalent to -MAX_D.

◆ LOW_F

const float LOW_F = std::numeric_limits<float>::lowest()
static

Float low value, equivalent to -MAX_F.

◆ LOW_I16

const int16_t LOW_I16 = std::numeric_limits<int16_t>::lowest()
static

16bit unsigned integer lowest value. This is equivalent to GZ_INT16_MIN, and is defined here for completeness.

◆ LOW_I32

const int32_t LOW_I32 = std::numeric_limits<int32_t>::lowest()
static

32bit unsigned integer lowest value. This is equivalent to GZ_INT32_MIN, and is defined here for completeness.

◆ LOW_I64

const int64_t LOW_I64 = std::numeric_limits<int64_t>::lowest()
static

64bit unsigned integer lowest value. This is equivalent to GZ_INT64_MIN, and is defined here for completeness.

◆ LOW_UI16

const uint16_t LOW_UI16 = std::numeric_limits<uint16_t>::lowest()
static

16bit unsigned integer lowest value. This is equivalent to GZ_UINT16_MIN, and is defined here for completeness.

◆ LOW_UI32

const uint32_t LOW_UI32 = std::numeric_limits<uint32_t>::lowest()
static

32bit unsigned integer lowest value. This is equivalent to GZ_UINT32_MIN, and is defined here for completeness.

◆ LOW_UI64

const uint64_t LOW_UI64 = std::numeric_limits<uint64_t>::lowest()
static

64bit unsigned integer lowest value. This is equivalent to GZ_UINT64_MIN, and is defined here for completeness.

◆ MAX_D

const double MAX_D = std::numeric_limits<double>::max()
static

Double maximum value. This value will be similar to 1.79769e+308.

Referenced by gz::math::graph::Dijkstra().

◆ MAX_F

const float MAX_F = std::numeric_limits<float>::max()
static

Float maximum value. This value will be similar to 3.40282e+38.

◆ MAX_I16

const int16_t MAX_I16 = std::numeric_limits<int16_t>::max()
static

16bit unsigned integer maximum value

◆ MAX_I32

const int32_t MAX_I32 = std::numeric_limits<int32_t>::max()
static

32bit unsigned integer maximum value

◆ MAX_I64

const int64_t MAX_I64 = std::numeric_limits<int64_t>::max()
static

64bit unsigned integer maximum value

◆ MAX_UI16

const uint16_t MAX_UI16 = std::numeric_limits<uint16_t>::max()
static

16bit unsigned integer maximum value

◆ MAX_UI32

const uint32_t MAX_UI32 = std::numeric_limits<uint32_t>::max()
static

32bit unsigned integer maximum value

◆ MAX_UI64

const uint64_t MAX_UI64 = std::numeric_limits<uint64_t>::max()
static

64bit unsigned integer maximum value

◆ MIN_D

const double MIN_D = std::numeric_limits<double>::min()
static

Double min value. This value will be similar to 2.22507e-308.

Referenced by Quaternion< Precision >::Integrate().

◆ MIN_F

const float MIN_F = std::numeric_limits<float>::min()
static

Float minimum value. This value will be similar to 1.17549e-38.

◆ MIN_I16

const int16_t MIN_I16 = std::numeric_limits<int16_t>::min()
static

16bit unsigned integer minimum value

◆ MIN_I32

const int32_t MIN_I32 = std::numeric_limits<int32_t>::min()
static

32bit unsigned integer minimum value

◆ MIN_I64

const int64_t MIN_I64 = std::numeric_limits<int64_t>::min()
static

64bit unsigned integer minimum value

◆ MIN_UI16

const uint16_t MIN_UI16 = std::numeric_limits<uint16_t>::min()
static

16bit unsigned integer minimum value

◆ MIN_UI32

const uint32_t MIN_UI32 = std::numeric_limits<uint32_t>::min()
static

32bit unsigned integer minimum value

◆ MIN_UI64

const uint64_t MIN_UI64 = std::numeric_limits<uint64_t>::min()
static

64bit unsigned integer minimum value

◆ NAN_D

const double NAN_D = std::numeric_limits<double>::quiet_NaN()
static

Returns the representation of a quiet not a number (NAN)

Referenced by Line2< T >::Slope().

◆ NAN_F

const float NAN_F = std::numeric_limits<float>::quiet_NaN()
static

Returns the representation of a quiet not a number (NAN)

◆ NAN_I

const int NAN_I = std::numeric_limits<int>::quiet_NaN()
static

Returns the representation of a quiet not a number (NAN)