5 #ifndef __pinocchio_multibody_liegroup_liegroup_operation_base_hpp__ 6 #define __pinocchio_multibody_liegroup_liegroup_operation_base_hpp__ 8 #include "pinocchio/multibody/liegroup/fwd.hpp" 14 #ifdef PINOCCHIO_WITH_CXX11_SUPPORT 15 constexpr
int SELF = 0;
20 #define PINOCCHIO_LIE_GROUP_PUBLIC_INTERFACE_GENERIC(Derived,TYPENAME) \ 21 typedef LieGroupBase<Derived> Base; \ 22 typedef TYPENAME Base::Index Index; \ 23 typedef TYPENAME traits<Derived>::Scalar Scalar; \ 25 Options = traits<Derived>::Options, \ 29 typedef TYPENAME Base::ConfigVector_t ConfigVector_t; \ 30 typedef TYPENAME Base::TangentVector_t TangentVector_t; \ 31 typedef TYPENAME Base::JacobianMatrix_t JacobianMatrix_t 33 #define PINOCCHIO_LIE_GROUP_PUBLIC_INTERFACE(Derived) \ 34 PINOCCHIO_LIE_GROUP_PUBLIC_INTERFACE_GENERIC(Derived,PINOCCHIO_MACRO_EMPTY_ARG) 36 #define PINOCCHIO_LIE_GROUP_TPL_PUBLIC_INTERFACE(Derived) \ 37 PINOCCHIO_LIE_GROUP_PUBLIC_INTERFACE_GENERIC(Derived,typename) 39 template<
typename Derived>
67 template <
class ConfigIn_t,
class Tangent_t,
class ConfigOut_t>
68 void integrate(
const Eigen::MatrixBase<ConfigIn_t> &
q,
69 const Eigen::MatrixBase<Tangent_t> &
v,
70 const Eigen::MatrixBase<ConfigOut_t> & qout)
const;
84 template<
class Config_t,
class Jacobian_t>
86 const Eigen::MatrixBase<Jacobian_t> &
J)
const;
101 template <ArgumentPosition arg,
class Config_t,
class Tangent_t,
class JacobianOut_t>
103 const Eigen::MatrixBase<Tangent_t> &
v,
104 const Eigen::MatrixBase<JacobianOut_t> &
J,
124 template<
class Config_t,
class Tangent_t,
class JacobianOut_t>
125 void dIntegrate(
const Eigen::MatrixBase<Config_t > &
q,
126 const Eigen::MatrixBase<Tangent_t> &
v,
127 const Eigen::MatrixBase<JacobianOut_t> &
J,
143 template <
class Config_t,
class Tangent_t,
class JacobianOut_t>
145 const Eigen::MatrixBase<Tangent_t> & v,
146 const Eigen::MatrixBase<JacobianOut_t> & J,
149 template <
class Config_t,
class Tangent_t,
class JacobianIn_t,
class JacobianOut_t>
151 const Eigen::MatrixBase<Tangent_t> & v,
152 const Eigen::MatrixBase<JacobianIn_t> & Jin,
154 const Eigen::MatrixBase<JacobianOut_t> & Jout,
157 template <
class Config_t,
class Tangent_t,
class JacobianIn_t,
class JacobianOut_t>
159 const Eigen::MatrixBase<Tangent_t> & v,
161 const Eigen::MatrixBase<JacobianIn_t> & Jin,
162 const Eigen::MatrixBase<JacobianOut_t> & Jout,
177 template <
class Config_t,
class Tangent_t,
class JacobianOut_t>
179 const Eigen::MatrixBase<Tangent_t> & v,
180 const Eigen::MatrixBase<JacobianOut_t> & J,
183 template <
class Config_t,
class Tangent_t,
class JacobianIn_t,
class JacobianOut_t>
185 const Eigen::MatrixBase<Tangent_t> & v,
187 const Eigen::MatrixBase<JacobianIn_t> & Jin,
188 const Eigen::MatrixBase<JacobianOut_t> & Jout,
191 template <
class Config_t,
class Tangent_t,
class JacobianIn_t,
class JacobianOut_t>
193 const Eigen::MatrixBase<Tangent_t> & v,
194 const Eigen::MatrixBase<JacobianIn_t> & Jin,
196 const Eigen::MatrixBase<JacobianOut_t> & Jout,
219 template<
class Config_t,
class Tangent_t,
class JacobianIn_t,
class JacobianOut_t>
221 const Eigen::MatrixBase<Tangent_t> & v,
222 const Eigen::MatrixBase<JacobianIn_t> & Jin,
223 const Eigen::MatrixBase<JacobianOut_t> & Jout,
244 template <
class Config_t,
class Tangent_t,
class JacobianIn_t,
class JacobianOut_t>
246 const Eigen::MatrixBase<Tangent_t> & v,
247 const Eigen::MatrixBase<JacobianIn_t> & Jin,
248 const Eigen::MatrixBase<JacobianOut_t> & Jout)
const;
267 template <
class Config_t,
class Tangent_t,
class JacobianIn_t,
class JacobianOut_t>
269 const Eigen::MatrixBase<Tangent_t> & v,
270 const Eigen::MatrixBase<JacobianIn_t> & Jin,
271 const Eigen::MatrixBase<JacobianOut_t> & Jout)
const;
291 template<
class Config_t,
class Tangent_t,
class Jacobian_t>
293 const Eigen::MatrixBase<Tangent_t> & v,
294 const Eigen::MatrixBase<Jacobian_t> & J,
314 template <
class Config_t,
class Tangent_t,
class Jacobian_t>
316 const Eigen::MatrixBase<Tangent_t> & v,
317 const Eigen::MatrixBase<Jacobian_t> & J)
const;
335 template <
class Config_t,
class Tangent_t,
class Jacobian_t>
337 const Eigen::MatrixBase<Tangent_t> & v,
338 const Eigen::MatrixBase<Jacobian_t> & J)
const;
349 template <
class ConfigL_t,
class ConfigR_t,
class ConfigOut_t>
351 const Eigen::MatrixBase<ConfigR_t> &
q1,
353 const Eigen::MatrixBase<ConfigOut_t> & qout)
const;
364 template <
class Config_t>
365 void normalize(
const Eigen::MatrixBase<Config_t> & qout)
const;
375 template <
class Config_t>
376 bool isNormalized(
const Eigen::MatrixBase<Config_t> & qin,
377 const Scalar& prec = Eigen::NumTraits<Scalar>::dummy_precision())
const;
387 template <
class Config_t>
388 void random(
const Eigen::MatrixBase<Config_t> & qout)
const;
399 template <
class ConfigL_t,
class ConfigR_t,
class ConfigOut_t>
401 const Eigen::MatrixBase<ConfigR_t> & upper_pos_limit,
402 const Eigen::MatrixBase<ConfigOut_t> & qout)
const;
417 template <
class ConfigL_t,
class ConfigR_t,
class Tangent_t>
418 void difference(
const Eigen::MatrixBase<ConfigL_t> & q0,
419 const Eigen::MatrixBase<ConfigR_t> & q1,
420 const Eigen::MatrixBase<Tangent_t> & v)
const;
442 template <ArgumentPosition arg,
class ConfigL_t,
class ConfigR_t,
class JacobianOut_t>
443 void dDifference(
const Eigen::MatrixBase<ConfigL_t> & q0,
444 const Eigen::MatrixBase<ConfigR_t> & q1,
445 const Eigen::MatrixBase<JacobianOut_t> & J)
const;
458 template<
class ConfigL_t,
class ConfigR_t,
class JacobianOut_t>
459 void dDifference(
const Eigen::MatrixBase<ConfigL_t> & q0,
460 const Eigen::MatrixBase<ConfigR_t> & q1,
461 const Eigen::MatrixBase<JacobianOut_t> & J,
464 template<ArgumentPosition arg,
class ConfigL_t,
class ConfigR_t,
class JacobianIn_t,
class JacobianOut_t>
465 void dDifference(
const Eigen::MatrixBase<ConfigL_t> & q0,
466 const Eigen::MatrixBase<ConfigR_t> & q1,
467 const Eigen::MatrixBase<JacobianIn_t> & Jin,
469 const Eigen::MatrixBase<JacobianOut_t> & Jout,
472 template<ArgumentPosition arg,
class ConfigL_t,
class ConfigR_t,
class JacobianIn_t,
class JacobianOut_t>
473 void dDifference(
const Eigen::MatrixBase<ConfigL_t> & q0,
474 const Eigen::MatrixBase<ConfigR_t> & q1,
476 const Eigen::MatrixBase<JacobianIn_t> & Jin,
477 const Eigen::MatrixBase<JacobianOut_t> & Jout,
488 template <
class ConfigL_t,
class ConfigR_t>
490 const Eigen::MatrixBase<ConfigR_t> & q1)
const;
500 template <
class ConfigL_t,
class ConfigR_t>
501 Scalar
distance(
const Eigen::MatrixBase<ConfigL_t> & q0,
502 const Eigen::MatrixBase<ConfigR_t> & q1)
const;
512 template <
class ConfigL_t,
class ConfigR_t>
514 const Eigen::MatrixBase<ConfigR_t> & q1,
515 const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
const;
531 template <
class Config_t,
class Tangent_t>
532 ConfigVector_t
integrate(
const Eigen::MatrixBase<Config_t> & q,
533 const Eigen::MatrixBase<Tangent_t> & v)
const ;
535 template <
class ConfigL_t,
class ConfigR_t>
536 ConfigVector_t
interpolate(
const Eigen::MatrixBase<ConfigL_t> & q0,
537 const Eigen::MatrixBase<ConfigR_t> & q1,
538 const Scalar& u)
const;
540 ConfigVector_t
random()
const;
542 template <
class ConfigL_t,
class ConfigR_t>
544 (
const Eigen::MatrixBase<ConfigL_t> & lower_pos_limit,
545 const Eigen::MatrixBase<ConfigR_t> & upper_pos_limit)
const;
547 template <
class ConfigL_t,
class ConfigR_t>
548 TangentVector_t
difference(
const Eigen::MatrixBase<ConfigL_t> & q0,
549 const Eigen::MatrixBase<ConfigR_t> & q1)
const;
556 template <
class Config_t,
class Tangent_t,
class JacobianIn_t,
class JacobianOut_t>
559 const JacobianIn_t & Jin,
560 JacobianOut_t & Jout,
561 bool dIntegrateOnTheLeft,
565 template <ArgumentPosition arg,
class ConfigL_t,
class ConfigR_t,
class JacobianIn_t,
class JacobianOut_t>
567 const ConfigR_t & q1,
568 const JacobianIn_t & Jin,
569 JacobianOut_t & Jout,
570 bool dDifferenceOnTheLeft,
573 template <
class ConfigL_t,
class ConfigR_t,
class ConfigOut_t>
575 const Eigen::MatrixBase<ConfigR_t> & q1,
577 const Eigen::MatrixBase<ConfigOut_t> & qout)
const;
579 template <
class Config_t>
580 void normalize_impl(
const Eigen::MatrixBase<Config_t> & qout)
const;
582 template <
class Config_t>
584 const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
const;
586 template <
class ConfigL_t,
class ConfigR_t>
588 const Eigen::MatrixBase<ConfigR_t> & q1)
const;
590 template <
class ConfigL_t,
class ConfigR_t>
592 const Eigen::MatrixBase<ConfigR_t> & q1,
593 const Scalar & prec)
const;
611 ConfigVector_t
neutral ()
const;
614 std::string
name ()
const;
618 return static_cast <Derived&> (*this);
623 return static_cast <
const Derived&> (*this);
646 #include "pinocchio/multibody/liegroup/liegroup-base.hxx" 648 #endif // ifndef __pinocchio_multibody_liegroup_liegroup_operation_base_hpp__ JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
void difference(const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Eigen::MatrixBase< Tangent_t > &v) const
Computes the tangent vector that must be integrated during one unit time to go from q0 to q1...
Eigen::Matrix< Scalar, NQ, 1, Options > ConfigVector_t
bool operator==(const LieGroupBase &other) const
ArgumentPosition
Argument position. Used as template parameter to refer to an argument.
Eigen::Matrix< Scalar, NV, NV, Options > JacobianMatrix_t
bool isDifferent_impl(const LieGroupBase &other) const
bool operator!=(const LieGroupBase &other) const
Scalar distance(const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1) const
Distance between two configurations of the joint.
void dIntegrate(const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianOut_t > &J, AssignmentOperatorType op=SETTO) const
Computes the Jacobian of a small variation of the configuration vector or the tangent vector into tan...
Eigen::Matrix< Scalar, NV, 1, Options > TangentVector_t
bool isSameConfiguration(const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
Check if two configurations are equivalent within the given precision.
Scalar squaredDistance_impl(const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1) const
void dIntegrate_dv(const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianOut_t > &J, const AssignmentOperatorType op=SETTO) const
Computes the Jacobian of a small variation of the tangent vector into tangent space at identity...
ConfigVector_t random() const
void integrate(const Eigen::MatrixBase< ConfigIn_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< ConfigOut_t > &qout) const
Integrate a joint's configuration with a tangent vector during one unit time duration.
traits< LieGroupDerived >::Scalar Scalar
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
void randomConfiguration(const Eigen::MatrixBase< ConfigL_t > &lower_pos_limit, const Eigen::MatrixBase< ConfigR_t > &upper_pos_limit, const Eigen::MatrixBase< ConfigOut_t > &qout) const
Generate a configuration vector uniformly sampled among provided limits.
Scalar squaredDistance(const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1) const
Squared distance between two joint configurations.
bool isNormalized_impl(const Eigen::MatrixBase< Config_t > &qin, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
void dIntegrate_dq(const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianOut_t > &J, const AssignmentOperatorType op=SETTO) const
Computes the Jacobian of a small variation of the configuration vector into tangent space at identity...
#define PINOCCHIO_STATIC_ASSERT(condition, msg)
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorIn1 > const Eigen::MatrixBase< ConfigVectorIn2 > const Scalar & u
void dDifference_product_impl(const ConfigL_t &q0, const ConfigR_t &q1, const JacobianIn_t &Jin, JacobianOut_t &Jout, bool dDifferenceOnTheLeft, const AssignmentOperatorType op) const
bool isSameConfiguration_impl(const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Scalar &prec) const
void dIntegrateTransport_dq(const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianIn_t > &Jin, const Eigen::MatrixBase< JacobianOut_t > &Jout) const
Transport a matrix from the terminal to the originate tangent space of the integrate operation...
const Derived & derived() const
void normalize_impl(const Eigen::MatrixBase< Config_t > &qout) const
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorIn1 > const Eigen::MatrixBase< ConfigVectorIn2 > & q1
void interpolate_impl(const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Scalar &u, const Eigen::MatrixBase< ConfigOut_t > &qout) const
void dDifference(const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Eigen::MatrixBase< JacobianOut_t > &J) const
Computes the Jacobian of the difference operation with respect to q0 or q1.
LieGroupBase & operator=(const LieGroupBase &)
void normalize(const Eigen::MatrixBase< Config_t > &qout) const
Normalize the joint configuration given as input. For instance, the quaternion must be unitary...
Main pinocchio namespace.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorIn1 > & q0
std::string name() const
Get name of instance.
void integrateCoeffWiseJacobian(const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Jacobian_t > &J) const
Computes the Jacobian of the integrate operator around zero.
Common traits structure to fully define base classes for CRTP.
void dIntegrate_product_impl(const Config_t &q, const Tangent_t &v, const JacobianIn_t &Jin, JacobianOut_t &Jout, bool dIntegrateOnTheLeft, const ArgumentPosition arg, const AssignmentOperatorType op) const
LieGroupBase(const LieGroupBase &)
void interpolate(const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Scalar &u, const Eigen::MatrixBase< ConfigOut_t > &qout) const
Interpolation between two joint's configurations.
void dIntegrateTransport_dv(const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianIn_t > &Jin, const Eigen::MatrixBase< JacobianOut_t > &Jout) const
Transport a matrix from the terminal to the originate tangent space of the integrate operation...
bool isNormalized(const Eigen::MatrixBase< Config_t > &qin, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
Check whether the input joint configuration is normalized. For instance, the quaternion must be unita...
bool isEqual_impl(const LieGroupBase &) const
Default equality check. By default, two LieGroupBase of same type are considered equal.
Index nv() const
Get dimension of Lie Group tangent space.
ConfigVector_t neutral() const
Get neutral element as a vector.
void dIntegrateTransport(const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianIn_t > &Jin, const Eigen::MatrixBase< JacobianOut_t > &Jout, const ArgumentPosition arg) const
Transport a matrix from the terminal to the originate tangent space of the integrate operation...