Gazebo Math

API Reference

8.1.0
eigen3 Namespace Reference

Functions

Eigen::AlignedBox3d convert (const AxisAlignedBox &_b)
 Convert from AxisAlignedBox to Eigen::AlignedBox3d.
 
AxisAlignedBox convert (const Eigen::AlignedBox3d &_b)
 Convert Eigen::AlignedBox3d to AxisAlignedBox.
 
Pose3d convert (const Eigen::Isometry3d &_tf)
 Convert Eigen::Isometry3d to Pose3d.
 
Matrix3d convert (const Eigen::Matrix3d &_m)
 Convert Eigen::Matrix3d to Matrix3d.
 
template<typename Precision >
Matrix6< Precision > convert (const Eigen::Matrix< Precision, 6, 6 > &_m)
 Convert Eigen::Matrix<Precision, 6, 6> to Matrix6d.
 
Quaterniond convert (const Eigen::Quaterniond &_q)
 Convert Eigen::Quaterniond to Quaterniond.
 
Vector3d convert (const Eigen::Vector3d &_v)
 Convert Eigen::Vector3d to Vector3d.
 
Eigen::Matrix3d convert (const Matrix3d &_m)
 Convert from Matrix3d to Eigen::Matrix3d.
 
template<typename Precision >
Eigen::Matrix< Precision, 6, 6 > convert (const Matrix6< Precision > &_m)
 Convert from Matrix6d to Eigen::Matrix<Precision, 6, 6>.
 
Eigen::Isometry3d convert (const Pose3d &_pose)
 Convert Pose3d to Eigen::Isometry3d.
 
Eigen::Quaterniond convert (const Quaterniond &_q)
 Convert Quaterniond to Eigen::Quaterniond.
 
Eigen::Vector3d convert (const Vector3d &_v)
 Convert from Vector3d to Eigen::Vector3d.
 
Eigen::Matrix3d covarianceMatrix (const std::vector< math::Vector3d > &_vertices)
 Get covariance matrix from a set of 3d vertices https://github.com/isl-org/Open3D/blob/76c2baf9debd460900f056a9b51e9a80de9c0e64/cpp/open3d/utility/Eigen.cpp#L305.
 
OrientedBoxd verticesToOrientedBox (const std::vector< math::Vector3d > &_vertices)
 Get the oriented 3d bounding box of a set of 3d vertices using PCA http://codextechnicanum.blogspot.com/2015/04/find-minimum-oriented-bounding-box-of.html.
 

Function Documentation

◆ convert() [1/12]

Eigen::AlignedBox3d convert ( const AxisAlignedBox &  _b)
inline

Convert from AxisAlignedBox to Eigen::AlignedBox3d.

Parameters
[in]_bAxisAlignedBox to convert
Returns
The equivalent Eigen::AlignedBox3d.

References convert().

◆ convert() [2/12]

AxisAlignedBox convert ( const Eigen::AlignedBox3d &  _b)
inline

Convert Eigen::AlignedBox3d to AxisAlignedBox.

Parameters
[in]_bEigen::AlignedBox3d to convert.
Returns
The equivalent AxisAlignedBox.

References convert().

◆ convert() [3/12]

Pose3d convert ( const Eigen::Isometry3d &  _tf)
inline

Convert Eigen::Isometry3d to Pose3d.

Parameters
[in]_tfEigen::Isometry3d to convert.
Returns
The equivalent Pose3d.

References convert().

◆ convert() [4/12]

Matrix3d convert ( const Eigen::Matrix3d &  _m)
inline

Convert Eigen::Matrix3d to Matrix3d.

Parameters
[in]_mEigen::Matrix3d to convert.
Returns
The equivalent Matrix3d.

◆ convert() [5/12]

template<typename Precision >
Matrix6< Precision > convert ( const Eigen::Matrix< Precision, 6, 6 > &  _m)
inline

Convert Eigen::Matrix<Precision, 6, 6> to Matrix6d.

Parameters
[in]_mEigen::Matrix<Precision, 6, 6> to convert.
Returns
The equivalent Matrix6d.
Template Parameters
PrecisionPrecision such as int, double or float.

◆ convert() [6/12]

Quaterniond convert ( const Eigen::Quaterniond &  _q)
inline

Convert Eigen::Quaterniond to Quaterniond.

Parameters
[in]_qEigen::Quaterniond to convert.
Returns
The equivalent Quaterniond.

◆ convert() [7/12]

Vector3d convert ( const Eigen::Vector3d &  _v)
inline

Convert Eigen::Vector3d to Vector3d.

Parameters
[in]_vEigen::Vector3d to convert.
Returns
The equivalent Vector3d.

◆ convert() [8/12]

Eigen::Matrix3d convert ( const Matrix3d &  _m)
inline

Convert from Matrix3d to Eigen::Matrix3d.

Parameters
[in]_mMatrix3d to convert.
Returns
The equivalent Eigen::Matrix3d.

◆ convert() [9/12]

template<typename Precision >
Eigen::Matrix< Precision, 6, 6 > convert ( const Matrix6< Precision > &  _m)
inline

Convert from Matrix6d to Eigen::Matrix<Precision, 6, 6>.

Parameters
[in]_mMatrix6d to convert.
Returns
The equivalent Eigen::Matrix<Precision, 6, 6>.
Template Parameters
PrecisionPrecision such as int, double or float.

◆ convert() [10/12]

Eigen::Isometry3d convert ( const Pose3d &  _pose)
inline

Convert Pose3d to Eigen::Isometry3d.

Parameters
[in]_posePose3d to convert.
Returns
The equivalent Eigen::Isometry3d.

References convert().

◆ convert() [11/12]

Eigen::Quaterniond convert ( const Quaterniond &  _q)
inline

Convert Quaterniond to Eigen::Quaterniond.

Parameters
[in]_qQuaterniond to convert.
Returns
The equivalent Eigen::Quaterniond.

◆ convert() [12/12]

Eigen::Vector3d convert ( const Vector3d &  _v)
inline

Convert from Vector3d to Eigen::Vector3d.

Parameters
[in]_vVector3d to convert
Returns
The equivalent Eigen::Vector3d.

Referenced by convert(), convert(), convert(), and convert().

◆ covarianceMatrix()

Eigen::Matrix3d covarianceMatrix ( const std::vector< math::Vector3d > &  _vertices)
inline

Get covariance matrix from a set of 3d vertices https://github.com/isl-org/Open3D/blob/76c2baf9debd460900f056a9b51e9a80de9c0e64/cpp/open3d/utility/Eigen.cpp#L305.

Parameters
[in]_verticesa vector of 3d vertices
Returns
Covariance matrix

References vector< T >::empty(), and vector< T >::size().

Referenced by verticesToOrientedBox().

◆ verticesToOrientedBox()

OrientedBoxd verticesToOrientedBox ( const std::vector< math::Vector3d > &  _vertices)
inline

Get the oriented 3d bounding box of a set of 3d vertices using PCA http://codextechnicanum.blogspot.com/2015/04/find-minimum-oriented-bounding-box-of.html.

Parameters
[in]_verticesa vector of 3d vertices
Returns
Oriented 3D box

References covarianceMatrix(), vector< T >::empty(), and vector< T >::size().