pinocchio  3.7.0
A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
 
Loading...
Searching...
No Matches
CartesianProductOperation< LieGroup1, LieGroup2 > Struct Template Reference
Inheritance diagram for CartesianProductOperation< LieGroup1, LieGroup2 >:
Collaboration diagram for CartesianProductOperation< LieGroup1, LieGroup2 >:

Public Member Functions

template<ArgumentPosition arg, class ConfigL_t , class ConfigR_t , class JacobianOut_t >
void dDifference_impl (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Eigen::MatrixBase< JacobianOut_t > &J) const
 
template<class ConfigL_t , class ConfigR_t , class Tangent_t >
void difference_impl (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Eigen::MatrixBase< Tangent_t > &d) const
 
template<class Config_t , class Tangent_t , class JacobianOut_t >
void dIntegrate_dq_impl (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianOut_t > &J, const AssignmentOperatorType op=SETTO) const
 
template<class Config_t , class Tangent_t , class JacobianOut_t >
void dIntegrate_dv_impl (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianOut_t > &J, const AssignmentOperatorType op=SETTO) const
 
template<class Config_t , class Tangent_t , class Jacobian_t >
void dIntegrateTransport_dq_impl (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< Jacobian_t > &Jin) const
 
template<class Config_t , class Tangent_t , class JacobianIn_t , class JacobianOut_t >
void dIntegrateTransport_dq_impl (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianIn_t > &J_in, const Eigen::MatrixBase< JacobianOut_t > &J_out) const
 
template<class Config_t , class Tangent_t , class Jacobian_t >
void dIntegrateTransport_dv_impl (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< Jacobian_t > &Jin) const
 
template<class Config_t , class Tangent_t , class JacobianIn_t , class JacobianOut_t >
void dIntegrateTransport_dv_impl (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianIn_t > &J_in, const Eigen::MatrixBase< JacobianOut_t > &J_out) const
 
template<class ConfigIn_t , class Velocity_t , class ConfigOut_t >
void integrate_impl (const Eigen::MatrixBase< ConfigIn_t > &q, const Eigen::MatrixBase< Velocity_t > &v, const Eigen::MatrixBase< ConfigOut_t > &qout) const
 
template<class Config_t , class Jacobian_t >
void integrateCoeffWiseJacobian_impl (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Jacobian_t > &J) const
 
bool isEqual_impl (const CartesianProductOperation &other) const
 
template<class Config_t >
bool isNormalized_impl (const Eigen::MatrixBase< Config_t > &qin, const Scalar &prec) const
 
template<class ConfigL_t , class ConfigR_t >
bool isSameConfiguration_impl (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Scalar &prec) const
 
std::string name () const
 
ConfigVector_t neutral () const
 
template<class Config_t >
void normalize_impl (const Eigen::MatrixBase< Config_t > &qout) const
 
Index nq () const
 
Index nv () const
 
 PINOCCHIO_LIE_GROUP_TPL_PUBLIC_INTERFACE (CartesianProductOperation)
 
template<class Config_t >
void random_impl (const Eigen::MatrixBase< Config_t > &qout) const
 
template<class ConfigL_t , class ConfigR_t , class ConfigOut_t >
void randomConfiguration_impl (const Eigen::MatrixBase< ConfigL_t > &lower, const Eigen::MatrixBase< ConfigR_t > &upper, const Eigen::MatrixBase< ConfigOut_t > &qout) const
 
template<class ConfigL_t , class ConfigR_t >
Scalar squaredDistance_impl (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1) const
 
- Public Member Functions inherited from LieGroupBase< CartesianProductOperation< LieGroup1, LieGroup2 > >
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.
 
void integrateCoeffWiseJacobian (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Jacobian_t > &J) const
 Computes the Jacobian of the integrate operator around zero.
 
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 tangent space at identity.
 
void dIntegrate (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianOut_t > &J, const ArgumentPosition arg, const AssignmentOperatorType op=SETTO) const
 Computes the Jacobian of a small variation of the configuration vector or the tangent vector into tangent space at identity.
 
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.
 
void dIntegrate_dq (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianIn_t > &Jin, int self, const Eigen::MatrixBase< JacobianOut_t > &Jout, const AssignmentOperatorType op=SETTO) const
 
void dIntegrate_dq (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, int self, const Eigen::MatrixBase< JacobianIn_t > &Jin, const Eigen::MatrixBase< JacobianOut_t > &Jout, const AssignmentOperatorType op=SETTO) 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.
 
void dIntegrate_dv (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, int self, const Eigen::MatrixBase< JacobianIn_t > &Jin, const Eigen::MatrixBase< JacobianOut_t > &Jout, const AssignmentOperatorType op=SETTO) const
 
void dIntegrate_dv (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianIn_t > &Jin, int self, const Eigen::MatrixBase< JacobianOut_t > &Jout, const AssignmentOperatorType op=SETTO) const
 
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 initial tangent space of the integrate operation, with respect to the configuration or the velocity arguments.
 
void dIntegrateTransport (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< Jacobian_t > &J, const ArgumentPosition arg) const
 Transport in place a matrix from the terminal to the initial tangent space of the integrate operation, with respect to the configuration or the velocity arguments.
 
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 initial tangent space of the integrate operation, with respect to the configuration argument.
 
void dIntegrateTransport_dq (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< Jacobian_t > &J) const
 Transport in place a matrix from the terminal to the initial tangent space of the integrate operation, with respect to the configuration argument.
 
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 initial tangent space of the integrate operation, with respect to the velocity argument.
 
void dIntegrateTransport_dv (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< Jacobian_t > &J) const
 Transport in place a matrix from the terminal to the initial tangent space of the integrate operation, with respect to the velocity argument.
 
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 normalize (const Eigen::MatrixBase< Config_t > &qout) const
 Normalize the joint configuration given as input. For instance, the quaternion must be unitary.
 
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 unitary.
 
void random (const Eigen::MatrixBase< Config_t > &qout) const
 Generate a random joint configuration, normalizing quaternions when necessary.
 
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.
 
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.
 
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.
 
void dDifference (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Eigen::MatrixBase< JacobianOut_t > &J, const ArgumentPosition arg) const
 Computes the Jacobian of the difference operation with respect to q0 or q1.
 
void dDifference (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Eigen::MatrixBase< JacobianIn_t > &Jin, int self, const Eigen::MatrixBase< JacobianOut_t > &Jout, const AssignmentOperatorType op=SETTO) const
 
void dDifference (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, int self, const Eigen::MatrixBase< JacobianIn_t > &Jin, const Eigen::MatrixBase< JacobianOut_t > &Jout, const AssignmentOperatorType op=SETTO) const
 
Scalar squaredDistance (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1) const
 Squared distance between two joint configurations.
 
Scalar distance (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1) const
 Distance between two configurations of the joint.
 
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.
 
bool operator== (const LieGroupBase &other) const
 
bool operator!= (const LieGroupBase &other) const
 
ConfigVector_t integrate (const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v) const
 
ConfigVector_t interpolate (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Scalar &u) const
 
ConfigVector_t random () const
 
ConfigVector_t randomConfiguration (const Eigen::MatrixBase< ConfigL_t > &lower_pos_limit, const Eigen::MatrixBase< ConfigR_t > &upper_pos_limit) const
 
TangentVector_t difference (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1) const
 
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
 
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
 
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 normalize_impl (const Eigen::MatrixBase< Config_t > &qout) const
 
bool isNormalized_impl (const Eigen::MatrixBase< Config_t > &qin, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
 
Scalar squaredDistance_impl (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1) const
 
bool isSameConfiguration_impl (const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Scalar &prec) const
 
bool isEqual_impl (const LieGroupBase &) const
 Default equality check. By default, two LieGroupBase of same type are considered equal.
 
bool isDifferent_impl (const LieGroupBase &other) const
 
Index nq () const
 
Index nv () const
 Get dimension of Lie Group tangent space.
 
ConfigVector_t neutral () const
 Get neutral element as a vector.
 
std::string name () const
 Get name of instance.
 
CartesianProductOperation< LieGroup1, LieGroup2 > & derived ()
 
const CartesianProductOperation< LieGroup1, LieGroup2 > & derived () const
 

Public Attributes

LieGroup1 lg1
 
LieGroup2 lg2
 

Additional Inherited Members

- Public Types inherited from LieGroupBase< CartesianProductOperation< LieGroup1, LieGroup2 > >
enum  
 
typedef Eigen::Matrix< Scalar, NQ, 1, Options > ConfigVector_t
 
typedef int Index
 
typedef Eigen::Matrix< Scalar, NV, NV, Options > JacobianMatrix_t
 
typedef CartesianProductOperation< LieGroup1, LieGroup2LieGroupDerived
 
typedef traits< LieGroupDerived >::Scalar Scalar
 
typedef Eigen::Matrix< Scalar, NV, 1, Options > TangentVector_t
 
- Protected Member Functions inherited from LieGroupBase< CartesianProductOperation< LieGroup1, LieGroup2 > >
 LieGroupBase ()
 
 LieGroupBase (const LieGroupBase &)
 
LieGroupBaseoperator= (const LieGroupBase &)
 

Detailed Description

template<typename LieGroup1, typename LieGroup2>
struct pinocchio::CartesianProductOperation< LieGroup1, LieGroup2 >

Definition at line 57 of file cartesian-product.hpp.

Constructor & Destructor Documentation

◆ CartesianProductOperation()

Definition at line 62 of file cartesian-product.hpp.

Member Function Documentation

◆ dDifference_impl()

void dDifference_impl ( const Eigen::MatrixBase< ConfigL_t > &  q0,
const Eigen::MatrixBase< ConfigR_t > &  q1,
const Eigen::MatrixBase< JacobianOut_t > &  J 
) const
inline

Definition at line 109 of file cartesian-product.hpp.

◆ difference_impl()

void difference_impl ( const Eigen::MatrixBase< ConfigL_t > &  q0,
const Eigen::MatrixBase< ConfigR_t > &  q1,
const Eigen::MatrixBase< Tangent_t > &  d 
) const
inline

Definition at line 99 of file cartesian-product.hpp.

◆ dIntegrate_dq_impl()

void dIntegrate_dq_impl ( const Eigen::MatrixBase< Config_t > &  q,
const Eigen::MatrixBase< Tangent_t > &  v,
const Eigen::MatrixBase< JacobianOut_t > &  J,
const AssignmentOperatorType  op = SETTO 
) const
inline

Definition at line 145 of file cartesian-product.hpp.

◆ dIntegrate_dv_impl()

void dIntegrate_dv_impl ( const Eigen::MatrixBase< Config_t > &  q,
const Eigen::MatrixBase< Tangent_t > &  v,
const Eigen::MatrixBase< JacobianOut_t > &  J,
const AssignmentOperatorType  op = SETTO 
) const
inline

Definition at line 169 of file cartesian-product.hpp.

◆ dIntegrateTransport_dq_impl() [1/2]

void dIntegrateTransport_dq_impl ( const Eigen::MatrixBase< Config_t > &  q,
const Eigen::MatrixBase< Tangent_t > &  v,
const Eigen::MatrixBase< Jacobian_t > &  Jin 
) const
inline

Definition at line 227 of file cartesian-product.hpp.

◆ dIntegrateTransport_dq_impl() [2/2]

void dIntegrateTransport_dq_impl ( const Eigen::MatrixBase< Config_t > &  q,
const Eigen::MatrixBase< Tangent_t > &  v,
const Eigen::MatrixBase< JacobianIn_t > &  J_in,
const Eigen::MatrixBase< JacobianOut_t > &  J_out 
) const
inline

Definition at line 193 of file cartesian-product.hpp.

◆ dIntegrateTransport_dv_impl() [1/2]

void dIntegrateTransport_dv_impl ( const Eigen::MatrixBase< Config_t > &  q,
const Eigen::MatrixBase< Tangent_t > &  v,
const Eigen::MatrixBase< Jacobian_t > &  Jin 
) const
inline

Definition at line 238 of file cartesian-product.hpp.

◆ dIntegrateTransport_dv_impl() [2/2]

void dIntegrateTransport_dv_impl ( const Eigen::MatrixBase< Config_t > &  q,
const Eigen::MatrixBase< Tangent_t > &  v,
const Eigen::MatrixBase< JacobianIn_t > &  J_in,
const Eigen::MatrixBase< JacobianOut_t > &  J_out 
) const
inline

Definition at line 210 of file cartesian-product.hpp.

◆ integrate_impl()

void integrate_impl ( const Eigen::MatrixBase< ConfigIn_t > &  q,
const Eigen::MatrixBase< Velocity_t > &  v,
const Eigen::MatrixBase< ConfigOut_t > &  qout 
) const
inline

Definition at line 122 of file cartesian-product.hpp.

◆ integrateCoeffWiseJacobian_impl()

void integrateCoeffWiseJacobian_impl ( const Eigen::MatrixBase< Config_t > &  q,
const Eigen::MatrixBase< Jacobian_t > &  J 
) const
inline

Definition at line 132 of file cartesian-product.hpp.

◆ isEqual_impl()

bool isEqual_impl ( const CartesianProductOperation< LieGroup1, LieGroup2 > &  other) const
inline

Definition at line 295 of file cartesian-product.hpp.

◆ isNormalized_impl()

template<class Config_t >
bool isNormalized_impl ( const Eigen::MatrixBase< Config_t > &  qin,
const Scalar &  prec 
) const
inline

Definition at line 263 of file cartesian-product.hpp.

◆ isSameConfiguration_impl()

bool isSameConfiguration_impl ( const Eigen::MatrixBase< ConfigL_t > &  q0,
const Eigen::MatrixBase< ConfigR_t > &  q1,
const Scalar &  prec 
) const
inline

Definition at line 286 of file cartesian-product.hpp.

◆ name()

std::string name ( ) const
inline

Definition at line 91 of file cartesian-product.hpp.

◆ neutral()

ConfigVector_t neutral ( ) const
inline

Definition at line 82 of file cartesian-product.hpp.

◆ normalize_impl()

template<class Config_t >
void normalize_impl ( const Eigen::MatrixBase< Config_t > &  qout) const
inline

Definition at line 256 of file cartesian-product.hpp.

◆ nq()

Index nq ( ) const
inline

Definition at line 71 of file cartesian-product.hpp.

◆ nv()

Index nv ( ) const
inline

Definition at line 77 of file cartesian-product.hpp.

◆ random_impl()

template<class Config_t >
void random_impl ( const Eigen::MatrixBase< Config_t > &  qout) const
inline

Definition at line 269 of file cartesian-product.hpp.

◆ randomConfiguration_impl()

void randomConfiguration_impl ( const Eigen::MatrixBase< ConfigL_t > &  lower,
const Eigen::MatrixBase< ConfigR_t > &  upper,
const Eigen::MatrixBase< ConfigOut_t > &  qout 
) const
inline

Definition at line 276 of file cartesian-product.hpp.

◆ squaredDistance_impl()

Scalar squaredDistance_impl ( const Eigen::MatrixBase< ConfigL_t > &  q0,
const Eigen::MatrixBase< ConfigR_t > &  q1 
) const
inline

Definition at line 249 of file cartesian-product.hpp.

Member Data Documentation

◆ lg1

Definition at line 300 of file cartesian-product.hpp.

◆ lg2

Definition at line 301 of file cartesian-product.hpp.


The documentation for this struct was generated from the following file: