Static Public Member Functions | Static Private Member Functions | List of all members
robot_model_services::MathHelper Class Reference

MathHelper unites the generally needed math operations. More...

#include <MathHelper.hpp>

Static Public Member Functions

static SimpleSphereCoordinates convertC2S (const SimpleVector3 &cartesian)
 converts cartesian coordinates to sphere coordinates More...
 
static void convertC2S (const SimpleVector3 &cartesian, SimpleSphereCoordinates &sphere)
 converts cartesian coordinates to sphere coordinates (lightweight) More...
 
static SimpleVector3 convertS2C (const SimpleSphereCoordinates &sphere)
 converts sphere coordinates to cartesian coordinates (lightweight) More...
 
static void convertS2C (const SimpleSphereCoordinates &sphere, SimpleVector3 &cartesian)
 converts sphere coordinates to cartesian coordinates (lightweight) More...
 
static double degToRad (double input)
 
template<typename PowerSet >
static boost::shared_ptr< PowerSet > filterCardinalityPowerSet (const boost::shared_ptr< PowerSet > &powerSetPtr, const std::size_t min, const std::size_t max)
 
template<typename PowerSet >
static boost::shared_ptr< PowerSet > filterCardinalityPowerSet (const boost::shared_ptr< PowerSet > &setPtr, const std::size_t min)
 
static Precision getAngle (const SimpleVector3 &X, const SimpleVector3 &Y)
 
static Precision getCosinus (const SimpleVector3 &X, const SimpleVector3 &Y)
 
static double getDotProduct (SimpleVector3 v1, SimpleVector3 v2)
 
static Precision getMinimumAngleDifference (const Precision &firstAngle, const Precision &secondAngle)
 
static SimpleQuaternionCollectionPtr getOrientationsOnUnitSphere (const int &numberOfPoints)
 
static SimpleVector3 getProjection (const std::size_t &idx, const SimpleVector3 &X)
 
static SimpleQuaternion getQuaternionByAngles (const Precision &heading, const Precision &attitude, const Precision &bank)
 
static int getRandomInteger (const int &min, const int &max)
 
static Precision getRandomNumber (const Precision &mean, const Precision &standardDeviation)
 
static SimpleQuaternion getRandomQuaternion ()
 
static SimpleVectorX getRandomVector (const SimpleVectorX &mean, const SimpleVectorX &standardDeviation)
 
static double getSignum (const double &value)
 
static SimpleVector3 getVisualAxis (const SimpleQuaternion &orientation)
 
static void getVisualAxis (const SimpleQuaternion &orientation, SimpleVector3 &resultAxis)
 
template<typename Set >
static boost::shared_ptr< std::set< boost::shared_ptr< Set > > > powerSet (const boost::shared_ptr< Set > &setPtr)
 
template<typename Set >
static void printPowerSet (boost::shared_ptr< std::set< boost::shared_ptr< Set > > > &powerSetPtr)
 
template<typename Set >
static void printSet (boost::shared_ptr< Set > &setPtr)
 
static double radToDeg (double input)
 

Static Private Member Functions

static boost::mt19937 & getRandomnessGenerator ()
 

Detailed Description

MathHelper unites the generally needed math operations.

Author
Ralf Schleicher
Date
2014
Version
1.0

Definition at line 44 of file MathHelper.hpp.

Member Function Documentation

SimpleSphereCoordinates robot_model_services::MathHelper::convertC2S ( const SimpleVector3 cartesian)
static

converts cartesian coordinates to sphere coordinates

Parameters
cartestianany cartesian coordinates
Returns
sphere coordinates (radius,inclinate,azimuth)

Definition at line 29 of file MathHelper.cpp.

void robot_model_services::MathHelper::convertC2S ( const SimpleVector3 cartesian,
SimpleSphereCoordinates sphere 
)
static

converts cartesian coordinates to sphere coordinates (lightweight)

Parameters
cartestianany cartesian coordinates
sphere(out) sphere coordinates (radius,inclinate,azimuth)

Definition at line 35 of file MathHelper.cpp.

SimpleVector3 robot_model_services::MathHelper::convertS2C ( const SimpleSphereCoordinates sphere)
static

converts sphere coordinates to cartesian coordinates (lightweight)

Parameters
sphereany sphere coordinates (radius,inclinate,azimuth)
Returns
cartesian coordinates

Definition at line 41 of file MathHelper.cpp.

void robot_model_services::MathHelper::convertS2C ( const SimpleSphereCoordinates sphere,
SimpleVector3 cartesian 
)
static

converts sphere coordinates to cartesian coordinates (lightweight)

Parameters
sphereany sphere coordinates (radius,inclinate,azimuth)
cartesian(out) cartesian coordinates

Definition at line 47 of file MathHelper.cpp.

double robot_model_services::MathHelper::degToRad ( double  input)
static
Parameters
inputin degrees
Returns
input in radians

Definition at line 172 of file MathHelper.cpp.

template<typename PowerSet >
static boost::shared_ptr<PowerSet> robot_model_services::MathHelper::filterCardinalityPowerSet ( const boost::shared_ptr< PowerSet > &  powerSetPtr,
const std::size_t  min,
const std::size_t  max 
)
inlinestatic

Definition at line 214 of file MathHelper.hpp.

template<typename PowerSet >
static boost::shared_ptr<PowerSet> robot_model_services::MathHelper::filterCardinalityPowerSet ( const boost::shared_ptr< PowerSet > &  setPtr,
const std::size_t  min 
)
inlinestatic

Definition at line 228 of file MathHelper.hpp.

Precision robot_model_services::MathHelper::getAngle ( const SimpleVector3 X,
const SimpleVector3 Y 
)
static
Parameters
X[in] the first 3d vector
Y[in] the second 3d vector
Returns
the angle between the two vectors

Definition at line 81 of file MathHelper.cpp.

Precision robot_model_services::MathHelper::getCosinus ( const SimpleVector3 X,
const SimpleVector3 Y 
)
static
Parameters
X[in] the first 3d vector
Y[in] the second 3d vector
Returns
the cosinus between the two vectors.

Definition at line 71 of file MathHelper.cpp.

double robot_model_services::MathHelper::getDotProduct ( SimpleVector3  v1,
SimpleVector3  v2 
)
static

Definition at line 176 of file MathHelper.cpp.

Precision robot_model_services::MathHelper::getMinimumAngleDifference ( const Precision firstAngle,
const Precision secondAngle 
)
static
Parameters
firstAngle[in] the first angle
secondAngle[in] the second angle
Returns
the minimum angle difference.

Definition at line 87 of file MathHelper.cpp.

SimpleQuaternionCollectionPtr robot_model_services::MathHelper::getOrientationsOnUnitSphere ( const int &  numberOfPoints)
static
Parameters
numberOfPoints[in] the number of points to use.
Returns
an array of orientations.

Definition at line 136 of file MathHelper.cpp.

SimpleVector3 robot_model_services::MathHelper::getProjection ( const std::size_t &  idx,
const SimpleVector3 X 
)
static
Parameters
idx[in] the index to project to 0
X[in] the 3d vector used for this action.
Returns
the 3d vector after projection

Definition at line 67 of file MathHelper.cpp.

SimpleQuaternion robot_model_services::MathHelper::getQuaternionByAngles ( const Precision heading,
const Precision attitude,
const Precision bank 
)
static
Parameters
heading[in] the heading angle
attitude[in] the attitude angle
bank[in] the bank angle
Returns
the corresponding quaternion

Definition at line 118 of file MathHelper.cpp.

int robot_model_services::MathHelper::getRandomInteger ( const int &  min,
const int &  max 
)
static
Parameters
min[in] the minumum integer
max[in] the maximum integer
Returns
a random integer in the range [min, max]

Definition at line 92 of file MathHelper.cpp.

boost::mt19937 & robot_model_services::MathHelper::getRandomnessGenerator ( )
staticprivate
Returns
the randomness generator.

Definition at line 24 of file MathHelper.cpp.

Precision robot_model_services::MathHelper::getRandomNumber ( const Precision mean,
const Precision standardDeviation 
)
static
Parameters
mean[in] the mean value
standardDeviation[in] the standard deviation to use.
Returns
a normal distributed random number.

Definition at line 98 of file MathHelper.cpp.

SimpleQuaternion robot_model_services::MathHelper::getRandomQuaternion ( )
static
Returns
a random rotation quaternion

Definition at line 113 of file MathHelper.cpp.

SimpleVectorX robot_model_services::MathHelper::getRandomVector ( const SimpleVectorX mean,
const SimpleVectorX standardDeviation 
)
static
Parameters
mean[in] the mean value in X dimensions
standardDeviation[in] the standard deviation to use in X dimensions.
Returns
a normal distributed random vector.

Definition at line 104 of file MathHelper.cpp.

double robot_model_services::MathHelper::getSignum ( const double &  value)
static
Parameters
value[in]
Returns
the signum of value

Definition at line 63 of file MathHelper.cpp.

SimpleVector3 robot_model_services::MathHelper::getVisualAxis ( const SimpleQuaternion orientation)
static

Definition at line 53 of file MathHelper.cpp.

void robot_model_services::MathHelper::getVisualAxis ( const SimpleQuaternion orientation,
SimpleVector3 resultAxis 
)
static

Definition at line 59 of file MathHelper.cpp.

template<typename Set >
static boost::shared_ptr<std::set<boost::shared_ptr<Set> > > robot_model_services::MathHelper::powerSet ( const boost::shared_ptr< Set > &  setPtr)
inlinestatic

Definition at line 188 of file MathHelper.hpp.

template<typename Set >
static void robot_model_services::MathHelper::printPowerSet ( boost::shared_ptr< std::set< boost::shared_ptr< Set > > > &  powerSetPtr)
inlinestatic

Definition at line 179 of file MathHelper.hpp.

template<typename Set >
static void robot_model_services::MathHelper::printSet ( boost::shared_ptr< Set > &  setPtr)
inlinestatic

Definition at line 171 of file MathHelper.hpp.

double robot_model_services::MathHelper::radToDeg ( double  input)
static
Parameters
inputin radians
Returns
input in degrees

Definition at line 168 of file MathHelper.cpp.


The documentation for this class was generated from the following files:


asr_robot_model_services
Author(s): Aumann Florian, Borella Jocelyn, Heller Florian, Meißner Pascal, Schleicher Ralf, Stöckle Patrick, Stroh Daniel, Trautmann Jeremias, Walter Milena, Wittenbeck Valerij
autogenerated on Mon Jun 10 2019 12:50:00