#include <joint-mimic.hpp>
Classes | |
struct | TransposeConst |
Public Types | |
enum | { NV = Constraint::NV } |
typedef ConstraintBase< ScaledConstraint > | Base |
typedef SE3GroupAction< Constraint >::ReturnType | SE3ActionReturnType |
Public Member Functions | |
template<typename VectorLike > | |
JointMotion | __mult__ (const Eigen::MatrixBase< VectorLike > &v) const |
const Constraint & | constraint () const |
Constraint & | constraint () |
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_impl () const |
ScaledConstraint & | operator= (const ScaledConstraint &other) |
ScaledConstraint () | |
ScaledConstraint (const Scalar &scaling_factor) | |
ScaledConstraint (const Constraint &constraint, const Scalar &scaling_factor) | |
ScaledConstraint (const ScaledConstraint &other) | |
const Scalar & | scaling () const |
Scalar & | scaling () |
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 |
Public Member Functions inherited from pinocchio::ConstraintBase< ScaledConstraint< Constraint > > | |
int | cols () const |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW ScaledConstraint< Constraint > & | derived () |
const ScaledConstraint< Constraint > & | derived () const |
void | disp (std::ostream &os) const |
bool | isApprox (const ConstraintBase< OtherDerived > &other, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const |
MatrixReturnType | matrix () |
ConstMatrixReturnType | matrix () const |
MotionAlgebraAction< ScaledConstraint< Constraint >, MotionDerived >::ReturnType | motionAction (const MotionDense< MotionDerived > &v) const |
int | nv () const |
JointMotion | operator* (const Eigen::MatrixBase< VectorLike > &vj) const |
bool | operator== (const ConstraintBase< ScaledConstraint< Constraint > > &other) const |
SE3GroupAction< ScaledConstraint< Constraint > >::ReturnType | se3Action (const SE3Tpl< Scalar, Options > &m) const |
SE3GroupAction< ScaledConstraint< Constraint > >::ReturnType | se3ActionInverse (const SE3Tpl< Scalar, Options > &m) const |
Protected Attributes | |
Constraint | m_constraint |
Scalar | m_scaling_factor |
Additional Inherited Members | |
Static Public Member Functions inherited from pinocchio::ConstraintBase< ScaledConstraint< Constraint > > | |
static int | rows () |
Definition at line 14 of file joint-mimic.hpp.
typedef ConstraintBase<ScaledConstraint> pinocchio::ScaledConstraint< Constraint >::Base |
Definition at line 67 of file joint-mimic.hpp.
typedef SE3GroupAction<Constraint>::ReturnType pinocchio::ScaledConstraint< Constraint >::SE3ActionReturnType |
Definition at line 70 of file joint-mimic.hpp.
anonymous enum |
Enumerator | |
---|---|
NV |
Definition at line 66 of file joint-mimic.hpp.
|
inline |
Definition at line 72 of file joint-mimic.hpp.
|
inlineexplicit |
Definition at line 74 of file joint-mimic.hpp.
|
inline |
Definition at line 78 of file joint-mimic.hpp.
|
inline |
Definition at line 84 of file joint-mimic.hpp.
|
inline |
Definition at line 97 of file joint-mimic.hpp.
|
inline |
Definition at line 167 of file joint-mimic.hpp.
|
inline |
Definition at line 168 of file joint-mimic.hpp.
|
inline |
Definition at line 170 of file joint-mimic.hpp.
|
inline |
Definition at line 149 of file joint-mimic.hpp.
|
inline |
Definition at line 157 of file joint-mimic.hpp.
|
inline |
Definition at line 120 of file joint-mimic.hpp.
|
inline |
Definition at line 89 of file joint-mimic.hpp.
|
inline |
Definition at line 164 of file joint-mimic.hpp.
|
inline |
Definition at line 165 of file joint-mimic.hpp.
|
inline |
Definition at line 106 of file joint-mimic.hpp.
|
inline |
Definition at line 114 of file joint-mimic.hpp.
|
inline |
Definition at line 147 of file joint-mimic.hpp.
|
protected |
Definition at line 178 of file joint-mimic.hpp.
|
protected |
Definition at line 179 of file joint-mimic.hpp.