5 #ifndef __pinocchio_spatial_symmetric3__
6 #define __pinocchio_spatial_symmetric3__
14 template<
typename _Scalar,
int _Options>
20 template<
typename _Scalar,
int _Options>
29 typedef Eigen::Matrix<Scalar, 3, 1, Options>
Vector3;
30 typedef Eigen::Matrix<Scalar, 6, 1, Options>
Vector6;
31 typedef Eigen::Matrix<Scalar, 3, 3, Options>
Matrix3;
32 typedef Eigen::Matrix<Scalar, 2, 2, Options>
Matrix2;
33 typedef Eigen::Matrix<Scalar, 3, 2, Options>
Matrix32;
35 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
42 template<
typename Sc,
int Opt>
64 template<
typename S2,
int O2>
67 *
this = other.template cast<Scalar>();
126 template<
typename Vector3Like>
129 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3);
143 return !(*
this == other);
148 const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
const
153 bool isZero(
const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
const
155 return m_data.isZero(prec);
163 template<
typename Matrix3Like>
164 void inverse(
const Eigen::MatrixBase<Matrix3Like> & res_)
const
166 Matrix3Like &
res = res_.const_cast_derived();
170 res(0, 0) = a33 * a22 - a32 * a32;
171 res(1, 0) =
res(0, 1) = -(a33 * a21 - a32 * a31);
172 res(2, 0) =
res(0, 2) = a32 * a21 - a22 * a31;
173 res(1, 1) = a33 * a11 - a31 * a31;
174 res(2, 1) =
res(1, 2) = -(a32 * a11 - a21 * a31);
175 res(2, 2) = a22 * a11 - a21 * a21;
177 const Scalar det = a11 *
res(0, 0) + a21 *
res(0, 1) + a31 *
res(0, 2);
204 const Scalar &
x =
v.v[0], &
y =
v.v[1], &z =
v.v[2];
212 const Scalar &
x =
v.v[0], &
y =
v.v[1], &z =
v.v[2];
242 -
m * (
y *
y + z * z),
m *
x *
y, -
m * (
x *
x + z * z),
m *
x * z,
m *
y * z,
243 -
m * (
x *
x +
y *
y));
249 return AlphaSkewSquare(
m, sk);
254 const Scalar &
x =
v.v[0], &
y =
v.v[1], &z =
v.v[2];
263 const Scalar &
x =
v.v[0], &
y =
v.v[1], &z =
v.v[2];
301 b *
d +
c * e + e *
f,
d *
d + e * e +
f *
f);
350 template<
typename Vector3,
typename Matrix3>
352 const Eigen::MatrixBase<Vector3> &
v,
354 const Eigen::MatrixBase<Matrix3> & M)
356 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(
Vector3, 3);
357 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(
Matrix3, 3, 3);
366 const typename Vector3::RealScalar &
v0 =
v[0];
367 const typename Vector3::RealScalar & v1 =
v[1];
368 const typename Vector3::RealScalar & v2 =
v[2];
371 M_(0, 0) =
d * v1 -
b * v2;
372 M_(1, 0) =
a * v2 -
d *
v0;
373 M_(2, 0) =
b *
v0 -
a * v1;
375 M_(0, 1) = e * v1 -
c * v2;
376 M_(1, 1) =
b * v2 - e *
v0;
377 M_(2, 1) =
c *
v0 -
b * v1;
379 M_(0, 2) =
f * v1 - e * v2;
380 M_(1, 2) =
d * v2 -
f *
v0;
381 M_(2, 2) = e *
v0 -
d * v1;
394 template<
typename Vector3>
411 template<
typename Vector3,
typename Matrix3>
413 const Eigen::MatrixBase<Vector3> &
v,
415 const Eigen::MatrixBase<Matrix3> & M)
417 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(
Vector3, 3);
418 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(
Matrix3, 3, 3);
427 const typename Vector3::RealScalar &
v0 =
v[0];
428 const typename Vector3::RealScalar & v1 =
v[1];
429 const typename Vector3::RealScalar & v2 =
v[2];
432 M_(0, 0) =
b * v2 -
d * v1;
433 M_(1, 0) =
c * v2 - e * v1;
434 M_(2, 0) = e * v2 -
f * v1;
436 M_(0, 1) =
d *
v0 -
a * v2;
437 M_(1, 1) = e *
v0 -
b * v2;
438 M_(2, 1) =
f *
v0 -
d * v2;
440 M_(0, 2) =
a * v1 -
b *
v0;
441 M_(1, 2) =
b * v1 -
c *
v0;
442 M_(2, 2) =
d * v1 - e *
v0;
453 template<
typename Vector3>
489 template<
typename V3in,
typename V3out>
492 const Eigen::MatrixBase<V3in> & vin,
493 const Eigen::MatrixBase<V3out> & vout)
495 EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(V3in,
Vector3);
496 EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(V3out,
Vector3);
505 template<
typename V3>
530 template<
typename Matrix3Like>
539 template<
typename Matrix3Like>
564 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(
D, 3, 3);
566 check_expression_if_real<Scalar>(
isUnitary(
R.transpose() *
R))
567 &&
"R is not a Unitary matrix");
575 const Matrix2 Y(
R.template block<2, 3>(1, 0) *
L);
578 Sres.
m_data(1) =
Y(0, 0) *
R(0, 0) +
Y(0, 1) *
R(0, 1);
579 Sres.
m_data(2) =
Y(0, 0) *
R(1, 0) +
Y(0, 1) *
R(1, 1);
580 Sres.
m_data(3) =
Y(1, 0) *
R(0, 0) +
Y(1, 1) *
R(0, 1);
581 Sres.
m_data(4) =
Y(1, 0) *
R(1, 0) +
Y(1, 1) *
R(1, 1);
582 Sres.
m_data(5) =
Y(1, 0) *
R(2, 0) +
Y(1, 1) *
R(2, 1);
604 template<
typename NewScalar>
612 os <<
"m_data: " << S3.
m_data.transpose() <<
"\n";
632 #endif // ifndef __pinocchio_spatial_symmetric3__