Go to the documentation of this file.
    6 #ifndef __pinocchio_spatial_motion_tpl_hpp__ 
    7 #define __pinocchio_spatial_motion_tpl_hpp__ 
   11   template<
typename _Scalar, 
int _Options>
 
   15     typedef Eigen::Matrix<Scalar, 3, 1, _Options> 
Vector3;
 
   16     typedef Eigen::Matrix<Scalar, 6, 1, _Options> 
Vector6;
 
   17     typedef Eigen::Matrix<Scalar, 4, 4, _Options> 
Matrix4;
 
   18     typedef Eigen::Matrix<Scalar, 6, 6, _Options> 
Matrix6;
 
   23     typedef typename Vector6::template FixedSegmentReturnType<3>::Type 
LinearType;
 
   24     typedef typename Vector6::template FixedSegmentReturnType<3>::Type 
AngularType;
 
   25     typedef typename Vector6::template ConstFixedSegmentReturnType<3>::Type 
ConstLinearType;
 
   26     typedef typename Vector6::template ConstFixedSegmentReturnType<3>::Type 
ConstAngularType;
 
   39   template<
typename _Scalar, 
int _Options>
 
   43     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
   51     using Base::operator=;
 
   56     using Base::__minus__;
 
   58     using Base::__opposite__;
 
   67     template<
typename V1, 
typename V2>
 
   68     MotionTpl(
const Eigen::MatrixBase<V1> & 
v, 
const Eigen::MatrixBase<V2> & 
w)
 
   70       EIGEN_STATIC_ASSERT_VECTOR_ONLY(
V1);
 
   71       EIGEN_STATIC_ASSERT_VECTOR_ONLY(V2);
 
   80       EIGEN_STATIC_ASSERT_VECTOR_ONLY(V6);
 
   88     template<
typename S2, 
int O2>
 
   91       *
this = other.template cast<Scalar>();
 
  103       typename std::enable_if<!std::is_convertible<MotionDense<M2>, 
MotionTpl>::value, 
bool>
::type =
 
  107       linear() = 
clone.linear();
 
  108       angular() = 
clone.angular();
 
  117       typename std::enable_if<!std::is_convertible<MotionBase<M2>, 
MotionTpl>::value, 
bool>
::type =
 
  145     inline PlainReturnType 
plain()
 const 
  162       return m_data.template segment<3>(ANGULAR);
 
  166       return m_data.template segment<3>(LINEAR);
 
  170       return m_data.template segment<3>(ANGULAR);
 
  174       return m_data.template segment<3>(LINEAR);
 
  177     template<
typename V3>
 
  180       EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(V3, 3);
 
  183     template<
typename V3>
 
  186       EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(V3, 3);
 
  194       return MotionPlain(
m_data + 
v.toVector());
 
  197     template<
typename Vector6ArgType>
 
  200       return MotionPlain(
m_data + 
v.toVector());
 
  206       return MotionPlain(
m_data - 
v.toVector());
 
  209     template<
typename Vector6ArgType>
 
  212       return MotionPlain(
m_data - 
v.toVector());
 
  222     template<
typename Vector6ArgType>
 
  236     template<
typename Vector6ArgType>
 
  243     template<
typename OtherScalar>
 
  255     template<
typename NewScalar>
 
  259       ReturnType 
res(linear().
template cast<NewScalar>(), angular().
template cast<NewScalar>());
 
  270 #endif // ifndef __pinocchio_spatial_motion_tpl_hpp__ 
  
ConstLinearType linear_impl() const
Eigen::Matrix< Scalar, 4, 4, _Options > Matrix4
Vector6::template FixedSegmentReturnType< 3 >::Type LinearType
MotionTpl(const MotionTpl< S2, O2 > &other)
MotionTpl< NewScalar, Options > cast() const
MotionTpl & __pequ__(const MotionTpl< Scalar, O2 > &v)
MotionTpl & operator=(const MotionTpl &clone)
Copy assignment operator.
MotionPlain __mult__(const OtherScalar &alpha) const
PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix6Like) operator*(const Eigen
Vector6::template ConstFixedSegmentReturnType< 3 >::Type ConstLinearType
Matrix4 HomogeneousMatrixType
MotionRef< Vector6 > MotionRefType
MotionTpl & __pequ__(const MotionRef< Vector6ArgType > &v)
MotionTpl< Scalar, _Options > MotionPlain
ConstAngularType angular_impl() const
Vector6::template ConstFixedSegmentReturnType< 3 >::Type ConstAngularType
MotionPlain __minus__(const MotionTpl< Scalar, O2 > &v) const
Eigen::Matrix< Scalar, 6, 1, _Options > Vector6
PlainReturnType plain() const
void linear_impl(const Eigen::MatrixBase< V3 > &v)
MotionTpl(const Eigen::MatrixBase< V6 > &v)
MotionRef< Vector6 > ref()
Eigen::Matrix< Scalar, 6, 6, _Options > Matrix6
MotionTpl(const MotionTpl &other)
Eigen::Matrix< Scalar, 3, 1, _Options > Vector3
MotionTpl(const MotionDense< M2 > &clone)
Vector6::template FixedSegmentReturnType< 3 >::Type AngularType
ToVectorReturnType toVector_impl()
AngularType angular_impl()
static MotionTpl Random()
virtual CollisionGeometry * clone() const=0
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
MotionTpl(const MotionTpl< Scalar, O2 > &clone)
MotionPlain __plus__(const MotionRef< Vector6ArgType > &v) const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef MotionDense< MotionTpl > Base
MotionTpl & __mequ__(const MotionTpl< Scalar, O2 > &v)
void angular_impl(const Eigen::MatrixBase< V3 > &w)
Common traits structure to fully define base classes for CRTP.
#define PINOCCHIO_EIGEN_REF_TYPE(D)
MotionTpl(const Eigen::MatrixBase< V1 > &v, const Eigen::MatrixBase< V2 > &w)
MotionTpl & __mequ__(const MotionRef< Vector6ArgType > &v)
const typedef MotionPlain & PlainReturnType
MotionTpl(const MotionBase< M2 > &clone)
MOTION_TYPEDEF_TPL(MotionTpl)
ToVectorConstReturnType toVector_impl() const
MotionPlain __minus__(const MotionRef< Vector6ArgType > &v) const
Main pinocchio namespace.
MotionPlain __plus__(const MotionTpl< Scalar, O2 > &v) const
pinocchio
Author(s): 
autogenerated on Wed May 28 2025 02:41:21