Classes | Public Types | Public Member Functions | Protected Attributes | List of all members
pinocchio::ScaledConstraint< Constraint > Struct Template Reference

#include <joint-mimic.hpp>

Classes

struct  TransposeConst
 

Public Types

enum  { NV = Constraint::NV }
 
typedef ConstraintBase< ScaledConstraintBase
 
typedef SE3GroupAction< Constraint >::ReturnType SE3ActionReturnType
 

Public Member Functions

template<typename VectorLike >
JointMotion __mult__ (const Eigen::MatrixBase< VectorLike > &v) const
 
Constraint & constraint ()
 
const Constraint & constraint () const
 
bool isEqual (const ScaledConstraint &other) const
 
DenseBase matrix_impl () const
 
template<typename MotionDerived >
MotionAlgebraAction< ScaledConstraint, MotionDerived >::ReturnType motionAction (const MotionDense< MotionDerived > &m) const
 
int nv () const
 
int nv_impl () const
 
ScaledConstraintoperator= (const ScaledConstraint &other)
 
 ScaledConstraint ()
 
 ScaledConstraint (const Constraint &constraint, const Scalar &scaling_factor)
 
 ScaledConstraint (const Scalar &scaling_factor)
 
 ScaledConstraint (const ScaledConstraint &other)
 
Scalar & scaling ()
 
const Scalar & scaling () const
 
template<typename S1 , int O1>
SE3ActionReturnType se3Action (const SE3Tpl< S1, O1 > &m) const
 
template<typename S1 , int O1>
SE3ActionReturnType se3ActionInverse (const SE3Tpl< S1, O1 > &m) const
 
TransposeConst transpose () const
 

Protected Attributes

Constraint m_constraint
 
Scalar m_scaling_factor
 

Detailed Description

template<class Constraint>
struct pinocchio::ScaledConstraint< Constraint >

Definition at line 14 of file joint-mimic.hpp.

Member Typedef Documentation

◆ Base

template<class Constraint >
typedef ConstraintBase<ScaledConstraint> pinocchio::ScaledConstraint< Constraint >::Base

Definition at line 67 of file joint-mimic.hpp.

◆ SE3ActionReturnType

template<class Constraint >
typedef SE3GroupAction<Constraint>::ReturnType pinocchio::ScaledConstraint< Constraint >::SE3ActionReturnType

Definition at line 70 of file joint-mimic.hpp.

Member Enumeration Documentation

◆ anonymous enum

template<class Constraint >
anonymous enum
Enumerator
NV 

Definition at line 66 of file joint-mimic.hpp.

Constructor & Destructor Documentation

◆ ScaledConstraint() [1/4]

template<class Constraint >
pinocchio::ScaledConstraint< Constraint >::ScaledConstraint ( )
inline

Definition at line 72 of file joint-mimic.hpp.

◆ ScaledConstraint() [2/4]

template<class Constraint >
pinocchio::ScaledConstraint< Constraint >::ScaledConstraint ( const Scalar &  scaling_factor)
inlineexplicit

Definition at line 74 of file joint-mimic.hpp.

◆ ScaledConstraint() [3/4]

template<class Constraint >
pinocchio::ScaledConstraint< Constraint >::ScaledConstraint ( const Constraint &  constraint,
const Scalar &  scaling_factor 
)
inline

Definition at line 78 of file joint-mimic.hpp.

◆ ScaledConstraint() [4/4]

template<class Constraint >
pinocchio::ScaledConstraint< Constraint >::ScaledConstraint ( const ScaledConstraint< Constraint > &  other)
inline

Definition at line 84 of file joint-mimic.hpp.

Member Function Documentation

◆ __mult__()

template<class Constraint >
template<typename VectorLike >
JointMotion pinocchio::ScaledConstraint< Constraint >::__mult__ ( const Eigen::MatrixBase< VectorLike > &  v) const
inline

Definition at line 97 of file joint-mimic.hpp.

◆ constraint() [1/2]

template<class Constraint >
Constraint& pinocchio::ScaledConstraint< Constraint >::constraint ( )
inline

Definition at line 168 of file joint-mimic.hpp.

◆ constraint() [2/2]

template<class Constraint >
const Constraint& pinocchio::ScaledConstraint< Constraint >::constraint ( ) const
inline

Definition at line 167 of file joint-mimic.hpp.

◆ isEqual()

template<class Constraint >
bool pinocchio::ScaledConstraint< Constraint >::isEqual ( const ScaledConstraint< Constraint > &  other) const
inline

Definition at line 170 of file joint-mimic.hpp.

◆ matrix_impl()

template<class Constraint >
DenseBase pinocchio::ScaledConstraint< Constraint >::matrix_impl ( ) const
inline

Definition at line 149 of file joint-mimic.hpp.

◆ motionAction()

template<class Constraint >
template<typename MotionDerived >
MotionAlgebraAction<ScaledConstraint,MotionDerived>::ReturnType pinocchio::ScaledConstraint< Constraint >::motionAction ( const MotionDense< MotionDerived > &  m) const
inline

Definition at line 157 of file joint-mimic.hpp.

◆ nv()

template<class Constraint >
int pinocchio::ConstraintBase< Derived >::nv
inline

Definition at line 66 of file constraint-base.hpp.

◆ nv_impl()

template<class Constraint >
int pinocchio::ScaledConstraint< Constraint >::nv_impl ( ) const
inline

Definition at line 120 of file joint-mimic.hpp.

◆ operator=()

template<class Constraint >
ScaledConstraint& pinocchio::ScaledConstraint< Constraint >::operator= ( const ScaledConstraint< Constraint > &  other)
inline

Definition at line 89 of file joint-mimic.hpp.

◆ scaling() [1/2]

template<class Constraint >
Scalar& pinocchio::ScaledConstraint< Constraint >::scaling ( )
inline

Definition at line 165 of file joint-mimic.hpp.

◆ scaling() [2/2]

template<class Constraint >
const Scalar& pinocchio::ScaledConstraint< Constraint >::scaling ( ) const
inline

Definition at line 164 of file joint-mimic.hpp.

◆ se3Action()

template<class Constraint >
template<typename S1 , int O1>
SE3ActionReturnType pinocchio::ScaledConstraint< Constraint >::se3Action ( const SE3Tpl< S1, O1 > &  m) const
inline

Definition at line 106 of file joint-mimic.hpp.

◆ se3ActionInverse()

template<class Constraint >
template<typename S1 , int O1>
SE3ActionReturnType pinocchio::ScaledConstraint< Constraint >::se3ActionInverse ( const SE3Tpl< S1, O1 > &  m) const
inline

Definition at line 114 of file joint-mimic.hpp.

◆ transpose()

template<class Constraint >
TransposeConst pinocchio::ScaledConstraint< Constraint >::transpose ( ) const
inline

Definition at line 147 of file joint-mimic.hpp.

Member Data Documentation

◆ m_constraint

template<class Constraint >
Constraint pinocchio::ScaledConstraint< Constraint >::m_constraint
protected

Definition at line 178 of file joint-mimic.hpp.

◆ m_scaling_factor

template<class Constraint >
Scalar pinocchio::ScaledConstraint< Constraint >::m_scaling_factor
protected

Definition at line 179 of file joint-mimic.hpp.


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


pinocchio
Author(s):
autogenerated on Tue Feb 13 2024 03:44:02