Go to the documentation of this file.
18 #ifndef GZ_MATH_EIGEN3_CONVERSIONS_HH_
19 #define GZ_MATH_EIGEN3_CONVERSIONS_HH_
21 #include <Eigen/Geometry>
48 const gz::math::AxisAlignedBox &_b)
63 matrix(i, j) = _m(i, j);
75 template<
typename Precision>
79 Eigen::Matrix<Precision, 6, 6> matrix;
84 matrix(i, j) = _m(i, j);
110 Eigen::Isometry3d tf = Eigen::Isometry3d::Identity();
111 tf.translation() =
convert(_pose.Pos());
134 const Eigen::AlignedBox3d &_b)
136 gz::math::AxisAlignedBox box;
153 matrix(i, j) = _m(i, j);
165 template<
typename Precision>
174 matrix(i, j) = _m(i, j);
Matrix3< double > Matrix3d
Definition: gz/math/Matrix3.hh:548
Encapsulates a position and rotation in three space.
Definition: gz/math/Pose3.hh:34
Definition: gz/math/AdditivelySeparableScalarField3.hh:27
Eigen::Vector3d convert(const Vector3d &_v)
Convert from Vector3d to Eigen::Vector3d.
Definition: gz/math/eigen3/Conversions.hh:38
const Quaternion< T > & Rot() const
Get the rotation.
Definition: gz/math/Pose3.hh:420
T X() const
Get the x value.
Definition: gz/math/Vector3.hh:654
A 3x3 matrix class.
Definition: gz/math/Matrix3.hh:40
const Vector3d & Max() const
Get the maximum corner.
A quaternion class.
Definition: gz/math/Matrix3.hh:35
Pose3< double > Pose3d
Definition: gz/math/Pose3.hh:495
Quaternion< double > Quaterniond
Definition: gz/math/Quaternion.hh:1101
const Vector3< T > & Pos() const
Get the position.
Definition: gz/math/Pose3.hh:361
T Z() const
Get the z value.
Definition: gz/math/Vector3.hh:668
const T & Y() const
Get the y component.
Definition: gz/math/Quaternion.hh:979
The Vector3 class represents the generic vector containing 3 elements. Since it's commonly used to ke...
Definition: gz/math/Vector3.hh:41
A 6x6 matrix class.
Definition: gz/math/Matrix6.hh:35
const Vector3d & Min() const
Get the minimum corner.
const T & Z() const
Get the z component.
Definition: gz/math/Quaternion.hh:986
Mathematical representation of a box that is aligned along an X,Y,Z axis.
Definition: gz/math/AxisAlignedBox.hh:42
const T & X() const
Get the x component.
Definition: gz/math/Quaternion.hh:972
T Y() const
Get the y value.
Definition: gz/math/Vector3.hh:661
Vector3< double > Vector3d
Definition: gz/math/Vector3.hh:770
const T & W() const
Get the w component.
Definition: gz/math/Quaternion.hh:965