Go to the documentation of this file.
5 #ifndef __pinocchio_spatial_force_ref_hpp__
6 #define __pinocchio_spatial_force_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;
40 template<
typename Vector6ArgType>
46 template<
typename Vector6ArgType,
typename MotionDerived>
52 template<
typename Vector6ArgType>
56 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
61 using Base::operator=;
62 using Base::operator==;
63 using Base::operator!=;
70 Vector6ArgType::ColsAtCompileTime == 1, YOU_TRIED_CALLING_A_VECTOR_METHOD_ON_A_MATRIX);
71 assert(f_like.size() == 6);
92 return ConstAngularType(
m_ref.derived(), ANGULAR);
96 return ConstLinearType(
m_ref.derived(), LINEAR);
100 return m_ref.template segment<3>(ANGULAR);
104 return m_ref.template segment<3>(LINEAR);
107 template<
typename V3>
110 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(V3, 3);
114 template<
typename V3>
117 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(V3, 3);
131 template<
typename Vector6ArgType>
142 typedef Eigen::Matrix<Scalar, 3, 1, Options>
Vector3;
143 typedef Eigen::Matrix<Scalar, 6, 6, Options>
Matrix6;
145 typedef typename Vector6ArgType::template ConstFixedSegmentReturnType<3>::Type
ConstLinearType;
146 typedef typename Vector6ArgType::template ConstFixedSegmentReturnType<3>::Type
ConstAngularType;
159 template<
typename Vector6ArgType>
163 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
172 Vector6ArgType::ColsAtCompileTime == 1, YOU_TRIED_CALLING_A_VECTOR_METHOD_ON_A_MATRIX);
173 assert(f_like.size() == 6);
184 return ConstAngularType(
m_ref.derived(), ANGULAR);
188 return ConstLinearType(
m_ref.derived(), LINEAR);
203 #endif // ifndef __pinocchio_spatial_force_ref_hpp__
traits< ForceRef< Vector6ArgType > >::ForcePlain ReturnType
ConstLinearType linear_impl() const
ConstLinearType linear_impl() const
Matrix4 HomogeneousMatrixType
ConstAngularType angular_impl() const
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
Vector6ArgType::template ConstFixedSegmentReturnType< 3 >::Type ConstLinearType
Eigen::Matrix< Scalar, 6, 6, Options > Matrix6
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
FORCE_TYPEDEF_TPL(ForceRef)
Vector6ArgType::Scalar Scalar
PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix6Like) operator*(const Eigen
void linear_impl(const Eigen::MatrixBase< V3 > &v)
Vector6ArgType::template ConstFixedSegmentReturnType< 3 >::Type ConstLinearType
const ForceRef & ref() const
ConstAngularType AngularType
Vector6ArgType::template ConstFixedSegmentReturnType< 3 >::Type ConstAngularType
ForceRef(typename PINOCCHIO_EIGEN_REF_TYPE(Vector6ArgType) f_like)
Default constructor from a 6 dimensional vector.
Return type of the ation of a Motion onto an object of type D.
DataRefType ToVectorReturnType
Vector6ArgType::template FixedSegmentReturnType< 3 >::Type LinearType
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef ForceDense< ForceRef > Base
Eigen::Matrix< Scalar, 4, 4, Options > Matrix4
DataRefType ToVectorReturnType
ForceRef(typename PINOCCHIO_EIGEN_REF_CONST_TYPE(Vector6ArgType) f_like)
ConstAngularType angular_impl() const
AngularType angular_impl()
Eigen::Matrix< Scalar, 6, 6, Options > Matrix6
ForceTpl< Scalar, Options > ForcePlain
ToVectorReturnType toVector_impl()
ConstDataRefType ToVectorConstReturnType
traits< ForceRef >::DataRefType DataRefType
Vector6ArgType::template ConstFixedSegmentReturnType< 3 >::Type ConstAngularType
ConstDataRefType ToVectorConstReturnType
ForceRef(const ForceRef &other)
Copy constructor from another ForceRef.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
traits< ForceRef< Vector6ArgType > >::ForcePlain ReturnType
ToVectorConstReturnType toVector_impl() const
ToVectorConstReturnType toVector_impl() const
Common traits structure to fully define base classes for CRTP.
ForceTpl< Scalar, Options > ForcePlain
Vector6ArgType::template FixedSegmentReturnType< 3 >::Type AngularType
ConstLinearType LinearType
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.
void angular_impl(const Eigen::MatrixBase< V3 > &w)
ForcePlain PlainReturnType
#define PINOCCHIO_EIGEN_REF_TYPE(D)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef ForceDense< ForceRef > Base
ForceRef< Vector6ArgType > ForceRefType
ConstDataRefType DataRefType
Vector6ArgType::Scalar Scalar
traits< ForceRef >::DataRefType DataRefType
Main pinocchio namespace.
ForceRef< const Vector6ArgType > ForceRefType
pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:44