DART  6.7.3
dart::math Namespace Reference

Namespaces

 detail
 
 suffixes
 

Classes

struct  RealVectorSpace
 
struct  SO3Space
 
struct  SE3Space
 
struct  MapsToManifoldPoint
 
struct  constants
 
struct  HullAngle
 
class  BoundingBox
 
class  Random
 

Typedefs

using NullSpace = RealVectorSpace< 0u >
 
using R1Space = RealVectorSpace< 1u >
 
using R2Space = RealVectorSpace< 2u >
 
using R3Space = RealVectorSpace< 3u >
 
using constantsf = constants< float >
 
using constantsd = constants< double >
 
typedef std::vector< Eigen::Vector3d > SupportGeometry
 
typedef common::aligned_vector< Eigen::Vector2d > SupportPolygon
 
using Inertia = Eigen::Matrix6d
 
using LinearJacobian = Eigen::Matrix< double, 3, Eigen::Dynamic >
 
using AngularJacobian = Eigen::Matrix< double, 3, Eigen::Dynamic >
 
using Jacobian = Eigen::Matrix< double, 6, Eigen::Dynamic >
 

Enumerations

enum  AxisType { AXIS_X = 0 , AXIS_Y = 1 , AXIS_Z = 2 }
 
enum  IntersectionResult { INTERSECTING = 0 , PARALLEL , BEYOND_ENDPOINTS }
 Intersection_t is returned by the computeIntersection() function to indicate whether there was a valid intersection between the two line segments. More...
 

Functions

template<typename SpaceT >
SpaceT::Matrix inverse (const typename SpaceT::Matrix &mat)
 
template<typename SpaceT >
SpaceT::EuclideanPoint toEuclideanPoint (const typename SpaceT::Point &point)
 
template<typename SpaceT >
SpaceT::Point toManifoldPoint (const typename SpaceT::EuclideanPoint &point)
 
template<typename SpaceT >
SpaceT::Point integratePosition (const typename SpaceT::Point &pos, const typename SpaceT::Vector &vel, double dt)
 
template<typename SpaceT >
SpaceT::Vector integrateVelocity (const typename SpaceT::Vector &vel, const typename SpaceT::Vector &acc, double dt)
 
Eigen::Quaterniond expToQuat (const Eigen::Vector3d &_v)
 
Eigen::Vector3d quatToExp (const Eigen::Quaterniond &_q)
 
Eigen::Vector3d matrixToEulerXYX (const Eigen::Matrix3d &_R)
 get the Euler XYX angle from R More...
 
Eigen::Vector3d matrixToEulerXYZ (const Eigen::Matrix3d &_R)
 get the Euler XYZ angle from R More...
 
Eigen::Vector3d matrixToEulerZYX (const Eigen::Matrix3d &_R)
 get the Euler ZYX angle from R More...
 
Eigen::Vector3d matrixToEulerXZY (const Eigen::Matrix3d &_R)
 get the Euler XZY angle from R More...
 
Eigen::Vector3d matrixToEulerYZX (const Eigen::Matrix3d &_R)
 get the Euler YZX angle from R More...
 
Eigen::Vector3d matrixToEulerZXY (const Eigen::Matrix3d &_R)
 get the Euler ZXY angle from R More...
 
Eigen::Vector3d matrixToEulerYXZ (const Eigen::Matrix3d &_R)
 get the Euler YXZ angle from R More...
 
Eigen::Matrix3d quatDeriv (const Eigen::Quaterniond &_q, int _el)
 
Eigen::Matrix3d quatSecondDeriv (const Eigen::Quaterniond &_q, int _el1, int _el2)
 
Eigen::Vector3d rotatePoint (const Eigen::Quaterniond &_q, const Eigen::Vector3d &_pt)
 
Eigen::Vector3d rotatePoint (const Eigen::Quaterniond &_q, double _x, double _y, double _z)
 
Eigen::Matrix3d expMapRot (const Eigen::Vector3d &_expmap)
 Computes the Rotation matrix from a given expmap vector. More...
 
Eigen::Matrix3d expMapJac (const Eigen::Vector3d &_expmap)
 Computes the Jacobian of the expmap. More...
 
Eigen::Matrix3d expMapJacDot (const Eigen::Vector3d &_expmap, const Eigen::Vector3d &_qdot)
 Computes the time derivative of the expmap Jacobian. More...
 
Eigen::Matrix3d expMapJacDeriv (const Eigen::Vector3d &_expmap, int _qi)
 computes the derivative of the Jacobian of the expmap wrt to _qi indexed dof; _qi \in {0,1,2} More...
 
Eigen::Vector3d logMap (const Eigen::Matrix3d &_R)
 Log mapping. More...
 
Eigen::Vector6d logMap (const Eigen::Isometry3d &_T)
 Log mapping. More...
 
Eigen::Vector6d AdT (const Eigen::Isometry3d &_T, const Eigen::Vector6d &_V)
 Rectify the rotation part so as that it satifies the orthogonality condition. More...
 
Eigen::Matrix6d getAdTMatrix (const Eigen::Isometry3d &T)
 Get linear transformation matrix of Adjoint mapping. More...
 
Eigen::Vector6d AdR (const Eigen::Isometry3d &_T, const Eigen::Vector6d &_V)
 Fast version of Ad([R 0; 0 1], V) More...
 
Eigen::Vector6d AdTAngular (const Eigen::Isometry3d &_T, const Eigen::Vector3d &_w)
 fast version of Ad(T, se3(w, 0)) More...
 
Eigen::Vector6d AdTLinear (const Eigen::Isometry3d &_T, const Eigen::Vector3d &_v)
 fast version of Ad(T, se3(0, v)) More...
 
Eigen::Vector6d AdInvT (const Eigen::Isometry3d &_T, const Eigen::Vector6d &_V)
 fast version of Ad(Inv(T), V) More...
 
Eigen::Vector6d AdInvRLinear (const Eigen::Isometry3d &_T, const Eigen::Vector3d &_v)
 Fast version of Ad(Inv([R 0; 0 1]), se3(0, v)) More...
 
Eigen::Vector6d ad (const Eigen::Vector6d &_X, const Eigen::Vector6d &_Y)
 adjoint mapping More...
 
Eigen::Vector6d dAdT (const Eigen::Isometry3d &_T, const Eigen::Vector6d &_F)
 dual adjoint mapping More...
 
Eigen::Vector6d dAdInvT (const Eigen::Isometry3d &_T, const Eigen::Vector6d &_F)
 fast version of dAd(Inv(T), F) More...
 
Eigen::Vector6d dAdInvR (const Eigen::Isometry3d &_T, const Eigen::Vector6d &_F)
 fast version of dAd(Inv([R 0; 0 1]), F) More...
 
Eigen::Matrix3d eulerXYXToMatrix (const Eigen::Vector3d &_angle)
 Given Euler XYX angles, return a 3x3 rotation matrix, which is equivalent to RotX(angle(0)) * RotY(angle(1)) * RotX(angle(2)). More...
 
Eigen::Matrix3d eulerXYZToMatrix (const Eigen::Vector3d &_angle)
 Given EulerXYZ angles, return a 3x3 rotation matrix, which is equivalent to RotX(angle(0)) * RotY(angle(1)) * RotZ(angle(2)). More...
 
Eigen::Matrix3d eulerXZXToMatrix (const Eigen::Vector3d &_angle)
 Given EulerXZX angles, return a 3x3 rotation matrix, which is equivalent to RotX(angle(0)) * RotZ(angle(1)) * RotX(angle(2)). More...
 
Eigen::Matrix3d eulerXZYToMatrix (const Eigen::Vector3d &_angle)
 Given EulerXZY angles, return a 3x3 rotation matrix, which is equivalent to RotX(angle(0)) * RotZ(angle(1)) * RotY(angle(2)). More...
 
Eigen::Matrix3d eulerYXYToMatrix (const Eigen::Vector3d &_angle)
 Given EulerYXY angles, return a 3x3 rotation matrix, which is equivalent to RotY(angle(0)) * RotX(angle(1)) * RotY(angle(2)). More...
 
Eigen::Matrix3d eulerYXZToMatrix (const Eigen::Vector3d &_angle)
 Given EulerYXZ angles, return a 3x3 rotation matrix, which is equivalent to RotY(angle(0)) * RotX(angle(1)) * RotZ(angle(2)). More...
 
Eigen::Matrix3d eulerYZXToMatrix (const Eigen::Vector3d &_angle)
 Given EulerYZX angles, return a 3x3 rotation matrix, which is equivalent to RotY(angle(0)) * RotZ(angle(1)) * RotX(angle(2)). More...
 
Eigen::Matrix3d eulerYZYToMatrix (const Eigen::Vector3d &_angle)
 Given EulerYZY angles, return a 3x3 rotation matrix, which is equivalent to RotY(angle(0)) * RotZ(angle(1)) * RotY(angle(2)). More...
 
Eigen::Matrix3d eulerZXYToMatrix (const Eigen::Vector3d &_angle)
 Given EulerZXY angles, return a 3x3 rotation matrix, which is equivalent to RotZ(angle(0)) * RotX(angle(1)) * RotY(angle(2)). More...
 
Eigen::Matrix3d eulerZYXToMatrix (const Eigen::Vector3d &_angle)
 Given EulerZYX angles, return a 3x3 rotation matrix, which is equivalent to RotZ(angle(0)) * RotY(angle(1)) * RotX(angle(2)). More...
 
Eigen::Matrix3d eulerZXZToMatrix (const Eigen::Vector3d &_angle)
 Given EulerZXZ angles, return a 3x3 rotation matrix, which is equivalent to RotZ(angle(0)) * RotX(angle(1)) * RotZ(angle(2)). More...
 
Eigen::Matrix3d eulerZYZToMatrix (const Eigen::Vector3d &_angle)
 Given EulerZYZ angles, return a 3x3 rotation matrix, which is equivalent to RotZ(angle(0)) * RotY(angle(1)) * RotZ(angle(2)). More...
 
Eigen::Isometry3d expMap (const Eigen::Vector6d &_S)
 Exponential mapping. More...
 
Eigen::Isometry3d expAngular (const Eigen::Vector3d &_s)
 fast version of Exp(se3(s, 0)) More...
 
Eigen::Vector6d dad (const Eigen::Vector6d &_s, const Eigen::Vector6d &_t)
 fast version of ad(se3(Eigen_Vec3(0), v), S) More...
 
Inertia transformInertia (const Eigen::Isometry3d &_T, const Inertia &_AI)
 
Eigen::Matrix3d parallelAxisTheorem (const Eigen::Matrix3d &_original, const Eigen::Vector3d &_comShift, double _mass)
 Use the Parallel Axis Theorem to compute the moment of inertia of a body whose center of mass has been shifted from the origin. More...
 
bool verifyRotation (const Eigen::Matrix3d &_R)
 Check if determinant of _R is equat to 1 and all the elements are not NaN values. More...
 
bool verifyTransform (const Eigen::Isometry3d &_T)
 Check if determinant of the rotational part of _T is equat to 1 and all the elements are not NaN values. More...
 
Eigen::Vector3d fromSkewSymmetric (const Eigen::Matrix3d &_m)
 
Eigen::Matrix3d makeSkewSymmetric (const Eigen::Vector3d &_v)
 
Eigen::Matrix3d computeRotation (const Eigen::Vector3d &axis, AxisType axisType=AxisType::AXIS_X)
 Compute a rotation matrix from a vector. More...
 
Eigen::Isometry3d computeTransform (const Eigen::Vector3d &axis, const Eigen::Vector3d &translation, AxisType axisType=AxisType::AXIS_X)
 Compute a transform from a vector and a position. More...
 
Eigen::Isometry3d getFrameOriginAxisZ (const Eigen::Vector3d &_origin, const Eigen::Vector3d &_axisZ)
 Generate frame given origin and z-axis. More...
 
SupportPolygon computeSupportPolgyon (const SupportGeometry &_geometry, const Eigen::Vector3d &_axis1=Eigen::Vector3d::UnitX(), const Eigen::Vector3d &_axis2=Eigen::Vector3d::UnitY())
 Project the support geometry points onto a plane with the given axes and then compute their convex hull, which will take the form of a polgyon. More...
 
SupportPolygon computeSupportPolgyon (std::vector< std::size_t > &_originalIndices, const SupportGeometry &_geometry, const Eigen::Vector3d &_axis1=Eigen::Vector3d::UnitX(), const Eigen::Vector3d &_axis2=Eigen::Vector3d::UnitY())
 Same as computeSupportPolgyon, except you can pass in a std::vector<std::size_t> which will have the same size as the returned SupportPolygon, and each entry will contain the original index of each point in the SupportPolygon. More...
 
static bool HullAngleComparison (const HullAngle &a, const HullAngle &b)
 
SupportPolygon computeConvexHull (const SupportPolygon &_points)
 Computes the convex hull of a set of 2D points. More...
 
Eigen::Vector2d computeCentroidOfHull (const SupportPolygon &_convexHull)
 Compute the centroid of a polygon, assuming the polygon is a convex hull. More...
 
static bool isLeftTurn (const Eigen::Vector2d &p1, const Eigen::Vector2d &p2, const Eigen::Vector2d &p3)
 
SupportPolygon computeConvexHull (std::vector< std::size_t > &_originalIndices, const SupportPolygon &_points)
 Computes the convex hull of a set of 2D points and fills in _originalIndices with the original index of each entry in the returned SupportPolygon. More...
 
IntersectionResult computeIntersection (Eigen::Vector2d &_intersectionPoint, const Eigen::Vector2d &a1, const Eigen::Vector2d &a2, const Eigen::Vector2d &b1, const Eigen::Vector2d &b2)
 Compute the intersection between a line segment that goes from a1 -> a2 and a line segment that goes from b1 -> b2. More...
 
double cross (const Eigen::Vector2d &_v1, const Eigen::Vector2d &_v2)
 Compute a 2D cross product. More...
 
bool isInsideSupportPolygon (const Eigen::Vector2d &_p, const SupportPolygon &_support, bool _includeEdge=true)
 Returns true if the point _p is inside the support polygon. More...
 
Eigen::Vector2d computeClosestPointOnLineSegment (const Eigen::Vector2d &_p, const Eigen::Vector2d &_s1, const Eigen::Vector2d &_s2)
 Returns the point which is closest to _p that also lays on the line segment that goes from _s1 -> _s2. More...
 
Eigen::Vector2d computeClosestPointOnSupportPolygon (const Eigen::Vector2d &_p, const SupportPolygon &_support)
 Returns the point which is closest to _p that also lays on the edge of the support polygon. More...
 
Eigen::Vector2d computeClosestPointOnSupportPolygon (std::size_t &_index1, std::size_t &_index2, const Eigen::Vector2d &_p, const SupportPolygon &_support)
 Same as closestPointOnSupportPolygon, but also fills in _index1 and _index2 with the indices of the line segment. More...
 
template<typename Derived >
Derived::PlainObject AdTJac (const Eigen::Isometry3d &_T, const Eigen::MatrixBase< Derived > &_J)
 Adjoint mapping for dynamic size Jacobian. More...
 
template<typename Derived >
Derived::PlainObject AdTJacFixed (const Eigen::Isometry3d &_T, const Eigen::MatrixBase< Derived > &_J)
 Adjoint mapping for fixed size Jacobian. More...
 
template<typename Derived >
Derived::PlainObject AdRJac (const Eigen::Isometry3d &_T, const Eigen::MatrixBase< Derived > &_J)
 Change coordinate Frame of a Jacobian. More...
 
template<typename Derived >
Derived::PlainObject AdRInvJac (const Eigen::Isometry3d &_T, const Eigen::MatrixBase< Derived > &_J)
 
template<typename Derived >
Derived::PlainObject adJac (const Eigen::Vector6d &_V, const Eigen::MatrixBase< Derived > &_J)
 
template<typename Derived >
Derived::PlainObject AdInvTJac (const Eigen::Isometry3d &_T, const Eigen::MatrixBase< Derived > &_J)
 Adjoint mapping for dynamic size Jacobian. More...
 
template<typename Derived >
Derived::PlainObject AdInvTJacFixed (const Eigen::Isometry3d &_T, const Eigen::MatrixBase< Derived > &_J)
 Adjoint mapping for fixed size Jacobian. More...
 
double wrapToPi (double angle)
 Compute the angle (in the range of -pi to +pi) which ignores any full rotations. More...
 
template<typename MatrixType , typename ReturnType >
void extractNullSpace (const Eigen::JacobiSVD< MatrixType > &_SVD, ReturnType &_NS)
 
template<typename MatrixType , typename ReturnType >
void computeNullSpace (const MatrixType &_M, ReturnType &_NS)
 
template<typename T >
constexpr T toRadian (const T &degree)
 
template<typename T >
constexpr T toDegree (const T &radian)
 
const Eigen::Matrix2d CR ((Eigen::Matrix2d()<< 0.0, -1.0, 1.0, 0.0).finished())
 a cross b = (CR*a) dot b const Matd CR(2,2,0.0,-1.0,1.0,0.0); More...
 
int delta (int _i, int _j)
 
template<typename T >
constexpr int sign (T x, std::false_type)
 
template<typename T >
constexpr int sign (T x, std::true_type)
 
template<typename T >
constexpr int sign (T x)
 
double sqr (double _x)
 
double Tsinc (double _theta)
 
bool isZero (double _theta)
 
double asinh (double _X)
 
double acosh (double _X)
 
double atanh (double _X)
 
double asech (double _X)
 
double acosech (double _X)
 
double acotanh (double _X)
 
double round (double _x)
 
double round2 (double _x)
 
template<typename T >
clip (const T &val, const T &lower, const T &upper)
 
template<typename DerivedA , typename DerivedB >
DerivedA::PlainObject clip (const Eigen::MatrixBase< DerivedA > &val, const Eigen::MatrixBase< DerivedB > &lower, const Eigen::MatrixBase< DerivedB > &upper)
 
bool isEqual (double _x, double _y)
 
bool isInt (double _x)
 
bool isNan (double _v)
 Returns whether _v is a NaN (Not-A-Number) value. More...
 
bool isNan (const Eigen::MatrixXd &_m)
 Returns whether _m is a NaN (Not-A-Number) matrix. More...
 
bool isInf (double _v)
 Returns whether _v is an infinity value (either positive infinity or negative infinity). More...
 
bool isInf (const Eigen::MatrixXd &_m)
 Returns whether _m is an infinity matrix (either positive infinity or negative infinity). More...
 
bool isSymmetric (const Eigen::MatrixXd &_m, double _tol=1e-6)
 Returns whether _m is symmetric or not. More...
 
unsigned seedRand ()
 
double random (double _min, double _max)
 
template<int N>
Eigen::Matrix< double, N, 1 > randomVector (double _min, double _max)
 
template<int N>
Eigen::Matrix< double, N, 1 > randomVector (double _limit)
 
Eigen::VectorXd randomVectorXd (std::size_t size, double min, double max)
 
Eigen::VectorXd randomVectorXd (std::size_t size, double limit)
 

Typedef Documentation

◆ AngularJacobian

using dart::math::AngularJacobian = typedef Eigen::Matrix<double, 3, Eigen::Dynamic>

◆ constantsd

using dart::math::constantsd = typedef constants<double>

◆ constantsf

using dart::math::constantsf = typedef constants<float>

◆ Inertia

◆ Jacobian

using dart::math::Jacobian = typedef Eigen::Matrix<double, 6, Eigen::Dynamic>

◆ LinearJacobian

using dart::math::LinearJacobian = typedef Eigen::Matrix<double, 3, Eigen::Dynamic>

◆ NullSpace

◆ R1Space

using dart::math::R1Space = typedef RealVectorSpace<1u>

◆ R2Space

using dart::math::R2Space = typedef RealVectorSpace<2u>

◆ R3Space

using dart::math::R3Space = typedef RealVectorSpace<3u>

◆ SupportGeometry

typedef std::vector<Eigen::Vector3d> dart::math::SupportGeometry

◆ SupportPolygon

Enumeration Type Documentation

◆ AxisType

Enumerator
AXIS_X 
AXIS_Y 
AXIS_Z 

◆ IntersectionResult

Intersection_t is returned by the computeIntersection() function to indicate whether there was a valid intersection between the two line segments.

Enumerator
INTERSECTING 

An intersection was found.

PARALLEL 

The line segments are parallel.

BEYOND_ENDPOINTS 

There is no intersection because the end points do not expand far enough.

Function Documentation

◆ acosech()

double dart::math::acosech ( double  _X)
inline

◆ acosh()

double dart::math::acosh ( double  _X)
inline

◆ acotanh()

double dart::math::acotanh ( double  _X)
inline

◆ ad()

Eigen::Vector6d dart::math::ad ( const Eigen::Vector6d _X,
const Eigen::Vector6d _Y 
)

adjoint mapping

Note
$ad_X Y = ( w_X @times w_Y@,,~w_X @times v_Y - w_Y @times v_X),$, where $X=(w_X,v_X)@in se(3), @quad Y=(w_Y,v_Y)@in se(3) $.

◆ AdInvRLinear()

Eigen::Vector6d dart::math::AdInvRLinear ( const Eigen::Isometry3d &  _T,
const Eigen::Vector3d &  _v 
)

Fast version of Ad(Inv([R 0; 0 1]), se3(0, v))

◆ AdInvT()

Eigen::Vector6d dart::math::AdInvT ( const Eigen::Isometry3d &  _T,
const Eigen::Vector6d _V 
)

fast version of Ad(Inv(T), V)

◆ AdInvTJac()

template<typename Derived >
Derived::PlainObject dart::math::AdInvTJac ( const Eigen::Isometry3d &  _T,
const Eigen::MatrixBase< Derived > &  _J 
)

Adjoint mapping for dynamic size Jacobian.

◆ AdInvTJacFixed()

template<typename Derived >
Derived::PlainObject dart::math::AdInvTJacFixed ( const Eigen::Isometry3d &  _T,
const Eigen::MatrixBase< Derived > &  _J 
)

Adjoint mapping for fixed size Jacobian.

◆ adJac()

template<typename Derived >
Derived::PlainObject dart::math::adJac ( const Eigen::Vector6d _V,
const Eigen::MatrixBase< Derived > &  _J 
)

◆ AdR()

Eigen::Vector6d dart::math::AdR ( const Eigen::Isometry3d &  _T,
const Eigen::Vector6d _V 
)

Fast version of Ad([R 0; 0 1], V)

◆ AdRInvJac()

template<typename Derived >
Derived::PlainObject dart::math::AdRInvJac ( const Eigen::Isometry3d &  _T,
const Eigen::MatrixBase< Derived > &  _J 
)

◆ AdRJac()

template<typename Derived >
Derived::PlainObject dart::math::AdRJac ( const Eigen::Isometry3d &  _T,
const Eigen::MatrixBase< Derived > &  _J 
)

Change coordinate Frame of a Jacobian.

◆ AdT()

Eigen::Vector6d dart::math::AdT ( const Eigen::Isometry3d &  _T,
const Eigen::Vector6d _V 
)

Rectify the rotation part so as that it satifies the orthogonality condition.

It is one step of $R_{i_1}=1/2(R_i + R_i^{-T})$. Hence by calling this function iterativley, you can make the rotation part closer to SO(3).

reparameterize such as ||s'|| < M_PI and Exp(s) == Epx(s')

adjoint mapping

Note
$Ad_TV = ( Rw@,, ~p @times Rw + Rv)$, where $T=(R,p)@in SE(3), @quad V=(w,v)@in se(3) $.

◆ AdTAngular()

Eigen::Vector6d dart::math::AdTAngular ( const Eigen::Isometry3d &  _T,
const Eigen::Vector3d &  _w 
)

fast version of Ad(T, se3(w, 0))

◆ AdTJac()

template<typename Derived >
Derived::PlainObject dart::math::AdTJac ( const Eigen::Isometry3d &  _T,
const Eigen::MatrixBase< Derived > &  _J 
)

Adjoint mapping for dynamic size Jacobian.

◆ AdTJacFixed()

template<typename Derived >
Derived::PlainObject dart::math::AdTJacFixed ( const Eigen::Isometry3d &  _T,
const Eigen::MatrixBase< Derived > &  _J 
)

Adjoint mapping for fixed size Jacobian.

◆ AdTLinear()

Eigen::Vector6d dart::math::AdTLinear ( const Eigen::Isometry3d &  _T,
const Eigen::Vector3d &  _v 
)

fast version of Ad(T, se3(0, v))

◆ asech()

double dart::math::asech ( double  _X)
inline

◆ asinh()

double dart::math::asinh ( double  _X)
inline

◆ atanh()

double dart::math::atanh ( double  _X)
inline

◆ clip() [1/2]

template<typename DerivedA , typename DerivedB >
DerivedA::PlainObject dart::math::clip ( const Eigen::MatrixBase< DerivedA > &  val,
const Eigen::MatrixBase< DerivedB > &  lower,
const Eigen::MatrixBase< DerivedB > &  upper 
)
inline

◆ clip() [2/2]

template<typename T >
T dart::math::clip ( const T &  val,
const T &  lower,
const T &  upper 
)
inline

◆ computeCentroidOfHull()

Eigen::Vector2d dart::math::computeCentroidOfHull ( const SupportPolygon _convexHull)

Compute the centroid of a polygon, assuming the polygon is a convex hull.

◆ computeClosestPointOnLineSegment()

Eigen::Vector2d dart::math::computeClosestPointOnLineSegment ( const Eigen::Vector2d &  _p,
const Eigen::Vector2d &  _s1,
const Eigen::Vector2d &  _s2 
)

Returns the point which is closest to _p that also lays on the line segment that goes from _s1 -> _s2.

◆ computeClosestPointOnSupportPolygon() [1/2]

Eigen::Vector2d dart::math::computeClosestPointOnSupportPolygon ( const Eigen::Vector2d &  _p,
const SupportPolygon _support 
)

Returns the point which is closest to _p that also lays on the edge of the support polygon.

◆ computeClosestPointOnSupportPolygon() [2/2]

Eigen::Vector2d dart::math::computeClosestPointOnSupportPolygon ( std::size_t &  _index1,
std::size_t &  _index2,
const Eigen::Vector2d &  _p,
const SupportPolygon _support 
)

Same as closestPointOnSupportPolygon, but also fills in _index1 and _index2 with the indices of the line segment.

◆ computeConvexHull() [1/2]

SupportPolygon dart::math::computeConvexHull ( const SupportPolygon _points)

Computes the convex hull of a set of 2D points.

◆ computeConvexHull() [2/2]

SupportPolygon dart::math::computeConvexHull ( std::vector< std::size_t > &  _originalIndices,
const SupportPolygon _points 
)

Computes the convex hull of a set of 2D points and fills in _originalIndices with the original index of each entry in the returned SupportPolygon.

◆ computeIntersection()

IntersectionResult dart::math::computeIntersection ( Eigen::Vector2d &  _intersectionPoint,
const Eigen::Vector2d &  a1,
const Eigen::Vector2d &  a2,
const Eigen::Vector2d &  b1,
const Eigen::Vector2d &  b2 
)

Compute the intersection between a line segment that goes from a1 -> a2 and a line segment that goes from b1 -> b2.

◆ computeNullSpace()

template<typename MatrixType , typename ReturnType >
void dart::math::computeNullSpace ( const MatrixType &  _M,
ReturnType &  _NS 
)

◆ computeRotation()

Eigen::Matrix3d dart::math::computeRotation ( const Eigen::Vector3d &  axis,
AxisType  axisType = AxisType::AXIS_X 
)

Compute a rotation matrix from a vector.

One axis of the rotated coordinates by the rotation matrix matches the input axis where the axis is specified by axisType.

◆ computeSupportPolgyon() [1/2]

SupportPolygon dart::math::computeSupportPolgyon ( const SupportGeometry _geometry,
const Eigen::Vector3d &  _axis1 = Eigen::Vector3d::UnitX(),
const Eigen::Vector3d &  _axis2 = Eigen::Vector3d::UnitY() 
)

Project the support geometry points onto a plane with the given axes and then compute their convex hull, which will take the form of a polgyon.

_axis1 and _axis2 must both have unit length for this function to work correctly.

◆ computeSupportPolgyon() [2/2]

SupportPolygon dart::math::computeSupportPolgyon ( std::vector< std::size_t > &  _originalIndices,
const SupportGeometry _geometry,
const Eigen::Vector3d &  _axis1,
const Eigen::Vector3d &  _axis2 
)

Same as computeSupportPolgyon, except you can pass in a std::vector<std::size_t> which will have the same size as the returned SupportPolygon, and each entry will contain the original index of each point in the SupportPolygon.

◆ computeTransform()

Eigen::Isometry3d dart::math::computeTransform ( const Eigen::Vector3d &  axis,
const Eigen::Vector3d &  translation,
AxisType  axisType = AxisType::AXIS_X 
)

Compute a transform from a vector and a position.

The rotation of the result transform is computed by computeRotationMatrix(), and the translation is just the input translation.

◆ CR()

const Eigen::Matrix2d dart::math::CR ( (Eigen::Matrix2d()<< 0.0, -1.0, 1.0, 0.0).finished()  )

a cross b = (CR*a) dot b const Matd CR(2,2,0.0,-1.0,1.0,0.0);

◆ cross()

double dart::math::cross ( const Eigen::Vector2d &  _v1,
const Eigen::Vector2d &  _v2 
)

Compute a 2D cross product.

◆ dad()

Eigen::Vector6d dart::math::dad ( const Eigen::Vector6d _s,
const Eigen::Vector6d _t 
)

fast version of ad(se3(Eigen_Vec3(0), v), S)

fast version of ad(se3(w, 0), se3(v, 0)) -> check

dual adjoint mapping

Note
$ad^{@,*}_V F = (m @times w + f @times v@,,~ f @times w),$ , where $F=(m,f)@in se^{@,*}(3), @quad V=(w,v)@in se(3) $.

◆ dAdInvR()

Eigen::Vector6d dart::math::dAdInvR ( const Eigen::Isometry3d &  _T,
const Eigen::Vector6d _F 
)

fast version of dAd(Inv([R 0; 0 1]), F)

◆ dAdInvT()

Eigen::Vector6d dart::math::dAdInvT ( const Eigen::Isometry3d &  _T,
const Eigen::Vector6d _F 
)

fast version of dAd(Inv(T), F)

◆ dAdT()

Eigen::Vector6d dart::math::dAdT ( const Eigen::Isometry3d &  _T,
const Eigen::Vector6d _F 
)

dual adjoint mapping

Note
$Ad^{@,*}_TF = ( R^T (m - p@times f)@,,~ R^T f)$, where $T=(R,p)@in SE(3), F=(m,f)@in se(3)^*$.

◆ delta()

int dart::math::delta ( int  _i,
int  _j 
)
inline

◆ eulerXYXToMatrix()

Eigen::Matrix3d dart::math::eulerXYXToMatrix ( const Eigen::Vector3d &  _angle)

Given Euler XYX angles, return a 3x3 rotation matrix, which is equivalent to RotX(angle(0)) * RotY(angle(1)) * RotX(angle(2)).

◆ eulerXYZToMatrix()

Eigen::Matrix3d dart::math::eulerXYZToMatrix ( const Eigen::Vector3d &  _angle)

Given EulerXYZ angles, return a 3x3 rotation matrix, which is equivalent to RotX(angle(0)) * RotY(angle(1)) * RotZ(angle(2)).

◆ eulerXZXToMatrix()

Eigen::Matrix3d dart::math::eulerXZXToMatrix ( const Eigen::Vector3d &  _angle)

Given EulerXZX angles, return a 3x3 rotation matrix, which is equivalent to RotX(angle(0)) * RotZ(angle(1)) * RotX(angle(2)).

◆ eulerXZYToMatrix()

Eigen::Matrix3d dart::math::eulerXZYToMatrix ( const Eigen::Vector3d &  _angle)

Given EulerXZY angles, return a 3x3 rotation matrix, which is equivalent to RotX(angle(0)) * RotZ(angle(1)) * RotY(angle(2)).

◆ eulerYXYToMatrix()

Eigen::Matrix3d dart::math::eulerYXYToMatrix ( const Eigen::Vector3d &  _angle)

Given EulerYXY angles, return a 3x3 rotation matrix, which is equivalent to RotY(angle(0)) * RotX(angle(1)) * RotY(angle(2)).

◆ eulerYXZToMatrix()

Eigen::Matrix3d dart::math::eulerYXZToMatrix ( const Eigen::Vector3d &  _angle)

Given EulerYXZ angles, return a 3x3 rotation matrix, which is equivalent to RotY(angle(0)) * RotX(angle(1)) * RotZ(angle(2)).

◆ eulerYZXToMatrix()

Eigen::Matrix3d dart::math::eulerYZXToMatrix ( const Eigen::Vector3d &  _angle)

Given EulerYZX angles, return a 3x3 rotation matrix, which is equivalent to RotY(angle(0)) * RotZ(angle(1)) * RotX(angle(2)).

◆ eulerYZYToMatrix()

Eigen::Matrix3d dart::math::eulerYZYToMatrix ( const Eigen::Vector3d &  _angle)

Given EulerYZY angles, return a 3x3 rotation matrix, which is equivalent to RotY(angle(0)) * RotZ(angle(1)) * RotY(angle(2)).

◆ eulerZXYToMatrix()

Eigen::Matrix3d dart::math::eulerZXYToMatrix ( const Eigen::Vector3d &  _angle)

Given EulerZXY angles, return a 3x3 rotation matrix, which is equivalent to RotZ(angle(0)) * RotX(angle(1)) * RotY(angle(2)).

◆ eulerZXZToMatrix()

Eigen::Matrix3d dart::math::eulerZXZToMatrix ( const Eigen::Vector3d &  _angle)

Given EulerZXZ angles, return a 3x3 rotation matrix, which is equivalent to RotZ(angle(0)) * RotX(angle(1)) * RotZ(angle(2)).

◆ eulerZYXToMatrix()

Eigen::Matrix3d dart::math::eulerZYXToMatrix ( const Eigen::Vector3d &  _angle)

Given EulerZYX angles, return a 3x3 rotation matrix, which is equivalent to RotZ(angle(0)) * RotY(angle(1)) * RotX(angle(2)).

singularity : angle[1] = -+ 0.5*PI

◆ eulerZYZToMatrix()

Eigen::Matrix3d dart::math::eulerZYZToMatrix ( const Eigen::Vector3d &  _angle)

Given EulerZYZ angles, return a 3x3 rotation matrix, which is equivalent to RotZ(angle(0)) * RotY(angle(1)) * RotZ(angle(2)).

singularity : angle[1] = 0, PI

◆ expAngular()

Eigen::Isometry3d dart::math::expAngular ( const Eigen::Vector3d &  _s)

fast version of Exp(se3(s, 0))

See: https://github.com/dartsim/dart/issues/88

◆ expMap()

Eigen::Isometry3d dart::math::expMap ( const Eigen::Vector6d _S)

Exponential mapping.

◆ expMapJac()

Eigen::Matrix3d dart::math::expMapJac ( const Eigen::Vector3d &  _q)

Computes the Jacobian of the expmap.

◆ expMapJacDeriv()

Eigen::Matrix3d dart::math::expMapJacDeriv ( const Eigen::Vector3d &  _q,
int  _qi 
)

computes the derivative of the Jacobian of the expmap wrt to _qi indexed dof; _qi \in {0,1,2}

◆ expMapJacDot()

Eigen::Matrix3d dart::math::expMapJacDot ( const Eigen::Vector3d &  _q,
const Eigen::Vector3d &  _qdot 
)

Computes the time derivative of the expmap Jacobian.

◆ expMapRot()

Eigen::Matrix3d dart::math::expMapRot ( const Eigen::Vector3d &  _q)

Computes the Rotation matrix from a given expmap vector.

◆ expToQuat()

Eigen::Quaterniond dart::math::expToQuat ( const Eigen::Vector3d &  _v)

◆ extractNullSpace()

template<typename MatrixType , typename ReturnType >
void dart::math::extractNullSpace ( const Eigen::JacobiSVD< MatrixType > &  _SVD,
ReturnType &  _NS 
)

◆ fromSkewSymmetric()

Eigen::Vector3d dart::math::fromSkewSymmetric ( const Eigen::Matrix3d &  _m)

◆ getAdTMatrix()

Eigen::Matrix6d dart::math::getAdTMatrix ( const Eigen::Isometry3d &  T)

Get linear transformation matrix of Adjoint mapping.

◆ getFrameOriginAxisZ()

Eigen::Isometry3d dart::math::getFrameOriginAxisZ ( const Eigen::Vector3d &  _origin,
const Eigen::Vector3d &  _axisZ 
)

Generate frame given origin and z-axis.

◆ HullAngleComparison()

static bool dart::math::HullAngleComparison ( const HullAngle a,
const HullAngle b 
)
static

◆ integratePosition()

template<typename SpaceT >
SpaceT::Point dart::math::integratePosition ( const typename SpaceT::Point &  pos,
const typename SpaceT::Vector &  vel,
double  dt 
)

◆ integrateVelocity()

template<typename SpaceT >
SpaceT::Vector dart::math::integrateVelocity ( const typename SpaceT::Vector &  vel,
const typename SpaceT::Vector &  acc,
double  dt 
)

◆ inverse()

template<typename SpaceT >
SpaceT::Matrix dart::math::inverse ( const typename SpaceT::Matrix &  mat)

◆ isEqual()

bool dart::math::isEqual ( double  _x,
double  _y 
)
inline

◆ isInf() [1/2]

bool dart::math::isInf ( const Eigen::MatrixXd &  _m)
inline

Returns whether _m is an infinity matrix (either positive infinity or negative infinity).

◆ isInf() [2/2]

bool dart::math::isInf ( double  _v)
inline

Returns whether _v is an infinity value (either positive infinity or negative infinity).

◆ isInsideSupportPolygon()

bool dart::math::isInsideSupportPolygon ( const Eigen::Vector2d &  _p,
const SupportPolygon _support,
bool  _includeEdge 
)

Returns true if the point _p is inside the support polygon.

◆ isInt()

bool dart::math::isInt ( double  _x)
inline

◆ isLeftTurn()

static bool dart::math::isLeftTurn ( const Eigen::Vector2d &  p1,
const Eigen::Vector2d &  p2,
const Eigen::Vector2d &  p3 
)
static

◆ isNan() [1/2]

bool dart::math::isNan ( const Eigen::MatrixXd &  _m)
inline

Returns whether _m is a NaN (Not-A-Number) matrix.

◆ isNan() [2/2]

bool dart::math::isNan ( double  _v)
inline

Returns whether _v is a NaN (Not-A-Number) value.

◆ isSymmetric()

bool dart::math::isSymmetric ( const Eigen::MatrixXd &  _m,
double  _tol = 1e-6 
)
inline

Returns whether _m is symmetric or not.

◆ isZero()

bool dart::math::isZero ( double  _theta)
inline

◆ logMap() [1/2]

Eigen::Vector6d dart::math::logMap ( const Eigen::Isometry3d &  _T)

Log mapping.

◆ logMap() [2/2]

Eigen::Vector3d dart::math::logMap ( const Eigen::Matrix3d &  _R)

Log mapping.

Note
When $|Log(R)| = @pi$, Exp(LogR(R) = Exp(-Log(R)). The implementation returns only the positive one.

◆ makeSkewSymmetric()

Eigen::Matrix3d dart::math::makeSkewSymmetric ( const Eigen::Vector3d &  _v)

◆ matrixToEulerXYX()

Eigen::Vector3d dart::math::matrixToEulerXYX ( const Eigen::Matrix3d &  _R)

get the Euler XYX angle from R

◆ matrixToEulerXYZ()

Eigen::Vector3d dart::math::matrixToEulerXYZ ( const Eigen::Matrix3d &  _R)

get the Euler XYZ angle from R

◆ matrixToEulerXZY()

Eigen::Vector3d dart::math::matrixToEulerXZY ( const Eigen::Matrix3d &  _R)

get the Euler XZY angle from R

◆ matrixToEulerYXZ()

Eigen::Vector3d dart::math::matrixToEulerYXZ ( const Eigen::Matrix3d &  _R)

get the Euler YXZ angle from R

◆ matrixToEulerYZX()

Eigen::Vector3d dart::math::matrixToEulerYZX ( const Eigen::Matrix3d &  _R)

get the Euler YZX angle from R

◆ matrixToEulerZXY()

Eigen::Vector3d dart::math::matrixToEulerZXY ( const Eigen::Matrix3d &  _R)

get the Euler ZXY angle from R

◆ matrixToEulerZYX()

Eigen::Vector3d dart::math::matrixToEulerZYX ( const Eigen::Matrix3d &  _R)

get the Euler ZYX angle from R

◆ parallelAxisTheorem()

Eigen::Matrix3d dart::math::parallelAxisTheorem ( const Eigen::Matrix3d &  _original,
const Eigen::Vector3d &  _comShift,
double  _mass 
)

Use the Parallel Axis Theorem to compute the moment of inertia of a body whose center of mass has been shifted from the origin.

◆ quatDeriv()

Eigen::Matrix3d dart::math::quatDeriv ( const Eigen::Quaterniond &  _q,
int  _el 
)

◆ quatSecondDeriv()

Eigen::Matrix3d dart::math::quatSecondDeriv ( const Eigen::Quaterniond &  ,
int  _el1,
int  _el2 
)

◆ quatToExp()

Eigen::Vector3d dart::math::quatToExp ( const Eigen::Quaterniond &  _q)

◆ random()

double dart::math::random ( double  _min,
double  _max 
)
inline
Deprecated:
Please use Random::uniform() instead.

◆ randomVector() [1/2]

template<int N>
Eigen::Matrix<double, N, 1> dart::math::randomVector ( double  _limit)
Deprecated:
Please use Random::uniform() instead.

◆ randomVector() [2/2]

template<int N>
Eigen::Matrix<double, N, 1> dart::math::randomVector ( double  _min,
double  _max 
)
Deprecated:
Please use Random::uniform() instead.

◆ randomVectorXd() [1/2]

Eigen::VectorXd dart::math::randomVectorXd ( std::size_t  size,
double  limit 
)
inline
Deprecated:
Please use Random::uniform() instead.

◆ randomVectorXd() [2/2]

Eigen::VectorXd dart::math::randomVectorXd ( std::size_t  size,
double  min,
double  max 
)
inline
Deprecated:
Please use Random::uniform() instead.

◆ rotatePoint() [1/2]

Eigen::Vector3d dart::math::rotatePoint ( const Eigen::Quaterniond &  _q,
const Eigen::Vector3d &  _pt 
)

◆ rotatePoint() [2/2]

Eigen::Vector3d dart::math::rotatePoint ( const Eigen::Quaterniond &  _q,
double  _x,
double  _y,
double  _z 
)

◆ round()

double dart::math::round ( double  _x)
inline

◆ round2()

double dart::math::round2 ( double  _x)
inline

◆ seedRand()

unsigned dart::math::seedRand ( )
inline

◆ sign() [1/3]

template<typename T >
constexpr int dart::math::sign ( x)
inlineconstexpr

◆ sign() [2/3]

template<typename T >
constexpr int dart::math::sign ( x,
std::false_type   
)
inlineconstexpr

◆ sign() [3/3]

template<typename T >
constexpr int dart::math::sign ( x,
std::true_type   
)
inlineconstexpr

◆ sqr()

double dart::math::sqr ( double  _x)
inline

◆ toDegree()

template<typename T >
constexpr T dart::math::toDegree ( const T &  radian)
constexpr

◆ toEuclideanPoint()

template<typename SpaceT >
SpaceT::EuclideanPoint dart::math::toEuclideanPoint ( const typename SpaceT::Point &  point)

◆ toManifoldPoint()

template<typename SpaceT >
SpaceT::Point dart::math::toManifoldPoint ( const typename SpaceT::EuclideanPoint &  point)

◆ toRadian()

template<typename T >
constexpr T dart::math::toRadian ( const T &  degree)
constexpr

◆ transformInertia()

Inertia dart::math::transformInertia ( const Eigen::Isometry3d &  _T,
const Inertia _I 
)

◆ Tsinc()

double dart::math::Tsinc ( double  _theta)
inline

◆ verifyRotation()

bool dart::math::verifyRotation ( const Eigen::Matrix3d &  _T)

Check if determinant of _R is equat to 1 and all the elements are not NaN values.

◆ verifyTransform()

bool dart::math::verifyTransform ( const Eigen::Isometry3d &  _T)

Check if determinant of the rotational part of _T is equat to 1 and all the elements are not NaN values.

◆ wrapToPi()

double dart::math::wrapToPi ( double  angle)
inline

Compute the angle (in the range of -pi to +pi) which ignores any full rotations.