5 #ifndef __pinocchio_motion_ref_hpp__ 6 #define __pinocchio_motion_ref_hpp__ 11 template<
typename Vector6ArgType>
21 typedef Eigen::Matrix<Scalar,3,1,Options>
Vector3;
22 typedef Eigen::Matrix<Scalar,6,6,Options>
Matrix6;
24 typedef typename Vector6ArgType::template FixedSegmentReturnType<3>::Type
LinearType;
25 typedef typename Vector6ArgType::template FixedSegmentReturnType<3>::Type
AngularType;
26 typedef typename Vector6ArgType::template ConstFixedSegmentReturnType<3>::Type
ConstLinearType;
27 typedef typename Vector6ArgType::template ConstFixedSegmentReturnType<3>::Type
ConstAngularType;
38 template<typename Vector6ArgType>
44 template<
typename Vector6ArgType,
typename MotionDerived>
52 template<
typename Vector6ArgType,
typename Scalar>
58 template<
typename Vector6ArgType,
typename Scalar>
65 template<
typename Vector6ArgType>
69 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
74 using Base::operator=;
79 using Base::__opposite__;
80 using Base::__minus__;
89 EIGEN_STATIC_ASSERT(Vector6ArgType::ColsAtCompileTime == 1,
90 YOU_TRIED_CALLING_A_VECTOR_METHOD_ON_A_MATRIX);
91 assert(v_like.size() == 6);
103 ConstAngularType
angular_impl()
const {
return ConstAngularType(m_ref.derived(),ANGULAR); }
104 ConstLinearType
linear_impl()
const {
return ConstLinearType(m_ref.derived(),LINEAR); }
105 AngularType
angular_impl() {
return m_ref.template segment<3> (ANGULAR); }
106 LinearType
linear_impl() {
return m_ref.template segment<3> (LINEAR); }
108 template<
typename V3>
111 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(V3,3);
115 template<
typename V3>
118 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(V3,3);
123 template<
typename S1,
int O1>
125 {
return MotionPlain(m_ref+v.
toVector()); }
127 template<
typename Vector6Like>
129 {
return MotionPlain(m_ref+v.
toVector()); }
131 template<
typename S1,
int O1>
133 {
return MotionPlain(m_ref-v.
toVector()); }
135 template<
typename Vector6Like>
137 {
return MotionPlain(m_ref-v.
toVector()); }
139 template<
typename S1,
int O1>
141 { m_ref += v.
toVector();
return *
this; }
143 template<
typename Vector6Like>
145 { m_ref += v.
toVector();
return *
this; }
147 template<
typename S1,
int O1>
149 { m_ref -= v.
toVector();
return *
this; }
151 template<
typename Vector6Like>
153 { m_ref -= v.
toVector();
return *
this; }
155 template<
typename OtherScalar>
156 MotionPlain
__mult__(
const OtherScalar & alpha)
const 157 {
return MotionPlain(alpha*m_ref); }
161 inline PlainReturnType
plain()
const {
return PlainReturnType(m_ref); }
168 template<
typename Vector6ArgType>
178 typedef Eigen::Matrix<Scalar,3,1,Options>
Vector3;
179 typedef Eigen::Matrix<Scalar,6,6,Options>
Matrix6;
181 typedef typename Vector6ArgType::template ConstFixedSegmentReturnType<3>::Type
ConstLinearType;
182 typedef typename Vector6ArgType::template ConstFixedSegmentReturnType<3>::Type
ConstAngularType;
189 typedef ConstDataRefType DataRefType;
195 template<typename Vector6ArgType>
200 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
205 using Base::operator=;
209 using Base::__plus__;
210 using Base::__opposite__;
211 using Base::__minus__;
212 using Base::__mult__;
217 EIGEN_STATIC_ASSERT(Vector6ArgType::ColsAtCompileTime == 1,
218 YOU_TRIED_CALLING_A_VECTOR_METHOD_ON_A_MATRIX);
219 assert(v_like.size() == 6);
225 ConstAngularType
angular_impl()
const {
return ConstAngularType(m_ref.derived(),ANGULAR); }
226 ConstLinearType
linear_impl()
const {
return ConstLinearType(m_ref.derived(),LINEAR); }
229 template<
typename S1,
int O1>
231 {
return MotionPlain(m_ref+v.
toVector()); }
233 template<
typename Vector6Like>
235 {
return MotionPlain(m_ref+v.
toVector()); }
237 template<
typename S1,
int O1>
239 {
return MotionPlain(m_ref-v.
toVector()); }
241 template<
typename Vector6Like>
243 {
return MotionPlain(m_ref-v.
toVector()); }
245 template<
typename OtherScalar>
246 MotionPlain
__mult__(
const OtherScalar & alpha)
const 247 {
return MotionPlain(alpha*m_ref); }
251 inline PlainReturnType
plain()
const {
return PlainReturnType(m_ref); }
260 #endif // ifndef __pinocchio_motion_ref_hpp__ Vector6ArgType::template ConstFixedSegmentReturnType< 3 >::Type ConstLinearType
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
ConstAngularType AngularType
ConstDataRefType ToVectorConstReturnType
Vector6ArgType::template ConstFixedSegmentReturnType< 3 >::Type ConstLinearType
Vector6ArgType::template ConstFixedSegmentReturnType< 3 >::Type ConstAngularType
traits< MotionRef< Vector6ArgType > >::MotionPlain ReturnType
traits< MotionRef< Vector6ArgType > >::MotionPlain ReturnType
void linear_impl(const Eigen::MatrixBase< V3 > &v)
MotionTpl< Scalar, Options > MotionPlain
Return type of the ation of a Motion onto an object of type D.
#define MOTION_TYPEDEF_TPL(Derived)
ToVectorConstReturnType toVector_impl() const
PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix6Like) operator*(const Eigen
ConstAngularType angular_impl() const
Eigen::Matrix< Scalar, 6, 6, Options > Matrix6
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef MotionDense< MotionRef > Base
MotionPlain __mult__(const OtherScalar &alpha) const
PlainReturnType plain() const
ConstDataRefType ToVectorConstReturnType
MotionRef & __mequ__(const MotionRef< Vector6ArgType > &v)
MotionRef(typename PINOCCHIO_EIGEN_REF_CONST_TYPE(Vector6ArgType) v_like)
MotionRef & __pequ__(const MotionRef< Vector6ArgType > &v)
MotionPlain PlainReturnType
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef MotionDense< MotionRef > Base
MotionRef(const MotionRef &other)
Copy constructor from another MotionRef.
MotionRef & __mequ__(const MotionTpl< S1, O1 > &v)
ToVectorConstReturnType toVector_impl() const
ConstLinearType LinearType
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
MotionPlain __plus__(const MotionRef< Vector6ArgType > &v) const
MotionPlain __mult__(const OtherScalar &alpha) const
MotionPlain __plus__(const MotionRef< Vector6ArgType > &v) const
traits< MotionRef< Vector6ArgType > >::MotionPlain ReturnType
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
ConstLinearType linear_impl() const
pinocchio::traits< MotionRef< Vector6ArgType > >::MotionPlain ReturnType
MotionRef & __pequ__(const MotionTpl< S1, O1 > &v)
Vector6ArgType::template ConstFixedSegmentReturnType< 3 >::Type ConstAngularType
const MotionRef & ref() const
MotionPlain __plus__(const MotionTpl< S1, O1 > &v) const
DataRefType ToVectorReturnType
MotionPlain __minus__(const MotionTpl< S1, O1 > &v) const
MotionTpl< Scalar, Options > MotionPlain
DataRefType ToVectorReturnType
MotionPlain PlainReturnType
#define PINOCCHIO_EIGEN_REF_TYPE(D)
Main pinocchio namespace.
MotionPlain __plus__(const MotionTpl< S1, O1 > &v) const
void angular_impl(const Eigen::MatrixBase< V3 > &w)
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...
AngularType angular_impl()
ToVectorConstReturnType toVector() const
Eigen::Matrix< Scalar, 6, 6, Options > Matrix6
Common traits structure to fully define base classes for CRTP.
traits< MotionRef >::DataRefType DataRefType
Vector6ArgType::Scalar Scalar
traits< MotionRef >::DataRefType DataRefType
Vector6ArgType::template FixedSegmentReturnType< 3 >::Type LinearType
Vector6ArgType::Scalar Scalar
PlainReturnType plain() const
ToVectorReturnType toVector_impl()
MotionPlain __minus__(const MotionRef< Vector6ArgType > &v) const
MotionPlain __minus__(const MotionTpl< S1, O1 > &v) const
ConstLinearType linear_impl() const
MotionRef(typename PINOCCHIO_EIGEN_REF_TYPE(Vector6ArgType) v_like)
Default constructor from a 6 dimensional vector.
ConstAngularType angular_impl() const
Vector6ArgType::template FixedSegmentReturnType< 3 >::Type AngularType
MotionPlain __minus__(const MotionRef< Vector6ArgType > &v) const