6 #ifndef LIB_ALMATH_SCENEGRAPH_URDFEIGEN_H
7 #define LIB_ALMATH_SCENEGRAPH_URDFEIGEN_H
10 #include <Eigen/Geometry>
17 return Eigen::AngleAxisd(rpy[2], Eigen::Vector3d::UnitZ()) *
18 Eigen::AngleAxisd(rpy[1], Eigen::Vector3d::UnitY()) *
19 Eigen::AngleAxisd(rpy[0], Eigen::Vector3d::UnitX());
24 Eigen::Vector3d ypr = t.eulerAngles(2, 1, 0);
29 typedef Eigen::Map<const Eigen::Vector3d> Vector3dMap;
30 return Eigen::Translation3d(Vector3dMap(p.xyz().data())) *
36 m(0, 0) = inertial.
ixx();
37 m(0, 1) = m(1, 0) = inertial.
ixy();
38 m(0, 2) = m(2, 0) = inertial.
ixz();
39 m(1, 1) = inertial.
iyy();
40 m(1, 2) = m(2, 1) = inertial.
iyz();
41 m(2, 2) = inertial.
izz();
46 template <
typename Scalar,
typename Derived0,
typename Derived1>
48 const Eigen::MatrixBase<Derived0> &position,
49 Eigen::MatrixBase<Derived1> &output) {
50 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Derived0, 3, 1)
51 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Derived1, 3, 3)
53 (Eigen::internal::is_same<Scalar, typename Derived0::Scalar>::value),
54 YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)
56 (Eigen::internal::is_same<Scalar, typename Derived1::Scalar>::value),
57 YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)
58 typedef Eigen::Array<Scalar, 3, 1> Array3;
59 Array3 position2 = position.array().square();
60 output(0, 0) += mass * (position2[1] + position2[2]);
61 output(1, 1) += mass * (position2[0] + position2[2]);
62 output(2, 2) += mass * (position2[0] + position2[1]);
64 output(0, 1) += -mass * position[0] * position[1];
65 output(1, 0) += -mass * position[0] * position[1];
67 output(0, 2) += -mass * position[0] * position[2];
68 output(2, 0) += -mass * position[0] * position[2];
70 output(1, 2) += -mass * position[1] * position[2];
71 output(2, 1) += -mass * position[1] * position[2];
80 template <
typename Scalar,
typename EPose,
typename Derived1>
82 const Eigen::MatrixBase<Derived1> &inertia_a, Scalar mass_b,
84 const Eigen::MatrixBase<Derived1> &inertia_b,
85 Scalar &mass_c, EPose &pose_c,
86 Eigen::MatrixBase<Derived1> &inertia_c) {
87 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Derived1, 3, 3)
89 (Eigen::internal::is_same<Scalar, typename EPose::Scalar>::value),
90 YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)
92 (Eigen::internal::is_same<Scalar, typename Derived1::Scalar>::value),
93 YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)
94 typedef Eigen::Transform<Scalar, 3, Eigen::AffineCompact, Eigen::DontAlign> T;
95 typedef Eigen::Matrix<Scalar, 3, 3> Matrix3;
96 typedef Eigen::Matrix<Scalar, 3, 1> Vector3;
99 mass_c = mass_a + mass_b;
102 pose_c.translation() =
103 (mass_a * pose_a.translation() + mass_b * pose_b.translation()) / mass_c;
104 pose_c.linear() = pose_a.linear();
107 inertia_c = inertia_a;
108 Vector3 displ = pose_c.translation() - pose_a.translation();
112 Matrix3 rot_cb = pose_c.linear().transpose() * pose_b.linear();
113 inertia_c += rot_cb.transpose() * inertia_b * rot_cb;
114 displ = pose_c.translation() - pose_b.translation();
118 template <
typename Scalar,
typename Derived0,
typename Derived1>
120 Eigen::MatrixBase<Derived0> &com_a,
121 Eigen::MatrixBase<Derived1> &inertia_a) {
122 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Derived0, 3, 1)
123 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Derived1, 3, 3)
125 (Eigen::internal::is_same<Scalar, typename Derived0::Scalar>::value),
126 YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)
128 (Eigen::internal::is_same<Scalar, typename Derived1::Scalar>::value),
129 YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)
130 typedef Eigen::Transform<Scalar, 3, Eigen::AffineCompact, Eigen::DontAlign> T;
131 typedef Eigen::Matrix<Scalar, 3, 3> Matrix3;
132 typedef Eigen::Matrix<Scalar, 3, 1> Vector3;
134 mass = inertial.
mass();
136 com_a = t_ab.translation();
138 inertia_a = t_ab.linear().transpose() * inertia_b * t_ab.linear();
void addPointMassInertia(Scalar mass, const Eigen::MatrixBase< Derived0 > &position, Eigen::MatrixBase< Derived1 > &output)
std::array< double, 3 > Array3d
Eigen::Isometry3d toEigenTransform(const AL::urdf::Pose &p)
Eigen::Matrix3f toEigenMatrix3(const AL::Math::Transform &tr)
Eigen::Quaterniond eigenQuaternionFromUrdfRpy(const AL::urdf::Array3d &rpy)
void urdfInertialToEigen(const AL::urdf::Inertial &inertial, Scalar &mass, Eigen::MatrixBase< Derived0 > &com_a, Eigen::MatrixBase< Derived1 > &inertia_a)
void squashInertial(Scalar mass_a, const EPose &pose_a, const Eigen::MatrixBase< Derived1 > &inertia_a, Scalar mass_b, const EPose &pose_b, const Eigen::MatrixBase< Derived1 > &inertia_b, Scalar &mass_c, EPose &pose_c, Eigen::MatrixBase< Derived1 > &inertia_c)
AL::urdf::Array3d urdfRpyFromEigenMatrix3(const T &t)