cisst-saw
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
Public Member Functions | List of all members
osaODEBarrettHand Class Reference

ODE Barrett Hand. More...

#include <osaODEBarrettHand.h>

Inheritance diagram for osaODEBarrettHand:
osaOSGBH osaOSGManipulator robManipulator

Public Member Functions

 osaODEBarrettHand (const std::string &palmmodel, const std::string &metacarpalmodel, const std::string &proximalmodel, const std::string &intermediatemodel, osaODEWorld *world, const vctFrame4x4< double > &Rtw0, const std::string &f1f2filename, const std::string &f3filename)
 Barrett Hand constructor. More...
 
 osaODEBarrettHand (const std::string &palmmodel, const std::string &metacarpalmodel, const std::string &proximalmodel, const std::string &intermediatemodel, osaODEWorld *world, const vctFrm3 &Rtw0, const std::string &f1f2filename, const std::string &f3filename)
 Barrett Hand constructor. More...
 
 ~osaODEBarrettHand ()
 
- Public Member Functions inherited from osaOSGBH
 osaOSGBH (const std::string &palmmodel, const std::string &metacarpalmodel, const std::string &proximalmodel, const std::string &intermediatemodel, osaOSGWorld *world, const vctFrame4x4< double > &Rtw0, const std::string &f1f2filename, const std::string &f3filename)
 Barrett Hand constructor. More...
 
 osaOSGBH (const std::string &palmmodel, const std::string &metacarpalmodel, const std::string &proximalmodel, const std::string &intermediatemodel, osaOSGWorld *world, const vctFrm3 &Rtw0, const std::string &f1f2filename, const std::string &f3filename)
 Barrett Hand constructor. More...
 
 ~osaOSGBH ()
 
void Initialize ()
 Initialize the hand. More...
 
virtual osaOSGBH::Errno GetPositions (vctDynamicVector< double > &q) const
 Return the joints positions. More...
 
virtual osaOSGBH::Errno SetPositions (const vctDynamicVector< double > &qs)
 Set the joint position. More...
 
- Public Member Functions inherited from osaOSGManipulator
 osaOSGManipulator (const std::vector< std::string > &models, osaOSGWorld *world, const vctFrame4x4< double > &Rtw0, const std::string &robfilename, const std::string &basemodel="")
 OSG Manipulator generic constructor. More...
 
 osaOSGManipulator (const std::vector< std::string > &models, osaOSGWorld *world, const vctFrm3 &Rtw0, const std::string &robfilename, const std::string &basemodel="")
 OSG Manipulator generic constructor. More...
 
 ~osaOSGManipulator ()
 
void Initialize ()
 
unsigned int GetNumLinks ()
 
osaOSGBodyGetLink (size_t i)
 
osaOSGBodyGetBase ()
 
virtual void Attach (osaOSGManipulator *CMN_UNUSED(tool))
 
- Public Member Functions inherited from robManipulator
robManipulator::Errno LoadRobot (const std::string &linkfile)
 Load the kinematics and the dynamics of the robot. More...
 
robManipulator::Errno LoadRobot (std::vector< robKinematics * > KinParms)
 
void JacobianBody (const vctDynamicVector< double > &q) const
 Evaluate the body Jacobian. More...
 
bool JacobianBody (const vctDynamicVector< double > &q, vctDynamicMatrix< double > &J) const
 Evaluate the body Jacobian and return it in the dynamic matrix J. More...
 
void JacobianSpatial (const vctDynamicVector< double > &q) const
 Evaluate the spatial Jacobian. More...
 
bool JacobianSpatial (const vctDynamicVector< double > &q, vctDynamicMatrix< double > &J) const
 Evaluate the spatial Jacobian and return it in the dynamic matrix J. More...
 
vctDynamicVector< double > RNE (const vctDynamicVector< double > &q, const vctDynamicVector< double > &qd, const vctDynamicVector< double > &qdd, const vctFixedSizeVector< double, 6 > &f, double g=9.81) const
 Recursive Newton-Euler altorithm. More...
 
vctDynamicVector< double > CCG (const vctDynamicVector< double > &q, const vctDynamicVector< double > &qd) const
 Coriolis/centrifugal and gravity. More...
 
vctFixedSizeVector< double, 6 > BiasAcceleration (const vctDynamicVector< double > &q, const vctDynamicVector< double > &qd) const
 End-effector accelerations. More...
 
void JSinertia (double **A, const vctDynamicVector< double > &q) const
 Compute the NxN manipulator inertia matrix. More...
 
vctDynamicMatrix< double > JSinertia (const vctDynamicVector< double > &q) const
 
void OSinertia (double Ac[6][6], const vctDynamicVector< double > &q) const
 Compute the 6x6 manipulator inertia matrix in operation space. More...
 
vctFixedSizeMatrix< double, 4, 4 > SE3Difference (const vctFrame4x4< double > &Rt1, const vctFrame4x4< double > &Rt2) const
 
void AddIdentificationColumn (vctDynamicMatrix< double > &J, vctFixedSizeMatrix< double, 4, 4 > &delRt) const
 
 robManipulator (const vctFrame4x4< double > &Rtw0=vctFrame4x4< double >())
 
 robManipulator (const std::string &robotfilename, const vctFrame4x4< double > &Rtw0=vctFrame4x4< double >())
 Manipulator generic constructor. More...
 
 robManipulator (const std::vector< robKinematics * > linkParms, const vctFrame4x4< double > &Rtw0=vctFrame4x4< double >())
 
virtual ~robManipulator ()
 Manipulator destructor. More...
 
virtual vctFrame4x4< double > ForwardKinematics (const vctDynamicVector< double > &q, int N=-1) const
 Evaluate the forward kinematics. More...
 
virtual robManipulator::Errno InverseKinematics (vctDynamicVector< double > &q, const vctFrame4x4< double > &Rts, double tolerance=1e-12, size_t Niteration=1000, double LAMBDA=0.001)
 Evaluate the inverse kinematics. More...
 
virtual robManipulator::Errno InverseKinematics (vctDynamicVector< double > &q, const vctFrm3 &Rts, double tolerance=1e-12, size_t Niteration=1000)
 
virtual void NormalizeAngles (vctDynamicVector< double > &q)
 Normalize angles to -pi to pi. More...
 
virtual vctDynamicVector< double > InverseDynamics (const vctDynamicVector< double > &q, const vctDynamicVector< double > &qd, const vctDynamicVector< double > &qdd) const
 Inverse dynamics in joint space. More...
 
virtual vctDynamicVector< double > InverseDynamics (const vctDynamicVector< double > &q, const vctDynamicVector< double > &qd, const vctFixedSizeVector< double, 6 > &vdwd) const
 Inverse dynamics in operation space. More...
 
virtual vctDynamicMatrix< double > JacobianKinematicsIdentification (const vctDynamicVector< double > &q, double epsilon=1e-6) const
 Compute Jacobian for kinematics identification. More...
 
void PrintKinematics (std::ostream &os) const
 Print the kinematics parameters to the specified output stream. More...
 
virtual void Attach (robManipulator *tool)
 Attach a tool. More...
 

Additional Inherited Members

- Public Types inherited from robManipulator
enum  Errno { ESUCCESS, EFAILURE }
 
enum  LinkID {
  L0, L1, L2, L3,
  L4, L5, L6, L7,
  L8, L9, LN
}
 
- Public Attributes inherited from robManipulator
vctFrame4x4< double > Rtw0
 Position and orientation of the first link. More...
 
double ** Jn
 Body Jacobian. More...
 
double ** Js
 Spatial Jacobian. More...
 
std::vector< robLinklinks
 A vector of links. More...
 
- Protected Member Functions inherited from osaOSGBH
 osaOSGBH (const vctFrame4x4< double > &Rtw0, const std::string &robotfile)
 
 osaOSGBH (const vctFrm3 &Rtw0, const std::string &robotfile)
 
- Protected Member Functions inherited from osaOSGManipulator
 osaOSGManipulator (const vctFrame4x4< double > &Rtw0, const std::string &robotfile)
 
 osaOSGManipulator (const vctFrm3 &Rtw0, const std::string &robotfile)
 
- Protected Attributes inherited from osaOSGBH
osg::ref_ptr< osaOSGManipulatorf1
 
osg::ref_ptr< osaOSGManipulatorf2
 
osg::ref_ptr< osaOSGManipulatorf3
 
- Protected Attributes inherited from osaOSGManipulator
vctDynamicVector< double > q
 Store the current joints values. More...
 
osg::ref_ptr< osaOSGBodybase
 
osg::ref_ptr< osg::Group > osglinks
 
- Protected Attributes inherited from robManipulator
std::vector< robManipulator * > tools
 A vector of tools. More...
 

Detailed Description

ODE Barrett Hand.

This class implements a Barrett hand device for ODE simulation. The class is derived from osaODEManipulator yet it reimplements most of the virtual methods due to the parallel and underactuated architecture. The hand creates 3 fingers, themselves ODE manipulators devices and dispatches the I/O to each finger.

Constructor & Destructor Documentation

osaODEBarrettHand::osaODEBarrettHand ( const std::string &  palmmodel,
const std::string &  metacarpalmodel,
const std::string &  proximalmodel,
const std::string &  intermediatemodel,
osaODEWorld world,
const vctFrame4x4< double > &  Rtw0,
const std::string &  f1f2filename,
const std::string &  f3filename 
)

Barrett Hand constructor.

osaODEBarrettHand::osaODEBarrettHand ( const std::string &  palmmodel,
const std::string &  metacarpalmodel,
const std::string &  proximalmodel,
const std::string &  intermediatemodel,
osaODEWorld world,
const vctFrm3 Rtw0,
const std::string &  f1f2filename,
const std::string &  f3filename 
)

Barrett Hand constructor.

osaODEBarrettHand::~osaODEBarrettHand ( )

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