Go to the documentation of this file.
5 #ifndef __pinocchio_spatial_motion_dense_hpp__
6 #define __pinocchio_spatial_motion_dense_hpp__
13 template<
typename Derived>
19 template<
typename Derived,
typename MotionDerived>
25 template<
typename Derived>
48 angular().setRandom();
55 X.template block<3, 3>(ANGULAR, ANGULAR) =
X.template block<3, 3>(LINEAR, LINEAR) =
57 X.template block<3, 3>(LINEAR, ANGULAR) =
skew(linear());
58 X.template block<3, 3>(ANGULAR, LINEAR).setZero();
66 X.template block<3, 3>(ANGULAR, ANGULAR) =
X.template block<3, 3>(LINEAR, LINEAR) =
68 X.template block<3, 3>(ANGULAR, LINEAR) =
skew(linear());
69 X.template block<3, 3>(LINEAR, ANGULAR).setZero();
76 HomogeneousMatrixType
M;
77 M.template block<3, 3>(0, 0) =
skew(angular());
78 M.template block<3, 1>(0, 3) = linear();
79 M.template block<1, 4>(3, 0).setZero();
86 return linear() == other.
linear() && angular() == other.
angular();
92 return other.
derived() == derived();
99 return derived().set(other.
derived());
104 return derived().set(other.
derived());
107 template<
typename D2>
110 linear() = other.
linear();
115 template<
typename D2>
118 other.
derived().setTo(derived());
122 template<
typename V6>
125 EIGEN_STATIC_ASSERT_VECTOR_ONLY(V6);
126 assert(
v.size() == 6);
127 linear() =
v.template segment<3>(LINEAR);
128 angular() =
v.template segment<3>(ANGULAR);
134 return derived().__opposite__();
136 template<
typename M1>
139 return derived().__plus__(
v.derived());
141 template<
typename M1>
144 return derived().__minus__(
v.derived());
147 template<
typename M1>
150 return derived().__pequ__(
v.derived());
152 template<
typename M1>
155 v.derived().addTo(derived());
159 template<
typename M1>
162 return derived().__mequ__(
v.derived());
167 return MotionPlain(-linear(), -angular());
170 template<
typename M1>
173 return MotionPlain(linear() +
v.linear(), angular() +
v.angular());
176 template<
typename M1>
179 return MotionPlain(linear() -
v.linear(), angular() -
v.angular());
182 template<
typename M1>
185 linear() +=
v.linear();
186 angular() +=
v.angular();
190 template<
typename M1>
193 linear() -=
v.linear();
194 angular() -=
v.angular();
198 template<
typename OtherScalar>
201 return MotionPlain(
alpha * linear(),
alpha * angular());
204 template<
typename OtherScalar>
207 return derived().__mult__((OtherScalar)(1) /
alpha);
210 template<
typename F1>
213 return phi.
linear().dot(linear()) + phi.
angular().dot(angular());
219 return d.motionAction(derived());
222 template<
typename M1,
typename M2>
225 mout.
linear() =
v.linear().cross(angular()) +
v.angular().cross(linear());
226 mout.
angular() =
v.angular().cross(angular());
229 template<
typename M1>
237 template<
typename M2>
240 const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
const
242 return derived().isApprox_impl(m2, prec);
245 template<
typename D2>
248 const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
const
250 return linear().isApprox(m2.
linear(), prec) && angular().isApprox(m2.
angular(), prec);
255 return linear().isZero(prec) && angular().isZero(prec);
258 template<
typename S2,
int O2,
typename D2>
261 v.angular().noalias() =
m.rotation() * angular();
262 v.linear().noalias() =
m.rotation() * linear() +
m.translation().cross(
v.angular());
265 template<
typename S2,
int O2>
273 template<
typename S2,
int O2,
typename D2>
276 v.linear().noalias() =
277 m.rotation().transpose() * (linear() -
m.translation().cross(angular()));
278 v.angular().noalias() =
m.rotation().transpose() * angular();
281 template<
typename S2,
int O2>
292 os <<
" v = " << linear().transpose() << std::endl
293 <<
" w = " << angular().transpose() << std::endl;
299 return derived().ref();
310 template<
typename M1,
typename M2>
316 template<
typename M1,
typename F1>
319 return v.derived().cross(
f.derived());
322 template<
typename M1>
331 #endif // ifndef __pinocchio_spatial_motion_dense_hpp__
MotionPlain __opposite__() const
SE3GroupAction< Derived >::ReturnType ReturnType
MotionPlain operator-(const MotionDense< M1 > &v) const
Derived & operator=(const Eigen::MatrixBase< V6 > &v)
ConstLinearType linear() const
Return the linear part of the force vector.
traits< Derived >::MotionRefType MotionRefType
void se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
Base interface for forces representation.
MOTION_TYPEDEF_TPL(Derived)
ConstAngularType angular() const
Derived & operator-=(const MotionDense< M1 > &v)
Derived & operator+=(const MotionBase< M1 > &v)
bool isEqual_impl(const MotionBase< D2 > &other) const
ConstLinearType linear() const
bool isApprox(const Derived &other, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
Return type of the ation of a Motion onto an object of type D.
bool isZero(const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
TridiagonalSymmetricMatrixApplyOnTheLeftReturnType< LhsMatrixType, TridiagonalSymmetricMatrixTpl< S, O > > operator*(const Eigen::MatrixBase< LhsMatrixType > &lhs, const TridiagonalSymmetricMatrixTpl< S, O > &rhs)
ConstLinearType linear() const
MotionPlain operator-() const
void se3Action_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
Derived & operator+=(const MotionDense< M1 > &v)
void skew(const Eigen::MatrixBase< Vector3 > &v, const Eigen::MatrixBase< Matrix3 > &M)
Computes the skew representation of a given 3d vector, i.e. the antisymmetric matrix representation o...
MotionPlain __plus__(const MotionDense< M1 > &v) const
MotionPlain operator+(const MotionDense< M1 > &v) const
bool isApprox_impl(const MotionDense< D2 > &m2, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
Derived & operator=(const MotionDense< D2 > &other)
MotionPlain __mult__(const OtherScalar &alpha) const
SE3GroupAction< Derived >::ReturnType se3Action_impl(const SE3Tpl< S2, O2 > &m) const
MotionAlgebraAction< Derived, MotionDerived >::ReturnType ReturnType
MotionPlain motionAction(const MotionDense< M1 > &v) const
Derived & __mequ__(const MotionDense< M1 > &v)
ActionMatrixType toActionMatrix_impl() const
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
Scalar dot(const ForceBase< F1 > &phi) const
Derived & operator=(const MotionDense &other)
MotionPlain __div__(const OtherScalar &alpha) const
ActionMatrixType toDualActionMatrix_impl() const
MotionAlgebraAction< D, Derived >::ReturnType cross_impl(const D &d) const
void motionAction(const MotionDense< M1 > &v, MotionDense< M2 > &mout) const
Derived & __pequ__(const MotionDense< M1 > &v)
SE3GroupAction< Derived >::ReturnType se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m) const
EIGEN_STRONG_INLINE MotionDerived::MotionPlain operator^(const MotionDense< MotionDerived > &m1, const MotionHelicalUnalignedTpl< S2, O2 > &m2)
HomogeneousMatrixType toHomogeneousMatrix_impl() const
bool isZero_impl(const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
Derived & set(const MotionDense< D2 > &other)
Common traits structure to fully define base classes for CRTP.
MotionPlain __minus__(const MotionDense< M1 > &v) const
ConstAngularType angular() const
Return the angular part of the force vector.
MotionBase< Derived > Base
Derived & operator=(const MotionBase< D2 > &other)
void disp_impl(std::ostream &os) const
bool isEqual_impl(const MotionDense< D2 > &other) const
ConstAngularType angular() const
Main pinocchio namespace.
bool isApprox(const MotionDense< M2 > &m2, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
pinocchio
Author(s):
autogenerated on Mon Dec 16 2024 03:41:04