In file /home/blah/darwin2k/src/d2k/ctrl/path.h: A base class for cartesian-space trajectories.
Inheritance:
Public Fields
-
int pathNum
- the group of paths to which the path belongs.
-
int endPtNum
- the index of the end effector that should follow the path
-
int reachedStart
- indicates whether the robot has reached the first point on the the path yet
-
int reachedEnd
- indicates whether the robot has reached the last point on the the path yet
-
int usePayload
- indicates whether a payload should be moved along the path
-
payload* pl
- the payload (if any) being moved along the path
-
int useAppliedForce
- indicates whether the end effector should apply a force and and torque as it moves along the path
-
triple toolForce
- the force (if useAppliedForce is 1) to apply along the path
-
triple toolTorque
- the torque (if useAppliedForce is 1) to apply along the path
-
endPointRec* endPt
- a pointer to the end effector (if any) currently following the path
-
const char* payloadLabel
- the label for the payload (if any) to be moved along the path
-
int payloadConnectorID
- the ID of the connector on the payload that should be connected to the tool's TCP
-
int alignPayload
- indicates whether the payload's connector should be aligned to the tool's TCP before attaching it.
Public Methods
-
~genericPath(void)
- destructor
-
virtual void getStartPoint(triple &t, quaternion &q) = 0
- returns the pose of the first point on the path
-
virtual vector computeVel(double dt, quaternion* outputFrame = NULL) = 0
- computes a velocity command for the end effector.
-
virtual void reset(void)
- resets the path state
-
virtual int atStart(void)
- returns 1 if the end effector has reached the first point on the path
-
virtual int done(void)
- returns 1 if the end effector has reached the last point on the path
-
virtual double completion(void)
- returns a number between 0 and 1 indicating the fraction of the the path that has been completed
-
virtual triple computeCrossTrackError(triple &pos) = 0
- returns the current cross-track error of the given position
-
virtual triple computeOrientationError(quaternion &q) = 0
- returns the current orientation error of the given orientation
Public Fields
-
d2kSimulator* sim
-
configuration* cfg
-
const char* label
-
int active
Public Methods
-
virtual int minCfgs(void) const
-
virtual int maxCfgs(void) const
-
virtual const char* getCfgName(int i)
-
virtual int readParams(paramParser* parser)
-
virtual int setVariables(const ptrList* taskParamRecs)
-
virtual int simInit(d2kSimulator* Sim)
-
virtual int init(ptrList* Cfgs)
-
virtual int forceCfgResolution(void)
-
virtual int cleanup(void)
-
virtual int update(int &violated)
-
virtual const cfgLabelRecord* getLabelRec(int i) const
Public Fields
-
static int staticClassID
-
int objectID
-
int verboseLevel
Public Methods
-
virtual const char* className(void) const
-
virtual synObject* copy(void) const
-
virtual int isOfType(int typeNum, int derivedOk)
-
static int setStaticClassID(void)
-
virtual int classID(void) const
Documentation
A base class for cartesian-space trajectories.
File variables
- int endPtNum required
- int pathNum required
- int verboseLevel = 1;
- int usePayload = 0;
- int payloadConnectorID (required if usePayload = 1)
- int alignPayload (required if usePayload = 1)
- int payloadLabel (required if usePayload = 1)
- int payloadConnectorID (required if usePayload = 1)
- int useAppliedForce = 0;
- triple toolForce = 0; (only used if useAppliedForce = 1)
- triple toolTorque = 0; (only used if useAppliedForce = 1)
int pathNum
- the group of paths to which the path belongs. This is used
by the pathEvaluator to group paths together if they should
be simultaneously followed by multiple end effectors
int endPtNum
- the index of the end effector that should follow the path
int reachedStart
- indicates whether the robot has reached the first point on the
the path yet
int reachedEnd
- indicates whether the robot has reached the last point on the
the path yet
int usePayload
- indicates whether a payload should be moved along the path
payload* pl
- the payload (if any) being moved along the path
int useAppliedForce
- indicates whether the end effector should apply a force and
and torque as it moves along the path
triple toolForce
- the force (if useAppliedForce is 1) to apply along the path
triple toolTorque
- the torque (if useAppliedForce is 1) to apply along the path
endPointRec* endPt
- a pointer to the end effector (if any) currently following the path
const char* payloadLabel
- the label for the payload (if any) to be moved along the path
int payloadConnectorID
- the ID of the connector on the payload that should be connected
to the tool's TCP
int alignPayload
- indicates whether the payload's connector should be aligned to the
tool's TCP before attaching it.
~genericPath(void)
- destructor
virtual void getStartPoint(triple &t, quaternion &q) = 0
- returns the pose of the first point on the path
virtual vector computeVel(double dt, quaternion* outputFrame = NULL) = 0
- computes a velocity command for the end effector. If outputFrame
is non-NULL, then the velocity will be transformed by it.
virtual void reset(void)
- resets the path state
virtual int atStart(void)
- returns 1 if the end effector has reached the first point on the path
virtual int done(void)
- returns 1 if the end effector has reached the last point on the path
virtual double completion(void)
- returns a number between 0 and 1 indicating the fraction of the
the path that has been completed
virtual triple computeCrossTrackError(triple &pos) = 0
- returns the current cross-track error of the given position
virtual triple computeOrientationError(quaternion &q) = 0
- returns the current orientation error of the given orientation
- Direct child classes:
- path
Alphabetic index HTML hierarchy of classes or Java
This page was generated with the help of DOC++.