Math namespace. More...
Classes | |
| class | Angle |
| An angle and related functions. More... | |
| class | BiQuad |
| Bi-quad filter base class. More... | |
| class | BiQuadVector3 |
| BiQuad vector3 filter. More... | |
| class | Box |
| Mathematical representation of a box and related functions. More... | |
| class | Filter |
| Filter base class. More... | |
| class | Kmeans |
| K-Means clustering algorithm. More... | |
| class | Matrix3 |
| A 3x3 matrix class. More... | |
| class | Matrix4 |
| A 3x3 matrix class. More... | |
| class | OnePole |
| A one-pole DSP filter. More... | |
| class | OnePoleQuaternion |
| One-pole quaternion filter. More... | |
| class | OnePoleVector3 |
| One-pole vector3 filter. More... | |
| class | Plane |
| A plane and related functions. More... | |
| class | Pose |
| Encapsulates a position and rotation in three space. More... | |
| class | Quaternion |
| A quaternion class. More... | |
| class | Rand |
| Random number generator class. More... | |
| class | RotationSpline |
| Spline for rotations. More... | |
| class | SignalMaxAbsoluteValue |
| Computing the maximum of the absolute value of a discretely sampled signal. More... | |
| class | SignalMean |
| Computing the mean 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 | SignalStatisticPrivate |
| Private data class for the SignalStatistic class. More... | |
| class | SignalStats |
| Collection of statistics for a scalar signal. More... | |
| class | SignalStatsPrivate |
| Private data class for the SignalStats class. More... | |
| class | Spline |
| Splines. More... | |
| class | Vector2d |
| Generic double x, y vector. More... | |
| class | Vector2i |
| Generic integer x, y vector. More... | |
| class | Vector3 |
| The Vector3 class represents the generic vector containing 3 elements. More... | |
| class | Vector3Stats |
| Collection of statistics for a Vector3 signal. More... | |
| class | Vector3StatsPrivate |
| Private data class for the Vector3Stats class. More... | |
| class | Vector4 |
| double Generic x, y, z, w vector More... | |
Typedefs | |
| typedef boost::mt19937 | GeneratorType |
| typedef boost::normal_distribution < double > | NormalRealDist |
| typedef boost::variate_generator < GeneratorType &, NormalRealDist > | NRealGen |
| typedef std::vector < SignalStatisticPtr > | SignalStatistic_V |
| typedef boost::shared_ptr < SignalStatistic > | SignalStatisticPtr |
| typedef boost::variate_generator < GeneratorType &, UniformIntDist > | UIntGen |
| typedef boost::uniform_int< int > | UniformIntDist |
| typedef boost::uniform_real < double > | UniformRealDist |
| typedef boost::variate_generator < GeneratorType &, UniformRealDist > | URealGen |
Functions | |
| template<typename T > | |
| T | clamp (T _v, T _min, T _max) |
| Simple clamping function. More... | |
| template<typename T > | |
| bool | equal (const T &_a, const T &_b, const T &_epsilon=1e-6) |
| check if two values are equal, within a tolerance More... | |
| float | fixnan (float _v) |
| Fix a nan value. More... | |
| double | fixnan (double _v) |
| Fix a nan value. More... | |
| bool | isnan (float _v) |
| check if a float is NaN More... | |
| bool | isnan (double _v) |
| check if a double is NaN More... | |
| bool | isPowerOfTwo (unsigned int _x) |
| is this a power of 2? 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... | |
| 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... | |
| unsigned int | roundUpPowerOfTwo (unsigned int _x) |
| Get the smallest power of two that is greater or equal to a given value. More... | |
| template<typename T > | |
| T | variance (const std::vector< T > &_values) |
| get variance of vector of values More... | |
Variables | |
| static const double | NAN_D = std::numeric_limits<double>::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... | |
Math namespace.
| typedef boost::mt19937 gazebo::math::GeneratorType |
| typedef boost::normal_distribution<double> gazebo::math::NormalRealDist |
| typedef boost::variate_generator<GeneratorType&, NormalRealDist > gazebo::math::NRealGen |
| typedef std::vector<SignalStatisticPtr> gazebo::math::SignalStatistic_V |
| typedef boost::shared_ptr<SignalStatistic> gazebo::math::SignalStatisticPtr |
| typedef boost::variate_generator<GeneratorType&, UniformIntDist > gazebo::math::UIntGen |
| typedef boost::uniform_int<int> gazebo::math::UniformIntDist |
| typedef boost::uniform_real<double> gazebo::math::UniformRealDist |
| typedef boost::variate_generator<GeneratorType&, UniformRealDist > gazebo::math::URealGen |