5 #ifndef __pinocchio_symmetric3_hpp__ 6 #define __pinocchio_symmetric3_hpp__ 8 #include "pinocchio/macros.hpp" 9 #include "pinocchio/math/matrix.hpp" 14 template<
typename _Scalar,
int _Options>
20 typedef Eigen::Matrix<Scalar,3,1,Options>
Vector3;
21 typedef Eigen::Matrix<Scalar,6,1,Options>
Vector6;
22 typedef Eigen::Matrix<Scalar,3,3,Options>
Matrix3;
23 typedef Eigen::Matrix<Scalar,2,2,Options>
Matrix2;
24 typedef Eigen::Matrix<Scalar,3,2,Options>
Matrix32;
26 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
31 template<
typename Sc,
int Opt>
34 assert( (I-I.transpose()).isMuchSmallerThan(I) );
43 const Scalar & a3,
const Scalar & a4,
const Scalar & a5)
44 {
m_data << a0,a1,a2,a3,a4,a5; }
68 {
return m_data == other.m_data; }
71 {
return !(*
this == other); }
74 const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
const 75 {
return m_data.isApprox(other.m_data,prec); }
77 bool isZero(
const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
const 78 {
return m_data.isZero(prec); }
88 const Scalar &
x = v[0], & y = v[1], & z = v[2];
91 x*z , y*z , -x*x-y*y );
97 const Scalar &
x = v.v[0], & y = v.v[1], & z = v.v[2];
105 const Scalar &
x = v.v[0], & y = v.v[1], & z = v.v[2];
115 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(
D,3,3);
116 Matrix3 result (S.matrix());
132 const Scalar &
x = v[0], & y = v[1], & z = v[2];
135 m* x*z,m* y*z,-m*(x*x+y*y));
140 {
return AlphaSkewSquare(m,sk); }
144 const Scalar &
x = v.v[0], & y = v.v[1], & z = v.v[2];
153 const Scalar &
x = v.v[0], & y = v.v[1], & z = v.v[2];
182 a*b+b*
c+d*e, b*b+
c*
c+e*e,
183 a*d+b*e+d*f, b*d+
c*e+e*f, d*d+e*e+f*f );
196 Scalar
vtiv (
const Vector3 &
v)
const 198 const Scalar &
x = v[0];
199 const Scalar & y = v[1];
200 const Scalar & z = v[2];
202 const Scalar xx = x*
x;
203 const Scalar xy = x*y;
204 const Scalar xz = x*z;
205 const Scalar yy = y*y;
206 const Scalar yz = y*z;
207 const Scalar zz = z*z;
222 template<
typename Vector3,
typename Matrix3>
223 static void vxs(
const Eigen::MatrixBase<Vector3> &
v,
225 const Eigen::MatrixBase<Matrix3> & M)
227 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3,3);
228 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Matrix3,3,3);
230 const Scalar &
a = S3.data()[0];
231 const Scalar & b = S3.data()[1];
232 const Scalar &
c = S3.data()[2];
233 const Scalar &
d = S3.data()[3];
234 const Scalar & e = S3.data()[4];
235 const Scalar & f = S3.data()[5];
238 const typename Vector3::RealScalar & v0 = v[0];
239 const typename Vector3::RealScalar & v1 = v[1];
240 const typename Vector3::RealScalar & v2 = v[2];
243 M_(0,0) = d * v1 - b * v2;
244 M_(1,0) = a * v2 - d * v0;
245 M_(2,0) = b * v0 - a * v1;
247 M_(0,1) = e * v1 - c * v2;
248 M_(1,1) = b * v2 - e * v0;
249 M_(2,1) = c * v0 - b * v1;
251 M_(0,2) = f * v1 - e * v2;
252 M_(1,2) = d * v2 - f * v0;
253 M_(2,2) = e * v0 - d * v1;
266 template<
typename Vector3>
267 Matrix3
vxs(
const Eigen::MatrixBase<Vector3> &
v)
const 283 template<
typename Vector3,
typename Matrix3>
284 static void svx(
const Eigen::MatrixBase<Vector3> &
v,
286 const Eigen::MatrixBase<Matrix3> & M)
288 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3,3);
289 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Matrix3,3,3);
291 const Scalar &
a = S3.data()[0];
292 const Scalar & b = S3.data()[1];
293 const Scalar &
c = S3.data()[2];
294 const Scalar &
d = S3.data()[3];
295 const Scalar & e = S3.data()[4];
296 const Scalar & f = S3.data()[5];
298 const typename Vector3::RealScalar & v0 = v[0];
299 const typename Vector3::RealScalar & v1 = v[1];
300 const typename Vector3::RealScalar & v2 = v[2];
303 M_(0,0) = b * v2 - d * v1;
304 M_(1,0) = c * v2 - e * v1;
305 M_(2,0) = e * v2 - f * v1;
307 M_(0,1) = d * v0 - a * v2;
308 M_(1,1) = e * v0 - b * v2;
309 M_(2,1) = f * v0 - d * v2;
311 M_(0,2) = a * v1 - b * v0;
312 M_(1,2) = b * v1 - c * v0;
313 M_(2,2) = d * v1 - e * v0;
324 template<
typename Vector3>
325 Matrix3
svx(
const Eigen::MatrixBase<Vector3> &
v)
const 339 m_data += s2.m_data;
return *
this;
342 template<
typename V3in,
typename V3out>
344 const Eigen::MatrixBase<V3in> & vin,
345 const Eigen::MatrixBase<V3out> & vout)
347 EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(V3in,Vector3);
348 EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(V3out,Vector3);
352 vout_[0] = S3.m_data(0) * vin[0] + S3.m_data(1) * vin[1] + S3.m_data(3) * vin[2];
353 vout_[1] = S3.m_data(1) * vin[0] + S3.m_data(2) * vin[1] + S3.m_data(4) * vin[2];
354 vout_[2] = S3.m_data(3) * vin[0] + S3.m_data(4) * vin[1] + S3.m_data(5) * vin[2];
357 template<
typename V3>
384 assert( (S-S.transpose()).isMuchSmallerThan(S) );
392 assert( (S-S.transpose()).isMuchSmallerThan(S) );
417 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(
D,3,3);
418 assert(
isUnitary(R.transpose()*R) &&
"R is not a Unitary matrix");
426 const Matrix2 Y( R.template block<2,3>(1,0) * L );
429 Sres.m_data(1) = Y(0,0)*R(0,0) + Y(0,1)*R(0,1);
430 Sres.m_data(2) = Y(0,0)*R(1,0) + Y(0,1)*R(1,1);
431 Sres.m_data(3) = Y(1,0)*R(0,0) + Y(1,1)*R(0,1);
432 Sres.m_data(4) = Y(1,0)*R(1,0) + Y(1,1)*R(1,1);
433 Sres.m_data(5) = Y(1,0)*R(2,0) + Y(1,1)*R(2,1);
441 Sres.m_data(0) = L(0,0) + L(1,1) - Sres.m_data(2) - Sres.m_data(5);
444 Sres.m_data(0) +=
m_data(5);
445 Sres.m_data(1) += r(2); Sres.m_data(2)+=
m_data(5);
446 Sres.m_data(3) +=-r(1); Sres.m_data(4)+= r(0); Sres.m_data(5) +=
m_data(5);
452 template<
typename NewScalar>
474 #endif // ifndef __pinocchio_symmetric3_hpp__ AlphaSkewSquare(const Scalar &m, const SkewSquare &v)
AlphaSkewSquare(const Scalar &m, const Vector3 &v)
friend AlphaSkewSquare operator*(const Scalar &m, const SkewSquare &sk)
static Symmetric3Tpl Random()
Eigen::Matrix< Scalar, 3, 3, Options > Matrix3
Symmetric3Tpl & operator-=(const SkewSquare &v)
Symmetric3Tpl rotate(const Eigen::MatrixBase< D > &R) const
Symmetric3Tpl operator-(const SkewSquare &v) const
Symmetric3Tpl operator+(const Symmetric3Tpl &s2) const
Symmetric3Tpl(const Vector6 &I)
const Scalar & operator()(const int &i, const int &j) const
Symmetric3Tpl(const Scalar &a0, const Scalar &a1, const Scalar &a2, const Scalar &a3, const Scalar &a4, const Scalar &a5)
static Symmetric3Tpl Zero()
Symmetric3Tpl< NewScalar, Options > cast() const
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
bool isUnitary(const Eigen::MatrixBase< MatrixLike > &mat, const typename MatrixLike::RealScalar &prec=Eigen::NumTraits< typename MatrixLike::Scalar >::dummy_precision())
Check whether the input matrix is Unitary within the given precision.
bool isZero(const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
Symmetric3Tpl & operator+=(const Symmetric3Tpl &s2)
Vector3 operator*(const Eigen::MatrixBase< V3 > &v) const
Eigen::Matrix< Scalar, 6, 1, Options > Vector6
static Symmetric3Tpl RandomPositive()
static void svx(const Eigen::MatrixBase< Vector3 > &v, const Symmetric3Tpl &S3, const Eigen::MatrixBase< Matrix3 > &M)
Performs the operation .
Matrix32 decomposeltI() const
Computes L for a symmetric matrix A.
Eigen::Matrix< Scalar, 2, 2, Options > Matrix2
Matrix3 vxs(const Eigen::MatrixBase< Vector3 > &v) const
Performs the operation . This operation is equivalent to applying the cross product of v on each colu...
static void rhsMult(const Symmetric3Tpl &S3, const Eigen::MatrixBase< V3in > &vin, const Eigen::MatrixBase< V3out > &vout)
static Symmetric3Tpl Identity()
Scalar vtiv(const Vector3 &v) const
bool operator!=(const Symmetric3Tpl &other) const
bool operator==(const Symmetric3Tpl &other) const
const Vector6 & data() const
Main pinocchio namespace.
SkewSquare(const Vector3 &v)
bool isApprox(const Symmetric3Tpl &other, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
static void vxs(const Eigen::MatrixBase< Vector3 > &v, const Symmetric3Tpl &S3, const Eigen::MatrixBase< Matrix3 > &M)
Performs the operation . This operation is equivalent to applying the cross product of v on each colu...
Matrix3 svx(const Eigen::MatrixBase< Vector3 > &v) const
Performs the operation .
Symmetric3Tpl(const Eigen::Matrix< Sc, 3, 3, Opt > &I)
Symmetric3Tpl operator+(const Matrix3 &S) const
void fill(const Scalar value)
Eigen::Matrix< Scalar, 3, 2, Options > Matrix32
Symmetric3Tpl operator-(const Matrix3 &S) const