Classes | Public Types | Public Member Functions | Protected Attributes | List of all members
pinocchio::ConstraintPrismaticUnalignedTpl< _Scalar, _Options > Struct Template Reference

#include <joint-prismatic-unaligned.hpp>

Inheritance diagram for pinocchio::ConstraintPrismaticUnalignedTpl< _Scalar, _Options >:
Inheritance graph
[legend]

Classes

struct  TransposeConst
 

Public Types

enum  { NV = 1 }
 
typedef traits< ConstraintPrismaticUnalignedTpl >::Vector3 Vector3
 

Public Member Functions

template<typename Vector1Like >
JointMotion __mult__ (const Eigen::MatrixBase< Vector1Like > &v) const
 
const Vector3axis () const
 
Vector3axis ()
 
 ConstraintPrismaticUnalignedTpl ()
 
template<typename Vector3Like >
 ConstraintPrismaticUnalignedTpl (const Eigen::MatrixBase< Vector3Like > &axis)
 
bool isEqual (const ConstraintPrismaticUnalignedTpl &other) const
 
DenseBase matrix_impl () const
 
template<typename MotionDerived >
DenseBase motionAction (const MotionDense< MotionDerived > &v) const
 
int nv_impl () const
 
template<typename S1 , int O1>
SE3GroupAction< ConstraintPrismaticUnalignedTpl >::ReturnType se3Action (const SE3Tpl< S1, O1 > &m) const
 
template<typename S1 , int O1>
SE3GroupAction< ConstraintPrismaticUnalignedTpl >::ReturnType se3ActionInverse (const SE3Tpl< S1, O1 > &m) const
 
TransposeConst transpose () const
 
- Public Member Functions inherited from pinocchio::ConstraintBase< ConstraintPrismaticUnalignedTpl< _Scalar, _Options > >
int cols () const
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW ConstraintPrismaticUnalignedTpl< _Scalar, _Options > & derived ()
 
const ConstraintPrismaticUnalignedTpl< _Scalar, _Options > & 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< ConstraintPrismaticUnalignedTpl< _Scalar, _Options >, MotionDerived >::ReturnType motionAction (const MotionDense< MotionDerived > &v) const
 
int nv () const
 
JointMotion operator* (const Eigen::MatrixBase< VectorLike > &vj) const
 
bool operator== (const ConstraintBase< ConstraintPrismaticUnalignedTpl< _Scalar, _Options > > &other) const
 
SE3GroupAction< ConstraintPrismaticUnalignedTpl< _Scalar, _Options > >::ReturnType se3Action (const SE3Tpl< Scalar, Options > &m) const
 
SE3GroupAction< ConstraintPrismaticUnalignedTpl< _Scalar, _Options > >::ReturnType se3ActionInverse (const SE3Tpl< Scalar, Options > &m) const
 

Protected Attributes

Vector3 m_axis
 

Additional Inherited Members

- Static Public Member Functions inherited from pinocchio::ConstraintBase< ConstraintPrismaticUnalignedTpl< _Scalar, _Options > >
static int rows ()
 

Detailed Description

template<typename _Scalar, int _Options>
struct pinocchio::ConstraintPrismaticUnalignedTpl< _Scalar, _Options >

Definition at line 182 of file joint-prismatic-unaligned.hpp.

Member Typedef Documentation

template<typename _Scalar, int _Options>
typedef traits<ConstraintPrismaticUnalignedTpl>::Vector3 pinocchio::ConstraintPrismaticUnalignedTpl< _Scalar, _Options >::Vector3

Definition at line 235 of file joint-prismatic-unaligned.hpp.

Member Enumeration Documentation

template<typename _Scalar, int _Options>
anonymous enum
Enumerator
NV 

Definition at line 233 of file joint-prismatic-unaligned.hpp.

Constructor & Destructor Documentation

template<typename _Scalar, int _Options>
pinocchio::ConstraintPrismaticUnalignedTpl< _Scalar, _Options >::ConstraintPrismaticUnalignedTpl ( )
inline

Definition at line 237 of file joint-prismatic-unaligned.hpp.

template<typename _Scalar, int _Options>
template<typename Vector3Like >
pinocchio::ConstraintPrismaticUnalignedTpl< _Scalar, _Options >::ConstraintPrismaticUnalignedTpl ( const Eigen::MatrixBase< Vector3Like > &  axis)
inline

Definition at line 240 of file joint-prismatic-unaligned.hpp.

Member Function Documentation

template<typename _Scalar, int _Options>
template<typename Vector1Like >
JointMotion pinocchio::ConstraintPrismaticUnalignedTpl< _Scalar, _Options >::__mult__ ( const Eigen::MatrixBase< Vector1Like > &  v) const
inline

Definition at line 245 of file joint-prismatic-unaligned.hpp.

template<typename _Scalar, int _Options>
const Vector3& pinocchio::ConstraintPrismaticUnalignedTpl< _Scalar, _Options >::axis ( ) const
inline

Definition at line 328 of file joint-prismatic-unaligned.hpp.

template<typename _Scalar, int _Options>
Vector3& pinocchio::ConstraintPrismaticUnalignedTpl< _Scalar, _Options >::axis ( )
inline

Definition at line 329 of file joint-prismatic-unaligned.hpp.

template<typename _Scalar, int _Options>
bool pinocchio::ConstraintPrismaticUnalignedTpl< _Scalar, _Options >::isEqual ( const ConstraintPrismaticUnalignedTpl< _Scalar, _Options > &  other) const
inline

Definition at line 331 of file joint-prismatic-unaligned.hpp.

template<typename _Scalar, int _Options>
DenseBase pinocchio::ConstraintPrismaticUnalignedTpl< _Scalar, _Options >::matrix_impl ( ) const
inline

Definition at line 310 of file joint-prismatic-unaligned.hpp.

template<typename _Scalar, int _Options>
template<typename MotionDerived >
DenseBase pinocchio::ConstraintPrismaticUnalignedTpl< _Scalar, _Options >::motionAction ( const MotionDense< MotionDerived > &  v) const
inline

Definition at line 319 of file joint-prismatic-unaligned.hpp.

template<typename _Scalar, int _Options>
int pinocchio::ConstraintPrismaticUnalignedTpl< _Scalar, _Options >::nv_impl ( ) const
inline

Definition at line 273 of file joint-prismatic-unaligned.hpp.

template<typename _Scalar, int _Options>
template<typename S1 , int O1>
SE3GroupAction<ConstraintPrismaticUnalignedTpl>::ReturnType pinocchio::ConstraintPrismaticUnalignedTpl< _Scalar, _Options >::se3Action ( const SE3Tpl< S1, O1 > &  m) const
inline

Definition at line 253 of file joint-prismatic-unaligned.hpp.

template<typename _Scalar, int _Options>
template<typename S1 , int O1>
SE3GroupAction<ConstraintPrismaticUnalignedTpl>::ReturnType pinocchio::ConstraintPrismaticUnalignedTpl< _Scalar, _Options >::se3ActionInverse ( const SE3Tpl< S1, O1 > &  m) const
inline

Definition at line 264 of file joint-prismatic-unaligned.hpp.

template<typename _Scalar, int _Options>
TransposeConst pinocchio::ConstraintPrismaticUnalignedTpl< _Scalar, _Options >::transpose ( ) const
inline

Definition at line 302 of file joint-prismatic-unaligned.hpp.

Member Data Documentation

template<typename _Scalar, int _Options>
Vector3 pinocchio::ConstraintPrismaticUnalignedTpl< _Scalar, _Options >::m_axis
protected

Definition at line 338 of file joint-prismatic-unaligned.hpp.


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


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:05