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

#include <osaGLUTManipulator.h>

Inheritance diagram for osaGLUTManipulator:
robManipulator

Public Member Functions

 osaGLUTManipulator (const std::vector< std::string > &geomfiles, const vctFrame4x4< double > &Rtw0, const std::string &robotfn, const vctDoubleVec &qinit, const std::string &basefile, bool rotateX90=false)
 GLUT Manipulator generic constructor. More...
 
 osaGLUTManipulator (const std::vector< std::string > &geomfiles, const vctFrm3 &Rtw0, const std::string &robotfn, const vctDoubleVec &qinit, const std::string &basefile, bool rotateX90=false)
 GLUT Manipulator generic constructor. More...
 
 ~osaGLUTManipulator ()
 
void Initialize (const std::vector< std::string > &geomfiles, const std::string &basefile, bool rotateX90)
 
virtual bool GetPositions (vctDoubleVec &q) const
 Return the joints positions. More...
 
virtual bool SetPositions (const vctDoubleVec &q)
 Set the joint position. More...
 
- 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...
 

Protected Attributes

vctDoubleVec q
 Store the current joints values. More...
 
osaMeshTriangular * base
 
std::vector< osaMeshTriangular * > meshes
 
- Protected Attributes inherited from robManipulator
std::vector< robManipulator * > tools
 A vector of tools. 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...
 

Constructor & Destructor Documentation

osaGLUTManipulator::osaGLUTManipulator ( const std::vector< std::string > &  geomfiles,
const vctFrame4x4< double > &  Rtw0,
const std::string &  robotfn,
const vctDoubleVec qinit,
const std::string &  basefile,
bool  rotateX90 = false 
)

GLUT Manipulator generic constructor.

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

Parameters
geomfilesA vector of 3D model file names
Rtw0The offset transformation of the robot base
robotfnThe file with the kinematics and dynamics parameters
qinitThe initial joint angles
basefileThe file name of the base 3D model
osaGLUTManipulator::osaGLUTManipulator ( const std::vector< std::string > &  geomfiles,
const vctFrm3 Rtw0,
const std::string &  robotfn,
const vctDoubleVec qinit,
const std::string &  basefile,
bool  rotateX90 = false 
)

GLUT Manipulator generic constructor.

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

Parameters
geomfilesA vector of 3D model file names
Rtw0The offset transformation of the robot base
robotfnThe file with the kinematics and dynamics parameters
qinitThe initial joint angles
basefileThe file name of the base 3D model
osaGLUTManipulator::~osaGLUTManipulator ( )

Member Function Documentation

virtual bool osaGLUTManipulator::GetPositions ( vctDoubleVec q) const
virtual

Return the joints positions.

Query each joint and return the joint positions

Parameters
q[in]A vector of joints positions
Returns
true if successfull. false otherwise.
void osaGLUTManipulator::Initialize ( const std::vector< std::string > &  geomfiles,
const std::string &  basefile,
bool  rotateX90 
)
virtual bool osaGLUTManipulator::SetPositions ( const vctDoubleVec q)
virtual

Set the joint position.

This sets the position command and stores a local copy

Parameters
qA vector of joint positions
Returns
true if successfull. false otherwise.

Member Data Documentation

osaMeshTriangular* osaGLUTManipulator::base
protected
std::vector< osaMeshTriangular* > osaGLUTManipulator::meshes
protected
vctDoubleVec osaGLUTManipulator::q
protected

Store the current joints values.


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