Go to the documentation of this file.
5 #ifndef __pinocchio_spatial_motion_ref_hpp__
6 #define __pinocchio_spatial_motion_ref_hpp__
11 template<
typename Vector6ArgType>
22 typedef Eigen::Matrix<Scalar, 3, 1, Options>
Vector3;
23 typedef Eigen::Matrix<Scalar, 4, 4, Options>
Matrix4;
24 typedef Eigen::Matrix<Scalar, 6, 6, Options>
Matrix6;
27 typedef typename Vector6ArgType::template FixedSegmentReturnType<3>::Type
LinearType;
28 typedef typename Vector6ArgType::template FixedSegmentReturnType<3>::Type
AngularType;
29 typedef typename Vector6ArgType::template ConstFixedSegmentReturnType<3>::Type
ConstLinearType;
30 typedef typename Vector6ArgType::template ConstFixedSegmentReturnType<3>::Type
ConstAngularType;
41 template<
typename Vector6ArgType>
47 template<
typename Vector6ArgType,
typename MotionDerived>
55 template<
typename Vector6ArgType,
typename Scalar>
61 template<
typename Vector6ArgType,
typename Scalar>
68 template<
typename Vector6ArgType>
72 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
77 using Base::operator=;
82 using Base::__minus__;
84 using Base::__opposite__;
93 Vector6ArgType::ColsAtCompileTime == 1, YOU_TRIED_CALLING_A_VECTOR_METHOD_ON_A_MATRIX);
94 assert(v_like.size() == 6);
115 return ConstAngularType(
m_ref.derived(), ANGULAR);
119 return ConstLinearType(
m_ref.derived(), LINEAR);
123 return m_ref.template segment<3>(ANGULAR);
127 return m_ref.template segment<3>(LINEAR);
130 template<
typename V3>
133 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(V3, 3);
137 template<
typename V3>
140 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(V3, 3);
145 template<
typename S1,
int O1>
148 return MotionPlain(
m_ref +
v.toVector());
151 template<
typename Vector6Like>
154 return MotionPlain(
m_ref +
v.toVector());
157 template<
typename S1,
int O1>
160 return MotionPlain(
m_ref -
v.toVector());
163 template<
typename Vector6Like>
166 return MotionPlain(
m_ref -
v.toVector());
169 template<
typename S1,
int O1>
176 template<
typename Vector6Like>
183 template<
typename S1,
int O1>
190 template<
typename Vector6Like>
197 template<
typename OtherScalar>
208 inline PlainReturnType
plain()
const
210 return PlainReturnType(
m_ref);
218 template<
typename Vector6ArgType>
229 typedef Eigen::Matrix<Scalar, 3, 1, Options>
Vector3;
230 typedef Eigen::Matrix<Scalar, 4, 4, Options>
Matrix4;
231 typedef Eigen::Matrix<Scalar, 6, 6, Options>
Matrix6;
234 typedef typename Vector6ArgType::template ConstFixedSegmentReturnType<3>::Type
ConstLinearType;
235 typedef typename Vector6ArgType::template ConstFixedSegmentReturnType<3>::Type
ConstAngularType;
248 template<
typename Vector6ArgType>
252 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
257 using Base::operator=;
261 using Base::__minus__;
262 using Base::__mult__;
263 using Base::__opposite__;
264 using Base::__plus__;
270 Vector6ArgType::ColsAtCompileTime == 1, YOU_TRIED_CALLING_A_VECTOR_METHOD_ON_A_MATRIX);
271 assert(v_like.size() == 6);
288 return ConstAngularType(
m_ref.derived(), ANGULAR);
292 return ConstLinearType(
m_ref.derived(), LINEAR);
296 template<
typename S1,
int O1>
299 return MotionPlain(
m_ref +
v.toVector());
302 template<
typename Vector6Like>
305 return MotionPlain(
m_ref +
v.toVector());
308 template<
typename S1,
int O1>
311 return MotionPlain(
m_ref -
v.toVector());
314 template<
typename Vector6Like>
317 return MotionPlain(
m_ref -
v.toVector());
320 template<
typename OtherScalar>
331 inline PlainReturnType
plain()
const
333 return PlainReturnType(
m_ref);
343 #endif // ifndef __pinocchio_spatial_motion_ref_hpp__
MotionPlain __plus__(const MotionRef< Vector6ArgType > &v) const
MotionRef(const MotionRef &other)
Copy constructor from another MotionRef.
DataRefType ToVectorReturnType
MOTION_TYPEDEF_TPL(MotionRef)
traits< MotionRef >::DataRefType DataRefType
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef MotionDense< MotionRef > Base
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
traits< MotionRef< Vector6ArgType > >::MotionPlain ReturnType
ConstDataRefType ToVectorConstReturnType
pinocchio::traits< MotionRef< Vector6ArgType > >::MotionPlain ReturnType
MotionRef< const Vector6ArgType > MotionRefType
traits< MotionRef< Vector6ArgType > >::MotionPlain ReturnType
PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix6Like) operator*(const Eigen
ToVectorReturnType toVector_impl()
Vector6ArgType::template ConstFixedSegmentReturnType< 3 >::Type ConstAngularType
ConstAngularType angular_impl() const
Eigen::Matrix< Scalar, 4, 4, Options > Matrix4
Vector6ArgType::template FixedSegmentReturnType< 3 >::Type LinearType
MotionRef(typename PINOCCHIO_EIGEN_REF_TYPE(Vector6ArgType) v_like)
Default constructor from a 6 dimensional vector.
Return type of the ation of a Motion onto an object of type D.
ConstDataRefType DataRefType
Eigen::Matrix< Scalar, 6, 6, Options > Matrix6
MotionTpl< Scalar, Options > MotionPlain
PlainReturnType plain() const
Vector6ArgType::template FixedSegmentReturnType< 3 >::Type AngularType
Vector6ArgType::template ConstFixedSegmentReturnType< 3 >::Type ConstLinearType
PlainReturnType plain() const
DataRefType ToVectorReturnType
void angular_impl(const Eigen::MatrixBase< V3 > &w)
ConstLinearType LinearType
traits< MotionRef< Vector6ArgType > >::MotionPlain ReturnType
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef MotionDense< MotionRef > Base
MotionPlain __plus__(const MotionTpl< S1, O1 > &v) const
MotionPlain __minus__(const MotionTpl< S1, O1 > &v) const
Eigen::Matrix< Scalar, 4, 4, Options > Matrix4
MotionRef & __mequ__(const MotionRef< Vector6ArgType > &v)
ToVectorConstReturnType toVector_impl() const
ConstLinearType linear_impl() const
MotionPlain __plus__(const MotionTpl< S1, O1 > &v) const
MotionPlain __minus__(const MotionTpl< S1, O1 > &v) const
MotionPlain __minus__(const MotionRef< Vector6ArgType > &v) const
ConstAngularType angular_impl() const
MotionRef< Vector6ArgType > MotionRefType
const MotionRef & ref() const
MotionPlain PlainReturnType
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
MotionPlain PlainReturnType
MotionPlain __plus__(const MotionRef< Vector6ArgType > &v) const
MotionPlain __mult__(const OtherScalar &alpha) const
ToVectorConstReturnType toVector_impl() const
ConstLinearType linear_impl() const
MotionPlain __mult__(const OtherScalar &alpha) const
traits< MotionRef >::DataRefType DataRefType
MotionRef & __pequ__(const MotionTpl< S1, O1 > &v)
Eigen::Matrix< Scalar, 6, 6, Options > Matrix6
Vector6ArgType::template ConstFixedSegmentReturnType< 3 >::Type ConstLinearType
ConstDataRefType ToVectorConstReturnType
ConstAngularType AngularType
MotionTpl< Scalar, Options > MotionPlain
Common traits structure to fully define base classes for CRTP.
void linear_impl(const Eigen::MatrixBase< V3 > &v)
Matrix4 HomogeneousMatrixType
PINOCCHIO_EIGEN_PLAIN_TYPE(ConfigVectorType) integrate(const ModelTpl< Scalar
Integrate a configuration vector for the specified model for a tangent vector during one unit time.
#define PINOCCHIO_EIGEN_REF_TYPE(D)
Vector6ArgType::Scalar Scalar
Vector6ArgType::template ConstFixedSegmentReturnType< 3 >::Type ConstAngularType
MotionRef & __mequ__(const MotionTpl< S1, O1 > &v)
MotionRef(const MotionRef &other)
Copy constructor from another MotionRef.
Vector6ArgType::Scalar Scalar
MotionRef(typename PINOCCHIO_EIGEN_REF_CONST_TYPE(Vector6ArgType) v_like)
MotionRef & __pequ__(const MotionRef< Vector6ArgType > &v)
MotionPlain __minus__(const MotionRef< Vector6ArgType > &v) const
Main pinocchio namespace.
AngularType angular_impl()
Matrix4 HomogeneousMatrixType
pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:47