javax.robotics.engine.controllers
Interface EndEffController

All Superinterfaces:
Controller
All Known Implementing Classes:
GravityCompensation, ResolvedRateAcceleration

public interface EndEffController
extends Controller

Interface for different schemes of robot end effector position and orientation controller.

Since:
1.0.0
Version:
7/10/2005
Author:
Carmine Lia

Method Summary
 RVector3d getOrientationError()
          Gets the current orientation error.
 RVector3d getPositionError()
          Gets the position error.
 RVector torqueCmd(RVector3d pdpp, RVector3d pdp, RVector3d pd)
          Sets the output torque for a desired end effector: acceleration, velocity, position.
 RVector torqueCmd(RVector3d pdpp, RVector3d pdp, RVector3d pd, RVector3d wdp, RVector3d wd, Quaternion quatd)
          Sets the output torque for a desired end effector: acceleration, velocity, position, angular acceleration, angular velocity, angular position.
 
Methods inherited from interface javax.robotics.engine.controllers.Controller
getID, getRobotID
 

Method Detail

getPositionError

RVector3d getPositionError()
Gets the position error.

Returns:
the position error vector.

getOrientationError

RVector3d getOrientationError()
Gets the current orientation error. The error is computed form quaternion as:

η(q)&epsilond - &etad&epsilon(q) - S(&epsilond)&epsilon(q)

where η and ε are the vector and the scalar components of quaternion respectively.

Returns:
the orientation error vector.

torqueCmd

RVector torqueCmd(RVector3d pdpp,
                  RVector3d pdp,
                  RVector3d pd,
                  RVector3d wdp,
                  RVector3d wd,
                  Quaternion quatd)
Sets the output torque for a desired end effector: acceleration, velocity, position, angular acceleration, angular velocity, angular position.

Parameters:
pdpp - desired acceleration
pdp - desired velocity
pd - desired position
wdp - desired angular acceleration
wd - desired angular velocity
quatd - desired vector angular position: quaternion (s,v1,v2,v3)
Returns:
the output torque

torqueCmd

RVector torqueCmd(RVector3d pdpp,
                  RVector3d pdp,
                  RVector3d pd)
Sets the output torque for a desired end effector: acceleration, velocity, position.

Parameters:
pdpp - desired acceleration
pdp - desired velocity
pd - desired position
Returns:
the output torque