6 #ifndef __pinocchio_motion_zero_hpp__ 7 #define __pinocchio_motion_zero_hpp__ 12 template<
typename Scalar,
int Options>
18 template<
typename Scalar,
int Options,
typename MotionDerived>
24 template<
typename _Scalar,
int _Options>
33 typedef Eigen::Matrix<Scalar,3,1,Options>
Vector3;
34 typedef Eigen::Matrix<Scalar,6,1,Options>
Vector6;
35 typedef Eigen::Matrix<Scalar,3,3,Options>
Matrix3;
36 typedef Eigen::Matrix<Scalar,6,6,Options>
Matrix6;
49 template<typename Scalar,
int Options>
56 static PlainReturnType
plain() {
return MotionPlain::Zero(); }
84 template<
typename S2,
int O2,
typename D2>
90 template<
typename S2,
int O2>
96 template<
typename S2,
int O2,
typename D2>
102 template<
typename S2,
int O2>
110 template<
typename M1,
typename Scalar,
int Options>
115 template<
typename Scalar,
int Options,
typename M1>
121 template<
typename Scalar,
int Options>
130 template<
typename Scalar,
int Options>
136 template<
typename Scalar,
int Options,
typename MotionDerived>
145 #endif // ifndef __pinocchio_motion_zero_hpp__ JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
static void setTo(MotionBase< D2 > &other)
MotionZeroTpl se3ActionInverse_impl(const SE3Tpl< S2, O2 > &) const
const Vector3 ConstAngularType
static bool isEqual_impl(const MotionZeroTpl &)
traits< MotionZeroTpl >::MotionPlain MotionPlain
MotionZeroTpl se3Action_impl(const SE3Tpl< S2, O2 > &) const
const Vector3 ConstLinearType
Return type of the ation of a Motion onto an object of type D.
PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix6Like) operator*(const Eigen
BiasZeroTpl has been replaced by MotionZeroTpl. Please use this naming instead.
Eigen::Matrix< Scalar, 6, 6, Options > Matrix6
MotionZeroTpl< Scalar, Options > ReturnType
BiasZeroTpl< Scalar, Options > ReturnType
MotionZeroTpl motionAction(const MotionBase< M1 > &) const
#define PINOCCHIO_COMPILER_DIAGNOSTIC_POP
Eigen::Matrix< Scalar, 6, 1, Options > Vector6
MotionDerived::MotionPlain operator+(const MotionPlanarTpl< Scalar, Options > &m1, const MotionDense< MotionDerived > &m2)
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
MotionZeroTpl< Scalar, Options > ReturnType
Eigen::Matrix< Scalar, 3, 3, Options > Matrix3
traits< MotionZeroTpl >::PlainReturnType PlainReturnType
ConstLinearType linear() const
static PlainReturnType plain()
static void addTo(const MotionBase< D2 > &)
MotionZeroTpl< Scalar, Options > Base
void se3Action_impl(const SE3Tpl< S2, O2 > &, MotionDense< D2 > &v) const
BiasZeroTpl< Scalar, Options > ReturnType
#define PINOCCHIO_EIGEN_REF_TYPE(D)
Main pinocchio namespace.
static bool isEqual_impl(const MotionDense< D2 > &other)
BiasZeroTpl(const Base &)
Common traits structure to fully define base classes for CRTP.
void se3ActionInverse_impl(const SE3Tpl< S2, O2 > &, MotionDense< D2 > &v) const
#define PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH
macros for pragma push/pop/ignore deprecated warnings
#define PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
ConstAngularType angular() const