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

#include <osaODEManipulator.h>

Inheritance diagram for osaODEManipulator:
osaOSGManipulator robManipulator

Public Types

typedef std::vector
< osaODEBody::State
State
 The ODE state of the manipulator. More...
 
- Public Types inherited from robManipulator
enum  Errno { ESUCCESS, EFAILURE }
 
enum  LinkID {
  L0, L1, L2, L3,
  L4, L5, L6, L7,
  L8, L9, LN
}
 

Public Member Functions

 osaODEManipulator (const std::vector< std::string > &models, osaODEWorld *world, const vctFrame4x4< double > &Rtw0, const std::string &robotfilename, const std::string &basemodel, const vctDynamicVector< double > &qinit)
 ODE Manipulator constructor. More...
 
 osaODEManipulator (const std::vector< std::string > &models, osaODEWorld *world, const vctFrm3 &Rtw0, const std::string &robotfilename, const std::string &basemodel, const vctDynamicVector< double > &qinit)
 ODE Manipulator constructor. More...
 
 osaODEManipulator (const std::vector< std::string > &models, osaODEWorld *world, const vctFrame4x4< double > &Rtw0, const std::string &robotfilename, osaODEBody *base, const vctDynamicVector< double > &qinit)
 ODE Manipulator constructor. More...
 
 osaODEManipulator (const std::vector< std::string > &models, osaODEWorld *world, const vctFrm3 &Rtw0, const std::string &robotfilename, osaODEBody *base, const vctDynamicVector< double > &qinit)
 ODE Manipulator constructor. More...
 
 ~osaODEManipulator ()
 
virtual osaODEManipulator::Errno GetPositions (vctDynamicVector< double > &q) const
 Return the joints positions. More...
 
virtual osaODEManipulator::Errno GetVelocities (vctDynamicVector< double > &qd) const
 Return the joints velocities. More...
 
virtual osaODEManipulator::Errno SetPositions (const vctDynamicVector< double > &qs)
 Set the joint position. More...
 
virtual osaODEManipulator::Errno SetVelocities (const vctDynamicVector< double > &qds)
 Set the joint velocity. More...
 
virtual osaODEManipulator::Errno SetForcesTorques (const vctDynamicVector< double > &ft)
 Set the joint forces or torques. More...
 
virtual osaODEManipulator::State GetState () const
 Return the state of the robot. More...
 
virtual void SetState (const osaODEManipulator::State &state)
 Set the state of the robot. More...
 
dBodyID GetBaseID () const
 Return the base ID of the manipulator. More...
 
virtual vctFrame4x4< double > ForwardKinematics (const vctDynamicVector< double > &q, int N=-1) const
 Evaluate the forward kinematics. More...
 
void ForwardKinematics (const vctDynamicVector< double > &q, vctFrm3 &Rt, int N=-1) const
 
virtual void Attach (osaOSGManipulator *osgtool)
 Attach a tool to the robot. More...
 
void Disable ()
 Disable all the bodies of the manipulator. More...
 
void Enable ()
 Enable all the bodies of the manipulator. 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 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...
 

Protected Member Functions

osaODEWorldGetWorld () const
 Return the world ID. More...
 
dWorldID GetWorldID () const
 
void Insert (osaODEBody *body)
 Insert a body in the manipulator. More...
 
void Insert (osaODEJoint *joint)
 Insert a joint in the manipulator. More...
 
void Insert (osaODEServoMotor *servo)
 Insert a joint in the manipulator. More...
 
- Protected Member Functions inherited from osaOSGManipulator
 osaOSGManipulator (const vctFrame4x4< double > &Rtw0, const std::string &robotfile)
 
 osaOSGManipulator (const vctFrm3 &Rtw0, const std::string &robotfile)
 

Additional Inherited Members

- 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 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...
 

Member Typedef Documentation

The ODE state of the manipulator.

Constructor & Destructor Documentation

osaODEManipulator::osaODEManipulator ( const std::vector< std::string > &  models,
osaODEWorld world,
const vctFrame4x4< double > &  Rtw0,
const std::string &  robotfilename,
const std::string &  basemodel,
const vctDynamicVector< double > &  qinit 
)

ODE Manipulator constructor.

This constructor initializes an ODE manipulator with the kinematics and dynamics contained in a file. Plus it initializes the ODE elements of the manipulators (bodies and joints) for the engine.

Parameters
modelsA vector of CAD models file name (one file per link)
worldThe ODE world used by the manipulator
Rtw0The offset transformation of the robot base
robotfilenameThe file with the kinematics and dynamics parameters
basemodelThe filename of the CAD file for the base
qinitThe initial joint angles
osaODEManipulator::osaODEManipulator ( const std::vector< std::string > &  models,
osaODEWorld world,
const vctFrm3 Rtw0,
const std::string &  robotfilename,
const std::string &  basemodel,
const vctDynamicVector< double > &  qinit 
)

ODE Manipulator constructor.

This constructor initializes an ODE manipulator with the kinematics and dynamics contained in a file. Plus it initializes the ODE elements of the manipulators (bodies and joints) for the engine.

Parameters
modelsA vector of CAD models file name (one file per link)
worldThe ODE world used by the manipulator
Rtw0The offset transformation of the robot base
robotfilenameThe file with the kinematics and dynamics parameters
basemodelThe filename of the CAD file for the base
qinitThe initial joint angles
osaODEManipulator::osaODEManipulator ( const std::vector< std::string > &  models,
osaODEWorld world,
const vctFrame4x4< double > &  Rtw0,
const std::string &  robotfilename,
osaODEBody base,
const vctDynamicVector< double > &  qinit 
)

ODE Manipulator constructor.

This constructor initializes an ODE manipulator with the kinematics and dynamics contained in a file. Plus it initializes the ODE elements of the manipulators (bodies and joints) for the engine.

Parameters
modelsA vector of CAD models file name (one file per link)
worldThe ODE world used by the manipulator
Rtw0The offset transformation of the robot base
robotfilenameThe file with the kinematics and dynamics parameters
baseA ODE body used for the base
qinitThe initial joint angles
osaODEManipulator::osaODEManipulator ( const std::vector< std::string > &  models,
osaODEWorld world,
const vctFrm3 Rtw0,
const std::string &  robotfilename,
osaODEBody base,
const vctDynamicVector< double > &  qinit 
)

ODE Manipulator constructor.

This constructor initializes an ODE manipulator with the kinematics and dynamics contained in a file. Plus it initializes the ODE elements of the manipulators (bodies and joints) for the engine.

Parameters
modelsA vector of CAD models file name (one file per link)
worldThe ODE world used by the manipulator
Rtw0The offset transformation of the robot base
robotfilenameThe file with the kinematics and dynamics parameters
baseA ODE body used for the base
qinitThe initial joint angles
osaODEManipulator::~osaODEManipulator ( )
inline

Member Function Documentation

virtual void osaODEManipulator::Attach ( osaOSGManipulator osgtool)
virtual

Attach a tool to the robot.

This attaches manipulator to the end-effector. This essentially create a joint between the end-effector and the tool but that joint has 0 angles of rotation.

Parameters
toolA pointer to a robot tool
void osaODEManipulator::Disable ( )

Disable all the bodies of the manipulator.

void osaODEManipulator::Enable ( )

Enable all the bodies of the manipulator.

virtual vctFrame4x4<double> osaODEManipulator::ForwardKinematics ( const vctDynamicVector< double > &  q,
int  N = -1 
) const
virtual

Evaluate the forward kinematics.

Compute the position and orientation of each link wrt to the world frame

Parameters
input]q The vector of joint positions
input]N The link number (0 => base, negative => end-effector)
Returns
The position and orientation, as a 4x4 frame

Reimplemented from robManipulator.

void osaODEManipulator::ForwardKinematics ( const vctDynamicVector< double > &  q,
vctFrm3 Rt,
int  N = -1 
) const
dBodyID osaODEManipulator::GetBaseID ( ) const

Return the base ID of the manipulator.

This returns the ODE body ID of the base of the robt. This is mostly used for attaching the robot to anothher body.

virtual osaODEManipulator::Errno osaODEManipulator::GetPositions ( vctDynamicVector< double > &  q) const
virtual

Return the joints positions.

Query each ODE joint and return the joint positions

Parameters
qA vector of joint positions
Returns
ESUCCESS if not error. EFAILURE otherwise.

Reimplemented from osaOSGManipulator.

virtual osaODEManipulator::State osaODEManipulator::GetState ( ) const
virtual

Return the state of the robot.

For an ODE manipulator, the state of a manipulator is defined by the position/orientation and the velocity of each link. It is not defined by the position/velocity of each joint. This method queries each link of the robot for its state (position/orientation + angular/linear velocities) and return them in a vector.

Returns
A vector containing the state of each link.
virtual osaODEManipulator::Errno osaODEManipulator::GetVelocities ( vctDynamicVector< double > &  qd) const
virtual

Return the joints velocities.

Query each ODE joint and return the joint velocities

Parameters
qdA vector of joint velocities
Returns
ESUCCESS if not error. EFAILURE otherwise.
osaODEWorld* osaODEManipulator::GetWorld ( ) const
inlineprotected

Return the world ID.

dWorldID osaODEManipulator::GetWorldID ( ) const
inlineprotected
void osaODEManipulator::Insert ( osaODEBody body)
protected

Insert a body in the manipulator.

void osaODEManipulator::Insert ( osaODEJoint joint)
protected

Insert a joint in the manipulator.

void osaODEManipulator::Insert ( osaODEServoMotor servo)
protected

Insert a joint in the manipulator.

virtual osaODEManipulator::Errno osaODEManipulator::SetForcesTorques ( const vctDynamicVector< double > &  ft)
virtual

Set the joint forces or torques.

This sets the force/torque value of each joint. This method does NOT apply the FT right away. The FT will be applied at the next iteration of the world.

Parameters
ftA vector of joint forces/torques
virtual osaODEManipulator::Errno osaODEManipulator::SetPositions ( const vctDynamicVector< double > &  qs)
virtual

Set the joint position.

This sets the position command of ODE (internal) servo motors. This does not instantly changes the position. The position values are used to set the velocity of the ODE servo motors.

Parameters
qsA vector of joint positions
Returns
ESUCCESS if not error. EFAILURE otherwise.

Reimplemented from osaOSGManipulator.

virtual void osaODEManipulator::SetState ( const osaODEManipulator::State state)
virtual

Set the state of the robot.

For an ODE manipulator, the state of a manipulator is defined by the position/orientation and the velocity of each link. It is not defined by the position/velocity of each joint. This method set the state of each link of the robot: (position/orientation + angular/linear velocities) and return them in a vector.

virtual osaODEManipulator::Errno osaODEManipulator::SetVelocities ( const vctDynamicVector< double > &  qds)
virtual

Set the joint velocity.

This sets the velocity command of ODE (internal) servo motors. This does not instantly changes the velocity. The velocity values are used to set the velocity of the ODE servo motors.

Parameters
qsdA vector of joint velocities
Returns
ESUCCESS if not error. EFAILURE otherwise.

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