ERC CISST - cisst software

robManipulator Class Reference

Inheritance diagram for robManipulator:

Inheritance graph
[legend]
Collaboration diagram for robManipulator:

Collaboration graph
[legend]
List of all members.

Detailed Description

Definition at line 26 of file robManipulator.h.

Public Types

Public Member Functions

Public Attributes

Protected Attributes


Constructor & Destructor Documentation

robManipulator::robManipulator ( const std::string &  robotfilename,
const vctFrame4x4< double > &  Rtw0 = vctFrame4x4< double >() 
)

This constructor initializes a manipulator with the kinematics and dynamics contained in a file.

Parameters:
robotfilename The file with the kinematics and dynamics parameters
Rtw0 The offset transformation of the robot base


Member Function Documentation

void robManipulator::JacobianBody ( const vctDynamicVector< double > &  q  )  const

Evaluates the geometric body Jacobian.

This implements the algorithm of Paul, Shimano, Mayer (SMC81)

void robManipulator::JacobianSpatial ( const vctDynamicVector< double > &  q  )  const

Evaluate the geometric spatial Jacobian.

Warning:
To evaluate the spatial Jacobian you must first evaluate the body Jacobia

vctDynamicVector<double> robManipulator::RNE ( const vctDynamicVector< double > &  q,
const vctDynamicVector< double > &  qd,
const vctDynamicVector< double > &  qdd,
const vctFixedSizeVector< double, 6 > &  f,
double  g = 9.81 
) const

Evaluate the inverse dynamics through RNE.

The joints positions, velocities and accelerations must be set before calling this method. It returns a vector of forces/torques that realize the desired state.

Parameters:
q The joints positions
qd The joints velocities
qdd The joints accelerations
fext An external force/moment acting on the tool control point
g The gravity acceleration

vctDynamicVector<double> robManipulator::CCG ( const vctDynamicVector< double > &  q,
const vctDynamicVector< double > &  qd 
) const

Evaluate the coriolis/centrifugal and gravitational forces acting on the manipulator.

The joints positions, velocities and accelerations must be set before calling this method. It returns a vector of forces/torques that realize the given positions and accelerations. This method is akin to calling RNE without the joints accelerations

vctFixedSizeVector<double,6> robManipulator::Acceleration ( const vctDynamicVector< double > &  q,
const vctDynamicVector< double > &  qd,
const vctDynamicVector< double > &  qdd 
) const

Compute the linear and angular accelerations of the last link.

This is akin to compute the forward recursion of the RNE.

vctFixedSizeVector<double,6> robManipulator::BiasAcceleration ( const vctDynamicVector< double > &  q,
const vctDynamicVector< double > &  qd 
) const

The bias acceleration is the 6D vector Jdqd that is used to evaluate the inverse dynamics in operations space.

This vector is derived from d (J qd) / dt = Jdqd + J qdd

void robManipulator::JSinertia ( double **  A,
const vctDynamicVector< double > &  q 
) const

Parameters:
input] A A pointer to an NxN matrix

Parameters:
output] A The NxN manipulator inertia matrix

void robManipulator::OSinertia ( double  Ac[6][6],
const vctDynamicVector< double > &  q 
) const

Parameters:
input] A A pointer to an 6x6 matrix

Parameters:
output] The 6x6 manipulator inertia matrix in operation space

virtual robManipulator::Errno robManipulator::InverseKinematics ( vctDynamicVector< double > &  q,
const vctFrame4x4< double > &  Rts,
double  tolerance = 1e-12,
size_t  Niteration = 1000 
) [virtual]

Compute the inverse kinematics.

The solution is computed with from Newton's algorithm.

Parameters:
input] q An initial guess of the solution
output] q The inverse kinematics solution
Rts The desired position and orientation of the tool control point
tolerance The error tolerance of the solution
Niteration The maximum number of iteration allowed to find asolution
Returns:
SUCCESS if a solution was found within the given tolerance and number of iterations. ERROR otherwise.

virtual vctDynamicVector<double> robManipulator::InverseDynamics ( const vctDynamicVector< double > &  q,
const vctDynamicVector< double > &  qd,
const vctDynamicVector< double > &  qdd 
) const [virtual]

Compute and return the inverse dynamics of the manipulator in joint space.

InverseDynamics returns the joint torques that corresponds to a manipulator with the given the joints positions, velocities and accelerations.

Parameters:
q A vector of joints positions
qd A vector of joints velocities
qdd A vector of joints accelerations
Returns:
A vector of joints torques

virtual vctDynamicVector<double> robManipulator::InverseDynamics ( const vctDynamicVector< double > &  q,
const vctDynamicVector< double > &  qd,
const vctFixedSizeVector< double, 6 > &  vdwd 
) const [virtual]

Compute and return the inverse dynamics of the manipulator in operation space.

InverseDynamics returns the joint torques that corresponds to a manipulator with the given the joints positions, velocities and the tool control point (TCP) accelerations. The reason why joints positions and velocities are given instead of the position and velocity of the TCP is that the coriolis, centrifugal and gravitational forces are uniquely determined by the joints positions and velocties.

Parameters:
q A vector of joints positions
qd A vector of joints velocities
vdwd A 6D vector of the TCP linear and angular accelerations
Returns:
A vector of joints torques


The documentation for this class was generated from the following file:
erc-cisst-devel<at>lists.johnshopkins.edu