In file /home/blah/darwin2k/src/d2k/ctrl/path.h:

class path

cartesian-space velocities that are fixed in space.

Inheritance:


Public Fields

[more]int np
number of points in the path
[more]int currentPt
the most recently-reached point on the path
[more]int targetPt
the point that the end effector is currently headed towards
[more]double targetDist
distance to target point
[more]int useSameTol
use same tolerances for each point?
[more]double* tol
the position tolerance for each waypoint.
[more]double* vTol
the velocity tolerance for each waypoint.
[more]double* angleTol
the angular tolerance for each waypoint.
[more]double vel
desired linear velocity
[more]double omega
desired angular velocity
[more]double maxAcc
maximum linear acceleration
[more]double maxOmegaDot
maximum angular acceleration
[more]triple* waypt
an array of waypoint positions
[more]quaternion* orientation
an array of waypont orientations
[more]int* stopAtPoint
an array indicating whether the end effector should stop at each waypoint (ie.

Public Methods

[more]virtual int setVariables(const ptrList* taskParams)
sets path-specific variables from a list of task parameters.
[more]virtual int getTargetPoint(const triple &pos, const quaternion &q, triple &targetPos, quaternion &targetQ)
returns the target position and orientation given an end effector pose
[more]virtual void getPoint(int i, triple &pos, quaternion &q)
returns the world-space pose of the i'th waypoint
[more]virtual void modifyEndpointPoseAndPath(triple &pos, quaternion &q, triple &tpos, quaternion &tq)
a hook to allow derived classes to modify the pose of the point returned by getPoint
[more]virtual void modifyVelocityCommand(triple &v, triple &omega)
a hook to allow derived classes to modify the velocity command computed by computeVel()
[more]virtual void setNumPoints(int n, int useSameTol)
resizes the arrays for storing path information.


Inherited from genericPath:

Public Fields

oint pathNum
oint endPtNum
oint reachedStart
oint reachedEnd
oint usePayload
opayload* pl
oint useAppliedForce
otriple toolForce
otriple toolTorque
oendPointRec* endPt
oconst char* payloadLabel
oint payloadConnectorID
oint alignPayload

Public Methods

ovirtual void getStartPoint(triple &t, quaternion &q)
ovirtual vector computeVel(double dt, quaternion* outputFrame = NULL)
ovirtual void reset(void)
ovirtual int atStart(void)
ovirtual int done(void)
ovirtual double completion(void)
ovirtual triple computeCrossTrackError(triple &pos)
ovirtual triple computeOrientationError(quaternion &q)


Inherited from d2kComponent:

Public Fields

od2kSimulator* sim
oconfiguration* cfg
oconst char* label
oint active

Public Methods

ovirtual int minCfgs(void) const
ovirtual int maxCfgs(void) const
ovirtual const char* getCfgName(int i)
ovirtual int readParams(paramParser* parser)
ovirtual int simInit(d2kSimulator* Sim)
ovirtual int init(ptrList* Cfgs)
ovirtual int forceCfgResolution(void)
ovirtual int cleanup(void)
ovirtual int update(int &violated)
ovirtual const cfgLabelRecord* getLabelRec(int i) const


Inherited from synObject:

Public Fields

ostatic int staticClassID
oint objectID
oint verboseLevel

Public Methods

ovirtual const char* className(void) const
ovirtual synObject* copy(void) const
ovirtual int isOfType(int typeNum, int derivedOk)
ostatic int setStaticClassID(void)
ovirtual int classID(void) const


Documentation

cartesian-space velocities that are fixed in space. The path is represented as a series of waypoints, each of which consists of a world-space position and orientation. The path will generate cartesian-space velocity commands that sequentially move the end effector towards each waypoint. Once the effector is with a certain distance of a waypoint (determined by the tol member), the next waypoint is pursued. Waypoints can either be stopped at or moved through, depending on whether stopAtPoint[i] is 0 or 1.

Cartesian-space PID control is used to compute angular and linear acceleration commands that follow a trapezoidal velocity profile. The PID gains are computed internally from maxVel, maxAcc, maxOmega, and maxOmegaDot; these can be read from a p-file, or can be specified by task parameters. When performing synthesis, it is best to include these four values as task parameters, since they have a significant impact on robot performance.

File variables

If readPath is 1, then pathFilename should specify a relative or absolute path (in the filesystem sense) to a path file. The path file contains np waypoint records, each in the following format:
oint np
number of points in the path

oint currentPt
the most recently-reached point on the path

oint targetPt
the point that the end effector is currently headed towards

odouble targetDist
distance to target point

oint useSameTol
use same tolerances for each point?

odouble* tol
the position tolerance for each waypoint. If useSameTol is 1, then tol points to a single double, which is used as the tolerance for all waypoints. If useSameTol is 0, then tol points to an array of np doubles specifying tolerances for each waypoint.

odouble* vTol
the velocity tolerance for each waypoint. If a point should be stopped at, then vtol determines how slowly the end effector should be moving to be considered motionless. If useSameTol is 1, then vTol points to a single double, which is used as the tolerance for all waypoints. If useSameTol is 0, then vTol points to an array of np doubles specifying tolerances for each waypoint.

odouble* angleTol
the angular tolerance for each waypoint. If useSameTol is 1, then tol points to a single double, which is used as the tolerance for all waypoints. If useSameTol is 0, then tol points to an array of np doubles specifying tolerances for each waypoint.

odouble vel
desired linear velocity

odouble omega
desired angular velocity

odouble maxAcc
maximum linear acceleration

odouble maxOmegaDot
maximum angular acceleration

otriple* waypt
an array of waypoint positions

oquaternion* orientation
an array of waypont orientations

oint* stopAtPoint
an array indicating whether the end effector should stop at each waypoint (ie. decelerate to zero velocity) or move through without decelerating. vTol determines how slowly the effector must be moving to be considered stopped.

ovirtual int setVariables(const ptrList* taskParams)
sets path-specific variables from a list of task parameters. The variables used by this function are: See the member documentation for more information on these variables. It is highly recommended that you included these variables as task parameters when doing synthesis, since they have a significant impact on the robot's ability to accurately follow the path

ovirtual int getTargetPoint(const triple &pos, const quaternion &q, triple &targetPos, quaternion &targetQ)
returns the target position and orientation given an end effector pose

ovirtual void getPoint(int i, triple &pos, quaternion &q)
returns the world-space pose of the i'th waypoint

ovirtual void modifyEndpointPoseAndPath(triple &pos, quaternion &q, triple &tpos, quaternion &tq)
a hook to allow derived classes to modify the pose of the point returned by getPoint

ovirtual void modifyVelocityCommand(triple &v, triple &omega)
a hook to allow derived classes to modify the velocity command computed by computeVel()

ovirtual void setNumPoints(int n, int useSameTol)
resizes the arrays for storing path information. NOTE: this does not preserve existing path data.


Direct child classes:
relativePath

Alphabetic index HTML hierarchy of classes or Java



This page was generated with the help of DOC++.