AURobotServers  4
Public Member Functions | Public Attributes | Protected Member Functions | List of all members
UPose Class Reference

#include <upose.h>

Inheritance diagram for UPose:
Inheritance graph

Public Member Functions

void add (double dist, double headingChange)
 
void add (double ix, double iy, double ih)
 
UMatrix4 asCol3 ()
 
UMatrix4 asCol4 ()
 
UMatrix4 asMatrix2x2MtoP ()
 
UMatrix4 asMatrix2x2PtoM ()
 
UMatrix4 asMatrix3x3MtoP ()
 
UMatrix4 asMatrix3x3PtoM ()
 
UMatrix4 asMatrix4x4MtoP ()
 
UMatrix4 asMatrix4x4PtoM ()
 
UMatrix4 asMatrix4x4PtoMPos ()
 
UMatrix4 asRow3 ()
 
UMatrix4 asRow4 ()
 
virtual void clear ()
 
virtual const char * codeXml (char *buf, const int bufCnt, const char *extraAttr)
 
virtual const char * codeXml (const char *name, char *buf, const int bufCnt, const char *extraAttr)
 
void fprint (FILE *fd, const char *prestring)
 
char * getAsSml (const char *name, char *buff, int buffCnt)
 
virtual const char * getDataType ()
 
double getDistance (UPose other)
 
double getDistance (UPose *other)
 
double getDistance (UPosition other)
 
double getDistance (UPosition *other)
 
double getDistToPoseLine (const double Px, const double Py)
 
double getDistToPoseLineSigned (const double Px, const double Py)
 
double getHeadingDeg ()
 
double getHeadingDiff (UPose other)
 
double getHeadingRad ()
 
UPosition getMapToPose (UPosition mapPos)
 
U2Dpos getMapToPose (U2Dpos mapPos)
 
UPosition getMapToPose (UPose *mapPos)
 
UPosition getMapToPose (UPose mapPos)
 
CvPoint getMapToPose (CvPoint mapPos)
 
UPose getMapToPosePose (UPose *mapPose)
 
UPose getMapToPosePose (UPose mapPose)
 
UPosition getPos (double z=0.0)
 
UPosition getPoseToMap (UPosition posePos)
 
U2Dpos getPoseToMap (U2Dpos posePos)
 
UPosition getPoseToMap (double localX, double localY)
 
UPosition getPoseToMap (UPose posePos)
 
CvPoint getPoseToMap (CvPoint mapPos)
 
UPose getPoseToMapPose (UPose poseLocal)
 
UPose getPoseToMapPose (double x, double y, double h)
 
UPose neg ()
 
UPose operator+ (UPose pDelta)
 
UPose operator+ (UPoseV pDelta)
 
UPose operator+ (UPoseTime pDelta)
 
UPose operator+ (UPoseTVQ pDelta)
 
UPose operator- (UPose pRef)
 
UPose operator- (UPoseV pRef)
 
UPose operator- (UPoseTime pRef)
 
UPose operator- (UPoseTVQ pRef)
 
UPose operator= (UPoseTime source)
 
UPose operator= (UPoseV source)
 
UPose operator= (UPoseTVQ source)
 
UPose operator= (UMatrix4 mat)
 
void print (char *buf, const char *prestring, int bufLng)
 
void print (const char *str)
 
void set (UPosition *pos, URotation *rot)
 
void set (double ix, double iy, double ih)
 
UPose set (UMatrix *mat)
 
virtual void snprint (const char *preString, char *buff, const int buffCnt)
 
 UPose ()
 
 UPose (double x, double y, double h)
 
 UPose (UPose *source)
 
 UPose (UPosition *pos, URotation *rot)
 
virtual ~UPose ()
 
- Public Member Functions inherited from UDataBase
bool isA (const char *typeString)
 
virtual bool isAlsoA (const char *typeString)
 
 UDataBase ()
 
virtual ~UDataBase ()
 

Public Attributes

double h
 
double x
 
double y
 

Protected Member Functions

UPose addCed (UPose D)
 
UPose addCed (UPose *D)
 
void addDeltaPose (UPose D)
 
void asAddC (UPose Vbase, UPose D)
 
void asNegC (UPose D)
 
void asSubC (UPose Va, UPose Vbase)
 
void subC (UPose *Vbase)
 
UPose subCed (UPose Vbase)
 
UPose subCed (UPose *Vbase)
 

Detailed Description

Position for a Robot and functions related to such function.
The main thing is the data in format [x,y,Theta]

Author
Christian Andersen

Constructor & Destructor Documentation

UPose::UPose ( )

Constructor

UPose::UPose ( double  x,
double  y,
double  h 
)

Constructor with initial value

References h, x, and y.

UPose::UPose ( UPose source)

Constructor, tahe data from other object

UPose::UPose ( UPosition pos,
URotation rot 
)

Set from 3D position (in robot coordiantes,
3D.x is forward, 3D.y is left, 3D.z is up (ignored).
3D.Omega is tilt -left +right (ignored), 3D.Phi is nose -up +down (ignored) 3D.Kappa is turn -right +left (heading).

References h, URotation::Kappa, UPosition::x, x, UPosition::y, and y.

virtual UPose::~UPose ( )
inlinevirtual

Destructor

Member Function Documentation

void UPose::add ( double  dist,
double  headingChange 
)

Advance the pose 'dist' distance with an heading change over the distance of 'headingChange'.

References h, limitToPi(), x, and y.

Referenced by ULaserMeasurement::clear(), clear(), UAvoidPath2::createMidPathPoints(), UAvoidPath2::crossTangent(), UFakeMap::fakeAdvanceControl(), UAvoidPath2::outherTangent(), and UResGps::updateVars().

void UPose::add ( double  ix,
double  iy,
double  ih 
)

Add this increment to present pose

References h, limitToPi(), x, and y.

UPose UPose::addCed ( UPose  D)
inlineprotected

References asSubC(), and subC().

Referenced by UPoseV::operator+(), operator+(), and UPoseTVQ::operator+().

UPose UPose::addCed ( UPose D)
protected

References asAddC().

void UPose::addDeltaPose ( UPose  D)
protected

Referenced by operator=().

void UPose::asAddC ( UPose  Vbase,
UPose  D 
)
protected

Compounding operation Va = Vbase o+ D, where Va, Vbase and are all poses and D is the movement from Vb to Va in Vb local coordinates, whereas Va and Vbase are in "global" coordinates. Va = [xa, ya, ha] Vbase = [xb, yb , hb] D = [x, y, h]. xa = xb + x cos(hb) - y sin(hb); ya = yb + x sin(hb) + y cos(hb); ha = hb + h; Returns the new pose Va. (from Lu and Milios (1997))

References h, limitToPi(), x, and y.

Referenced by addCed(), and operator=().

UMatrix4 UPose::asCol3 ( )

pose as [x,y,h] column.

References h, UMatrix::set(), x, and y.

Referenced by getDistToPoseLine().

UMatrix4 UPose::asCol4 ( )

pose as homogenous [x,y,h,1] column.

References h, UMatrix::set(), x, and y.

Referenced by getDistToPoseLine(), and testPoseMatrix().

UMatrix4 UPose::asMatrix2x2MtoP ( )

Get rotation matrix when converting from map (or global) coordinates to local pose coordinates.
R = [cos(h) sin(h); -sin(h) cos(h)].

References h, and UMatrix::setRow().

Referenced by getDistToPoseLine().

UMatrix4 UPose::asMatrix2x2PtoM ( )

Get rotation matrix when converting from local (pose) coordinates to map or global coordinates.
R = [cos(h) -sin(h); sin(h) cos(h)].

References h, and UMatrix::setRow().

Referenced by getDistToPoseLine().

UMatrix4 UPose::asMatrix3x3MtoP ( )

Get this pose as a transformation matrix of size 3x3, that converts 2D positions in homogeous coordinates (x,y,1) in map coordinates to local 2D coordinates in the coordinate system of this pose.
intended use (x', y', w) = this * (x,y,1)'
where resulting (x,y) = (x'/w, y'/w); This may be a faster method when converting many points and if through many transformations.

Returns
a UMatrix4 (openCV matrix packed into UMatrix)

References h, UMatrix::setRow(), x, and y.

Referenced by getDistToPoseLine(), and testPoseMatrix().

UMatrix4 UPose::asMatrix3x3PtoM ( )

Get this pose as a transformation matrix of size 3x3, that converts 2D positions in homogeous coordinates (x,y,1) in local coordinates at this pose to 2D coordinates in the coordinate system in which this pose is defined (a more global coordinate system, often called map or global).
intended use (x', y', w) = this * (x,y,1)'
where resulting (x,y) = (x'/w, y'/w); This may be a faster method when converting many points and if through many transformations.

Returns
a UMatrix4 (openCV matrix packed into UMatrix)

References h, UMatrix::setRow(), x, and y.

Referenced by getDistToPoseLine(), and testPoseMatrix().

UMatrix4 UPose::asMatrix4x4MtoP ( )

Get this pose as a transformation matrix of size 4x4, that converts a pose in homogeous coordinates (x,y,h,1) in map coordinates to a pose in local coordinates of this pose.
intended use (x', y', h',1) = this * (x,y,h,1)'
to result (x', y', h'); This may be a faster method when converting many points and if through many transformations.

Returns
a UMatrix4 (openCV matrix packed into UMatrix)

References h, UMatrix::setRow(), x, and y.

Referenced by getDistToPoseLine(), and testPoseMatrix().

UMatrix4 UPose::asMatrix4x4PtoM ( )

Get this pose as a transformation matrix of size 4x4, that converts a pose in homogeous coordinates (x,y,h,1) in local coordinates at this pose to a pose in the coordinate system in which this pose is defined (a more global coordinate system, often called map or global).
intended use (x', y', h',1) = this * (x,y,h,1)'
for result (x',y',h'); This may be a faster method when converting many points and if through many transformations.

Returns
a UMatrix4 (openCV matrix packed into UMatrix)

References h, UMatrix::setRow(), x, and y.

Referenced by getDistToPoseLine(), testPoseMatrix(), and UPaintPcp::update().

UMatrix4 UPose::asMatrix4x4PtoMPos ( )

Get this pose as a transformation matrix of size 4x4 for use to convert 3D positions in local coordinates into to the more global system, where this pose is defined (z posiition is left s is)

Returns
a UMatrix4 (openCV matrix packed into UMatrix)

References h, UMatrix::setRow(), x, and y.

Referenced by UNamedBoxes::addBox(), UNamedBoxes::doDetect(), getDistToPoseLine(), UPaintLaserScan::makeScanCloud(), and UPaintPcp::update().

void UPose::asNegC ( UPose  D)
protected

Reverse the relative pose D, so that it reverses the change from Vbase to Va Returns [0,0,0] o- D, or -D = subc([0,0,0], D);

References asSubC().

Referenced by neg(), and subCed().

UMatrix4 UPose::asRow3 ( )

pose as [x,y,h] row.

References h, UMatrix::set(), x, and y.

Referenced by getDistToPoseLine().

UMatrix4 UPose::asRow4 ( )

pose as homogenous [x,y,h,1] row.

References h, UMatrix::set(), x, and y.

Referenced by getDistToPoseLine().

void UPose::asSubC ( UPose  Va,
UPose  Vbase 
)
protected

Inverse compounding operation calculating the pose change from Vbase to Va, i.e. D = Va o- Vb. Va = [xa, ya, ha] Vbase = [xb, yb , hb] D = [x, y, h]. x = (xa - xb)cos(hb) + (ya - yb)sin(hb); y = -(xa - xb)sin(hb) + (ya - yb)cos(hb); h = ha - hb; Returns the inverse compound pose. (from Lu and Milios (1997))

References h, limitToPi(), x, and y.

Referenced by addCed(), asNegC(), subC(), and subCed().

virtual void UPose::clear ( void  )
inlinevirtual
const char * UPose::codeXml ( char *  buf,
const int  bufCnt,
const char *  extraAttr 
)
virtual

Code this structure in XML format. The open tag includes any additional XML attributes from the codeXmlAttributes function call

Parameters
bufis the character buffer where the attributes are stored
bufCntis the amount of buffer space allocated
extraAttris an optional extra set of attributes, pre-coded as form "name=\"value" name=...".
Returns
a pointer to the buffer

Reimplemented in UPoseTime.

References buf, h, x, and y.

Referenced by codeXml(), UPoseTime::codeXml(), UResAvoid::codeXmlRobotFront(), operator+(), UPoseTime::operator=(), and UFunctionAvoid::sendCurrentAvoidPath().

const char * UPose::codeXml ( const char *  name,
char *  buf,
const int  bufCnt,
const char *  extraAttr 
)
virtual

Code this structure in XML format. The open tag includes any additional XML attributes from the codeXmlAttributes function call

Parameters
nameoptional extra name value for a name attribute.
bufis the character buffer where the attributes are stored
bufCntis the amount of buffer space allocated
extraAttris an optional extra set of attributes, pre-coded as form "name=\"value" name=...".
Returns
a pointer to the buffer

References codeXml().

void UPose::fprint ( FILE *  fd,
const char *  prestring 
)

Print pose in single line to console, with the provided prestring in front of data.

References getHeadingDeg(), x, and y.

Referenced by clear(), UPoseTime::fprint(), UPoseTime::getPose(), testManDistance(), testManToSeg(), testPose(), testPoseCoordinateTransfer(), and testPoseToPose().

char * UPose::getAsSml ( const char *  name,
char *  buff,
int  buffCnt 
)

Code the pose in XML-like format. The name string is added as a name attribute.

Todo:
This is deprecated, use codeXml()

References h, x, and y.

Referenced by operator+(), and USmlTag::sendProbPoly().

virtual const char* UPose::getDataType ( )
inlinevirtual

Get (end) type of this structure

Reimplemented from UDataBase.

Reimplemented in UPoseTVQ, UPoseTime, and UPoseV.

Referenced by UFunctionVarPool::initCallReturnStructType().

double UPose::getDistance ( UPose  other)
inline
double UPose::getDistance ( UPose other)
inline

Get distance to another pose.

References x, and y.

double UPose::getDistance ( UPosition  other)
inline

Get distance to another position (XY-part only).

References UPosition::x, and UPosition::y.

double UPose::getDistance ( UPosition other)
inline

Get distance to another position (XY-part only).

References UPosition::x, and UPosition::y.

double UPose::getDistToPoseLine ( const double  Px,
const double  Py 
)
inline

Get distance to line described by this line

Parameters
Px,Pyis the position to be evaluated
Returns
the distance

References asCol3(), asCol4(), asMatrix2x2MtoP(), asMatrix2x2PtoM(), asMatrix3x3MtoP(), asMatrix3x3PtoM(), asMatrix4x4MtoP(), asMatrix4x4PtoM(), asMatrix4x4PtoMPos(), asRow3(), asRow4(), and getDistToPoseLineSigned().

Referenced by UResSmrCtl::run().

double UPose::getDistToPoseLineSigned ( const double  Px,
const double  Py 
)

Get distance to line described by this line (signed)

Parameters
Px,Pyis the position to be evaluated
Returns
the signed distance (left is positive)

References h, x, and y.

Referenced by getDistToPoseLine(), operator+(), and testPoseDist().

double UPose::getHeadingDeg ( )

Returns heading in 0-360 degree range.

References h, and limitToPi().

Referenced by fprint(), UPoseV::fprint(), Funcavoid::handleCommand(), print(), snprint(), UPoseV::snprint(), and UPoseTVQ::snprint().

double UPose::getHeadingDiff ( UPose  other)
inline

Get heading difference to another pose. I.e. how much angle should I add th this heading to get the other (return limitToPi(other.h - h)).

References getMapToPose(), getPoseToMap(), h, limitToPi(), and neg().

Referenced by UPoseHistNotUsed::addIfNeeded(), and UResPoseHist::addIfNeeded().

double UPose::getHeadingRad ( )
inline

Returns heading in radians.

References h.

UPosition UPose::getMapToPose ( UPosition  mapPos)

Convert this map position to local pose coordinates. This is done by translating map coordinates to pose position followed by rotation to pose-heading.

References h, UPosition::x, x, UPosition::y, y, and UPosition::z.

Referenced by ULineMatch::addToPoly(), UAvoidPath2::avoidToTheLeft(), UAvoidPath2::createMidPathPoints(), UClientFuncLaserGui::doImage(), UAvoidPath2::findRoutes(), ULaserPi::get2DDistToCross(), UManPPSeq::getDistanceXYSigned(), getHeadingDiff(), getMapToPose(), getMapToPosePose(), UImgPolyProj::getMapToRob(), UImgProj::getMapToRob(), UManPPSeq::getMinDistanceXYSigned(), UResMapObst::getNearObstacles(), getPoseToMapPose(), UAvoidPath2::isAfterDestination(), UProbPoly::moveToPose(), UNavPaint::paintFeatures(), UNavView::paintFeatures(), UNavPaint::paintFreePoly(), UClientFuncLaserGui::paintFreePoly(), UNavView::paintFreePoly(), UResObj3d::paintGndPlane(), UNavPaint::paintHistScan(), UClientFuncLaserGui::paintHistScan(), UClientFuncLaserGui::paintLineSegments(), UNavPaint::paintManData(), UNavPaint::paintObstGrp(), UClientFuncLaserGui::paintObstGrp(), UNavView::paintObstGrp(), UClientFuncLaserGui::paintOdoData(), UNavPaint::paintOdoGrid(), UClientFuncLaserGui::paintOdoGrid(), UClientFuncLaserGui::paintPathData(), UNavPaint::paintPis(), UClientFuncLaserGui::paintPis(), UNavView::paintPis(), UNavPaint::paintPoseHistLine(), UClientFuncLaserGui::paintPostHistLine(), UNavPaint::paintRoadLine(), UClientFuncLaserGui::paintWpListData(), UResLocater::rowEndDetect(), UAvoidPath2::setPreStopPoint(), testPoseCoordinateTransfer(), testPoseMatrix(), UNavPaint::toPixels(), and UAvoidParams::withinRobotOutline().

U2Dpos UPose::getMapToPose ( U2Dpos  mapPos)

Convert this map position to local pose coordinates. This is done by translating map coordinates to pose position followed by rotation to pose-heading.

References h, U2Dpos::x, x, U2Dpos::y, and y.

UPosition UPose::getMapToPose ( UPose mapPos)

Convert this map pose (x,y part) to local pose coordinates. This is done by translating map coordinates to pose position followed by rotation to pose-heading. See also getMapToPosePose(UPose * mapPose)

References h, UPosition::x, x, UPosition::y, y, and UPosition::z.

UPosition UPose::getMapToPose ( UPose  mapPos)
inline
CvPoint UPose::getMapToPose ( CvPoint  mapPos)

Convert this position to local value (used in UClient)

References h, roundi(), x, and y.

UPose UPose::getMapToPosePose ( UPose mapPose)
UPose UPose::getMapToPosePose ( UPose  mapPose)
inline
UPosition UPose::getPos ( double  z = 0.0)
inline
UPosition UPose::getPoseToMap ( UPosition  posePos)

Convert this local position coordinate to map (global) coordinates. The z value is maintained

References h, UPosition::x, x, UPosition::y, y, and UPosition::z.

Referenced by UPaintBase::addBox(), UObstacleGroupLaser::addObst(), UObj3dPool::addObstacle(), UPaintPolygon::addPolyToViewer(), ULineMatch::addToPoly(), UAvoidPath2::createMidPathPoints(), Funcavoid::direkte(), UResRoadDrive::findExitPose(), UFuncCropRow::findPlants(), UManLine::getFoodprintPolygon(), UManArc::getFoodprintPolygon(), getHeadingDiff(), UAvoidPath2::getManAsPolygon(), UManPPSeq::getMinDistanceXYSigned(), UResMapObst::getNearObstacles(), UImgPolyProj::getRobToMap(), UImgProj::getRobToMap(), UFuncObj3d::handleCommand(), UFuncCropRow::handleCommand(), UFunctionPassable::handleObstGet(), Funcavoid::korrigerHuller(), UFuncBall::makeDisplayPolygon(), UFuncImSeg::makeDisplayPolygon(), UPaintPolygon::makePolyCloud(), UResLocater::match_points(), USFData::moveLocalToMap(), UFeatureData::moveLocalToOdo(), UProbPoly::moveToMap(), ULaserObst::moveToMap(), ULaserPi::moveToMap(), UNavView::paint(), UNavPaint::paintFeatures(), UNavView::paintFeatures(), UNavPaint::paintHistScan(), UClientFuncLaserGui::paintHistScan(), UNavPaint::paintManData(), UNavPaint::paintObstGrp(), UNavView::paintObstGrp(), UClientFuncLaserGui::paintPathData(), UProbPoly::paintRobot(), UObstaclePool::pointsToPolygon(), UResLobst::sendAsObstacles(), UAvoidPath2::setClosestPoint(), UAvoidPath2::setPreStopPoint(), testPoseCoordinateTransfer(), testPoseMatrix(), UNavPaint::toPixels(), UFuncStraightLine::toRobot(), UFuncStraightLine::toWorld(), and UResRoadLine::updateRoadVariables().

U2Dpos UPose::getPoseToMap ( U2Dpos  posePos)

Convert this local position coordinate to map (global) coordinates.

References h, U2Dpos::x, x, U2Dpos::y, and y.

UPosition UPose::getPoseToMap ( double  localX,
double  localY 
)

Convert this local position coordinate to map (global) coordinates.

References h, UPosition::x, x, UPosition::y, y, and UPosition::z.

UPosition UPose::getPoseToMap ( UPose  posePos)

Convert this local pose position coordinate to map (global) coordinates.

References h, UPosition::x, x, UPosition::y, y, and UPosition::z.

CvPoint UPose::getPoseToMap ( CvPoint  mapPos)

Convert this local pose position coordinate to map (global) coordinates. The pose is assumed to be in pixel coordinates. the function takes and returns pixel coordinates. Used if a known local position is first scaled to pixel size and the function is then used to get the correct pixel position.

References h, roundi(), x, and y.

UPose UPose::getPoseToMapPose ( UPose  poseLocal)
UPose UPose::getPoseToMapPose ( double  x,
double  y,
double  h 
)
inline

Convert this local pose position coordinate to map (global) coordinates. This is done by rotating with the heading and translating with the pose position. See also getMapToPosePose(UPose * mapPose)

References a, getMapToPose(), and getPoseToMapPose().

UPose UPose::neg ( )

Save data in html-like format. Returns true if saved Load a pose from this xml-class. Returns true if read. Reports format error to xml-class. Negate this delta pose.

References asNegC().

Referenced by getHeadingDiff(), and testPose().

UPose UPose::operator+ ( UPose  pDelta)
inline

Add a delta pose to a base pose to get a new pose. The delta pose must be in base pose perspective. i.e. To get from a reference position P1 to a new position P2 after a movement of 'pDelta'

References addCed(), buf, codeXml(), getAsSml(), and getDistToPoseLineSigned().

Referenced by UPoseTVQ::operator-(), and UPoseTVQ::operator=().

UPose UPose::operator+ ( UPoseV  pDelta)

References addCed().

UPose UPose::operator+ ( UPoseTime  pDelta)

References addCed().

UPose UPose::operator+ ( UPoseTVQ  pDelta)

References addCed().

UPose UPose::operator- ( UPose  pRef)
inline

Subtract 2 poses to get a delta pose from ref to base. i.e. if P1 and P2 is two poses, and deltaPose Pd = P2 - P1, then P2 is at position Pd in local P1 coordinates, and P2 = P1 + Pd

References subCed().

Referenced by UPoseTVQ::clear().

UPose UPose::operator- ( UPoseV  pRef)

References subCed().

UPose UPose::operator- ( UPoseTime  pRef)

References subCed().

UPose UPose::operator- ( UPoseTVQ  pRef)

References subCed().

UPose UPose::operator= ( UPoseTime  source)

get a pose from a pose-time object

References h, x, and y.

Referenced by clear(), and UPoseTime::operator=().

UPose UPose::operator= ( UPoseV  source)

get a pose from a pose-velocity object

References h, x, and y.

UPose UPose::operator= ( UPoseTVQ  source)

get a pose from a pose-velocity object

References h, x, and y.

UPose UPose::operator= ( UMatrix4  mat)
inline

Assignment operator from matrix

References addDeltaPose(), and asAddC().

void UPose::print ( char *  buf,
const char *  prestring,
int  bufLng 
)
inline

Print pose in single line to a string buffer of length 'bufLng', with the provided prestring in front of data. Deprecated call - use snprint(...).

References snprint().

Referenced by UFuncCropRow::handleCommand(), UProbPoly::print(), testManDistance(), testManLineToSeg(), and testPoseMatrix().

void UPose::print ( const char *  str)
inline

Print pose in single line to a string buffer of length 'bufLng', with the provided prestring in front of data.

References getHeadingDeg(), and snprint().

void UPose::set ( UPosition pos,
URotation rot 
)

Set from 3D position (in robot coordiantes,
3D.x is forward, 3D.y is left, 3D.z is up.
3D.Omega is tilt -left +right, 3D.Phi is nose -up +down 3D.Kappa is turn -right +left.

References h, URotation::Kappa, UPosition::x, x, UPosition::y, and y.

Referenced by UResRoadDrive::findExitPose(), UManLine::getDistanceXYSigned(), UManArc::getDistanceXYSigned(), UImgPolyProj::getImageName(), UImgProj::getImageName(), UManLine::getMinDistanceXYSigned(), UManArc::getMinDistanceXYSigned(), UResMapObst::getNearObstacles(), UVariable::getPose(), UPoseHistNotUsed::getPoseFitAtDistance(), UResPoseHist::getPoseFitAtDistance(), UVariable::getPoseTime(), UManLine::getPoseV(), UFunctionCamPath::getRobotPose(), UResSmrCtl::getSMRCLDrive2cmd(), UFunctionAvoid::handleAvoid(), UFunctionAvoid::handlePoseToPose(), UResLocater::locate(), UResLocater::match_points(), UResMapObst::methodCall(), UResAvoid::methodCall(), UResRuleState::methodCallV(), UImgPolyProj::paintPath(), UImgProj::paintPath(), UClientFuncLaserGui::paintPathData(), UNavPaint::paintPoseHistLine(), UFunctionAvoid::sendCurrentAvoidPath(), USmrCl::setDriveState(), UPlannerValue::setFromTag(), UAvoidPath2::setMidPoint(), UProbPoly::setPoseNow(), UProbPoly::setPoseOrg(), UImgProj::setRobPose(), UImgPolyProj::setRobPose(), UImgProj::setStartPose(), UImgPolyProj::setStartPose(), UAvoidPath2::setTurnCentre(), testManPoly(), testPoseDist(), testPoseMatrix(), UImgPolyProj::UImgPolyProj(), UImgProj::UImgProj(), UNavPaint::UNavPaint(), UResV360::update(), and UV360Scan::UV360Scan().

void UPose::set ( double  ix,
double  iy,
double  ih 
)

Set value from these data

References h, x, and y.

UPose UPose::set ( UMatrix mat)

Set pose from matrix (column or row vector).

Parameters
matis a pointer to the matrix.
Returns
this pose.

References UMatrix::get(), h, UMatrix::size(), x, and y.

void UPose::snprint ( const char *  preString,
char *  buff,
const int  buffCnt 
)
virtual

Print status for this structure into a string

Reimplemented from UDataBase.

Reimplemented in UPoseTVQ, UPoseTime, and UPoseV.

References getHeadingDeg(), x, and y.

Referenced by UPoseTime::getPose(), print(), UPoseTVQ::print(), and UPoseTime::snprint().

void UPose::subC ( UPose Vbase)
protected

References asSubC().

Referenced by addCed().

UPose UPose::subCed ( UPose  Vbase)
inlineprotected
UPose UPose::subCed ( UPose Vbase)
protected

References asSubC().

Member Data Documentation

double UPose::h

heading (Theta) zero in x direction and positive towards y. That is right hand coordinates with z pointing up.

Referenced by add(), UPaintBase::addBox(), UPaintBase::addCircleCloud(), UResPoseHist::addIfNeeded(), UAvoidPath2::addLnksToOpenSet(), UResPoseHist::addPoseHist(), UAvoidPath2::addToLnkSeqs(), asAddC(), asCol3(), asCol4(), asMatrix2x2MtoP(), asMatrix2x2PtoM(), asMatrix3x3MtoP(), asMatrix3x3PtoM(), asMatrix4x4MtoP(), asMatrix4x4PtoM(), asMatrix4x4PtoMPos(), asRow3(), asRow4(), asSubC(), UReactivePath::avoidObst(), UAvoidPath2::avoidToTheLeft(), ULaserMeasurement::clear(), UPoseTime::clear(), USmlTag::codePose(), USmlTag::codePoseV(), UPolyItem::codeXML(), codeXml(), UAvoidPath2::convertToManSeq(), UAvoidPath2::createMidPathPoints(), UAvoidPath2::createPointList(), UAvoidPath2::crossTangent(), UClientFuncLaserGui::doImage(), UResLocater::doLocatorUpdates(), UResDrivePos::driveOdo(), UResRoadDrive::driveSide(), UResSmrIf::eventGpsUpdate(), UResSmrIf::eventPoseUpdated(), UManSeq::expandAddManALA(), UManSeq::expandAddManLALA(), UAvoidPath2::expandOmegaTurn(), UAvoidPath2::extendManoeuvre(), extract_control(), UFakeMap::fakeAdvanceControl(), UFakeMap::fakeAdvancePose(), UAvoidCellGraph::findBestCellPath(), Funcavoid::findDrej(), UResRoadDrive::findExitPose(), UPlannerData::findPose(), UAvoidPath2::findRoutes(), UAvoidPath2::findRoutesA(), UResRoseBot::findRows(), UFuncTracking::FirstImage(), UPoseV::fprint(), UPose2pose::get22arcLeft(), UPose2pose::get2arcQ4(), UPose2pose::get2LeftLineLeft(), UPose2pose::get2LeftLineRight(), UPose2pose::get2line(), UPose2pose::get2lineStartLeft(), UPose2pose::get2RightLineLeft(), UPose2pose::get2RightLineRight(), UPose2pose::get2ViaBreakLeftLineLeft(), UPose2pose::get2ViaBreakLeftLineRight(), UPose2pose::get2ViaBreakRightLineLeft(), UPose2pose::get2ViaBreakRightLineRight(), getAsSml(), UResDrivePos::getCurrentPose(), UManSeq::getDistanceFromEndPoseLine(), UManArc::getDistanceXYSigned(), getDistToPoseLineSigned(), UManArc::getEndPose(), getHeadingDeg(), getHeadingDiff(), getHeadingRad(), UPoseHistNotUsed::getHistHeading(), UResPoseHist::getHistHeading(), getMapToPose(), getMapToPosePose(), UReactivePath::getMidPoseHere(), UManArc::getMinDistanceXYSigned(), USmlTag::getPose(), UPoseTime::getPose(), UPoseTime::getPoseAtTime(), getPoseToMap(), getPoseToMapPose(), USmlTag::getPoseV(), UPoseTVQ::getPoseV(), USmlTag::getProbPoly(), UManLine::getSMRCLcmd2(), UManArc::getSMRCLcmd2(), UResSmrCtl::getSMRCLDrive2cmd(), UReactivePath::getTangentMidPose(), UManArc::getTurnCentre(), UFunctionAvoid::handleAvoid(), Funcavoid::handleCommand(), UFuncRoseBot::handleCommand(), UFuncCropRow::handleCommand(), UFunctionDrivePos::handleDrivePos(), UClientFuncLaser::handleEkf(), UFuncPlan::handleFindRoute(), UResLaserIfScan::handleLaserScan(), UClientFuncLaser::handleLaserScan(), UFuncLocalize::handleLocalize(), UFuncLoca2::handleLocalize(), UFuncLocalize::handleLocalizeMHF(), UFuncLocalize::handleLocalizeUKF(), UResPoly::handleNewData(), UClientFuncLaser::handleOdo(), UClientFuncLaser::handlePath(), UFunctionPoseHist::handlePoseHistCommand(), UFunctionAvoid::handlePoseToPose(), UFuncV360::handleV360Command(), UClientFuncLaser::handleWpf(), UAvoidPath2::insertNewPointAfter(), interpolatePoses(), UFunctionPoseHist::listPoses(), UResLocater::locate(), USmrOdoState::logState(), UResLocater::match_points(), UResAvoid::methodCall(), UResPoseHist::methodCall(), UResLobst::methodCallV(), UResAvoid::methodCallV(), UResRuleState::methodCallV(), UNavPaint::mousePan(), UProbPoly::moveToPose(), UPoseV::operator=(), operator=(), UPose2pose::operator=(), UPoseTime::operator=(), UPoseTVQ::operator=(), UAvoidPath2::outherTangent(), UClientFuncLaserGui::paintEkfData(), UNavPaint::paintManData(), UClientFuncLaserGui::paintOdoData(), UNavPaint::paintOdoDataText(), UNavView::paintOdoDataText(), UClientFuncLaserGui::paintOdoDest(), UImgPolyProj::paintPath(), UImgProj::paintPath(), UClientFuncLaserGui::paintPathData(), UAvoidPath2::pointTangent(), USmrOdoState::print(), UFakeDevice::print(), UResV360::print(), UAvoidPoint::printPoses(), UNavPaint::printRefSystems(), UNavView::printRefSystems(), UReplayDevice::replayStep(), UPoseHistNotUsed::replayStep(), UResPoseHist::replayStep(), UFuncPpl::robotToOdoCooTransf(), UResLocater::rowEndDetect(), UResSmrCtl::run(), UPoseHistNotUsed::saveToLog(), UResPoseHist::saveToLog(), UFuncEfLine::sendBoxPose(), UResSmrCtl::sendNewManoeuvreToSMR(), set(), UPoseTVQ::set(), UResLocater::set_state(), UResLocater::set_utmstate(), USmrCl::setDriveState(), ULaserPathResult::setFromTag(), UResVarPool::setLocalVarPose(), UVarPool::setLocalVarPose(), UAvoidPath2::setMidPoint(), URoadLine::setNew(), UVariable::setPose(), UAvoidPath2::setPreStopPoint(), UPoseTime::setPt(), UFuncView::setRobotPose(), UReactivePath::setRouteStats(), UResRoadDrive::setTarget(), UResLaserIfScan::snprint(), UPoseV::snprint(), UPoseTVQ::snprint(), testDriveonEst(), UFuncLobst::testMethodCall(), testPose2Pose(), testPoseDist(), UFuncTracking::TrackObjects(), UV360Scan::update(), UResRoadLine::update(), updateDisplacement(), UFuncLoca2::updateDisplacement(), UResGps::updateVars(), UResAuEf::updateWalls(), UPose(), and UResLocater::varprint().

double UPose::x

x position (forward or east)

Referenced by add(), UPaintBase::addCircleCloud(), UPaintBase::addCylinder(), UResPoseHist::addIfNeeded(), UResPoseHist::addPoseHist(), UAvoidPath2::addStartAndExit(), UPaintBase::addWheel(), asAddC(), asCol3(), asCol4(), asMatrix3x3MtoP(), asMatrix3x3PtoM(), asMatrix4x4MtoP(), asMatrix4x4PtoM(), asMatrix4x4PtoMPos(), asRow3(), asRow4(), asSubC(), UReactivePath::avoidObst(), UAvoidPath2::avoidToTheLeft(), UFuncPpl::calculateVars(), ULaserMeasurement::clear(), UPoseTime::clear(), USmlTag::codePose(), USmlTag::codePoseV(), UPolyItem::codeXML(), codeXml(), UAvoidPath2::convertToManSeq(), UFakeMap::copyToPoly(), UAvoidPath2::createCellBasedPointList(), UAvoidPath2::createMidPathPoints(), UAvoidPath2::crossTangent(), Funcavoid::direkte(), UClientFuncLaserGui::doImage(), UResLocater::doLocatorUpdates(), UResDrivePos::driveOdo(), UResRoadDrive::driveSide(), UResSmrIf::eventGpsUpdate(), UResSmrIf::eventPoseUpdated(), UManSeq::expandAddManALA(), UManSeq::expandAddManLALA(), UManSeq::expandManDriveon(), UAvoidPath2::expandOmegaTurn(), extract_control(), UFakeMap::fakeAdvanceControl(), UAvoidCellGraph::findBestCellPath(), UAvoidCellGraph::findCell(), UAvoidCellGraph::findCellPath(), UAvoidCellGraph::findCellPointPath(), UResRoadLine::findCurrentRoad(), UResRoadLine::findCurrentRoad2(), Funcavoid::findDrej(), Funcavoid::findDrejEfter(), UResRoadDrive::findExitPose(), UAvoidPath2::findObstAvoidRoute(), UFuncCropRow::findPlants(), UPlannerData::findPose(), UResRoseBot::findRows(), UFuncTracking::FirstImage(), fprint(), UPoseV::fprint(), UPose2pose::get22arcLeft(), UPose2pose::get2arcQ4(), UPose2pose::get2LeftLineLeft(), UPose2pose::get2LeftLineRight(), UPose2pose::get2line(), UPose2pose::get2lineStartLeft(), UPose2pose::get2RightLineLeft(), UPose2pose::get2RightLineRight(), UPose2pose::get2ViaBreakLeftLineLeft(), UPose2pose::get2ViaBreakLeftLineRight(), UPose2pose::get2ViaBreakRightLineLeft(), UPose2pose::get2ViaBreakRightLineRight(), getAsSml(), UAvoidPath2::getClosestObst2(), UResDrivePos::getCurrentPose(), getDistance(), UManSeq::getDistanceFromEndPoseLine(), UManArc::getDistanceXYSigned(), UManSeq::getDistanceXYSigned(), getDistToPoseLineSigned(), UManPPSeq::getEndDistTo(), UManArc::getEndPose(), UPoseHistNotUsed::getHistHeading(), UResPoseHist::getHistHeading(), UPaintBase::getInViewedCoordinates(), UAvoidPath2::getManAsPolygon(), getMapToPose(), getMapToPosePose(), UReactivePath::getMidPoseHere(), UManLine::getMinDistanceXYSigned(), UManArc::getMinDistanceXYSigned(), UManSeq::getMinDistanceXYSigned(), UResMapObst::getNearObstacles(), UObj3dPool::getObstGrp(), UObstaclePool::getObstGrp(), USmlTag::getPose(), UPoseTime::getPose(), UPoseTime::getPoseAtTime(), UPoseHistNotUsed::getPoseFitAtDistance(), UResPoseHist::getPoseFitAtDistance(), UPoseHistNotUsed::getPoseNearDistance(), UResPoseHist::getPoseNearDistance(), getPoseToMap(), getPoseToMapPose(), USmlTag::getPoseV(), UPoseTVQ::getPoseV(), USmlTag::getProbPoly(), UManLine::getSMRCLcmd2(), UManArc::getSMRCLcmd2(), UResSmrCtl::getSMRCLDrive2cmd(), UManPPSeq::getStartDistTo(), UReactivePath::getTangentMidPose(), UManArc::getTurnCentre(), UFunctionAvoid::handleAvoid(), Funcavoid::handleCommand(), UFunctionDisp::handleCommand(), UFuncRoseBot::handleCommand(), UFuncCropRow::handleCommand(), UFunctionDrivePos::handleDrivePos(), UClientFuncLaser::handleEkf(), UFuncPlan::handleFindRoute(), UResLaserIfScan::handleLaserScan(), UClientFuncLaser::handleLaserScan(), UFuncLocalize::handleLocalize(), UFuncLoca2::handleLocalize(), UFuncLocalize::handleLocalizeMHF(), UFuncLocalize::handleLocalizeUKF(), UResPoly::handleNewData(), UClientFuncLaser::handleOdo(), UClientFuncLaser::handlePath(), UFunctionPoseHist::handlePoseHistCommand(), UFunctionAvoid::handlePoseToPose(), UFunctionLaser::handleScanGetCommand(), UFuncV360::handleV360Command(), UClientFuncLaser::handleWpf(), UFuncLinefinder::houghTest(), UAvoidPath2::insertNewPointAfter(), interpolatePoses(), UFunctionPoseHist::listPoses(), UResLocater::locate(), USmrOdoState::logState(), UPaintPolygon::makePolyCloud(), UResLocater::match_points(), UResPoseHist::methodCall(), UResLobst::methodCallV(), UResAvoid::methodCallV(), UResPoly::methodCallV(), UResRuleState::methodCallV(), UNavPaint::mousePan(), UProbPoly::moveToPose(), UPoseV::operator=(), operator=(), UPose2pose::operator=(), UPoseTime::operator=(), UPoseTVQ::operator=(), UAvoidPath2::outherTangent(), UNavPaint::paint(), UNavView::paint(), UPaintPoseHist::paint(), UClientFuncLaserGui::paintEkfData(), UImgPolyProj::paintGrid(), UImgProj::paintGrid(), UNavPaint::paintManData(), UClientFuncLaserGui::paintOdoData(), UNavPaint::paintOdoDataText(), UNavView::paintOdoDataText(), UClientFuncLaserGui::paintOdoDest(), UNavPaint::paintOdoGrid(), UClientFuncLaserGui::paintOdoGrid(), UNavView::paintOdoGrid(), UImgProj::paintPath(), UImgPolyProj::paintPath(), UClientFuncLaserGui::paintPathData(), UAvoidPath2::pointTangent(), USmrOdoState::print(), UFakeDevice::print(), UResV360::print(), UAvoidPoint::printPoses(), UNavPaint::printRefSystems(), UNavView::printRefSystems(), UReplayDevice::replayStep(), UPoseHistNotUsed::replayStep(), UResPoseHist::replayStep(), UFuncPpl::robotToOdoCooTransf(), UResLocater::rowEndDetect(), UResSmrCtl::run(), UPoseHistNotUsed::saveToLog(), UResPoseHist::saveToLog(), UFuncEfLine::sendBoxPose(), UResSmrCtl::sendNewManoeuvreToSMR(), set(), UPoseTVQ::set(), UResLocater::set_state(), UResLocater::set_utmstate(), ULaserPathResult::setFromTag(), UResVarPool::setLocalVarPose(), UVarPool::setLocalVarPose(), UAvoidPath2::setMidPoint(), UVariable::setPose(), UResPoseHist::setPoseResult(), UAvoidPath2::setPreStopPoint(), UPoseTime::setPt(), UFuncView::setRobotPose(), UReactivePath::setRouteStats(), UResRoadDrive::setTarget(), UResLaserIfScan::snprint(), snprint(), UPoseV::snprint(), UPoseTVQ::snprint(), testDriveonEst(), UFuncLobst::testMethodCall(), testPose2Pose(), testPoseDist(), UNavPaint::toPixels(), UFuncStraightLine::toRobot(), UFuncStraightLine::toWorld(), UFuncTracking::TrackObjects(), UAvoidPath2::turnCentreCrossing(), Funcavoid::undersoeg(), UV360Scan::update(), UResRoadLine::update(), updateDisplacement(), UFuncLoca2::updateDisplacement(), UResGps::updateVars(), UResAuEf::updateWalls(), UPose(), UAvoidPath2::validNewClosePoint(), and UResLocater::varprint().

double UPose::y

y position (left or north)

Referenced by add(), UPaintBase::addCircleCloud(), UPaintBase::addCylinder(), UResPoseHist::addIfNeeded(), UResPoseHist::addPoseHist(), UAvoidPath2::addStartAndExit(), UPaintBase::addWheel(), asAddC(), asCol3(), asCol4(), asMatrix3x3MtoP(), asMatrix3x3PtoM(), asMatrix4x4MtoP(), asMatrix4x4PtoM(), asMatrix4x4PtoMPos(), asRow3(), asRow4(), asSubC(), UReactivePath::avoidObst(), UAvoidPath2::avoidToTheLeft(), UFuncPpl::calculateVars(), ULaserMeasurement::clear(), UPoseTime::clear(), USmlTag::codePose(), USmlTag::codePoseV(), UPolyItem::codeXML(), codeXml(), UAvoidPath2::convertToManSeq(), UFakeMap::copyToPoly(), UAvoidPath2::createCellBasedPointList(), UAvoidPath2::createMidPathPoints(), UAvoidPath2::crossTangent(), Funcavoid::direkte(), UClientFuncLaserGui::doImage(), UResLocater::doLocatorUpdates(), UResDrivePos::driveOdo(), UResRoadDrive::driveSide(), UResSmrIf::eventGpsUpdate(), UResSmrIf::eventPoseUpdated(), UManSeq::expandAddManALA(), UManSeq::expandAddManLALA(), UManSeq::expandManDriveon(), UAvoidPath2::expandOmegaTurn(), extract_control(), UFakeMap::fakeAdvanceControl(), UAvoidCellGraph::findBestCellPath(), UAvoidCellGraph::findCell(), UAvoidCellGraph::findCellPath(), UAvoidCellGraph::findCellPointPath(), UResRoadLine::findCurrentRoad(), UResRoadLine::findCurrentRoad2(), Funcavoid::findDrej(), Funcavoid::findDrejEfter(), UResRoadDrive::findExitPose(), UAvoidPath2::findObstAvoidRoute(), UFuncCropRow::findPlants(), UPlannerData::findPose(), UResRoseBot::findRows(), UFuncTracking::FirstImage(), fprint(), UPoseV::fprint(), UPose2pose::get22arcLeft(), UPose2pose::get2arcQ4(), UPose2pose::get2LeftLineLeft(), UPose2pose::get2LeftLineRight(), UPose2pose::get2line(), UPose2pose::get2lineStartLeft(), UPose2pose::get2RightLineLeft(), UPose2pose::get2RightLineRight(), UPose2pose::get2ViaBreakLeftLineLeft(), UPose2pose::get2ViaBreakLeftLineRight(), UPose2pose::get2ViaBreakRightLineLeft(), UPose2pose::get2ViaBreakRightLineRight(), getAsSml(), UAvoidPath2::getClosestObst2(), UResDrivePos::getCurrentPose(), getDistance(), UManSeq::getDistanceFromEndPoseLine(), UManArc::getDistanceXYSigned(), UManSeq::getDistanceXYSigned(), getDistToPoseLineSigned(), UManPPSeq::getEndDistTo(), UManArc::getEndPose(), UPoseHistNotUsed::getHistHeading(), UResPoseHist::getHistHeading(), UPaintBase::getInViewedCoordinates(), UAvoidPath2::getManAsPolygon(), getMapToPose(), getMapToPosePose(), UReactivePath::getMidPoseHere(), UManArc::getMinDistanceXYSigned(), UManSeq::getMinDistanceXYSigned(), UResMapObst::getNearObstacles(), UObj3dPool::getObstGrp(), UObstaclePool::getObstGrp(), USmlTag::getPose(), UPoseTime::getPose(), UPoseTime::getPoseAtTime(), UPoseHistNotUsed::getPoseFitAtDistance(), UResPoseHist::getPoseFitAtDistance(), UPoseHistNotUsed::getPoseNearDistance(), UResPoseHist::getPoseNearDistance(), getPoseToMap(), getPoseToMapPose(), USmlTag::getPoseV(), UPoseTVQ::getPoseV(), USmlTag::getProbPoly(), UManLine::getSMRCLcmd2(), UManArc::getSMRCLcmd2(), UResSmrCtl::getSMRCLDrive2cmd(), UManPPSeq::getStartDistTo(), UReactivePath::getTangentMidPose(), UManArc::getTurnCentre(), UFunctionAvoid::handleAvoid(), Funcavoid::handleCommand(), UFunctionDisp::handleCommand(), UFuncRoseBot::handleCommand(), UFuncCropRow::handleCommand(), UFunctionDrivePos::handleDrivePos(), UClientFuncLaser::handleEkf(), UFuncPlan::handleFindRoute(), UResLaserIfScan::handleLaserScan(), UClientFuncLaser::handleLaserScan(), UFuncLocalize::handleLocalize(), UFuncLoca2::handleLocalize(), UFuncLocalize::handleLocalizeMHF(), UFuncLocalize::handleLocalizeUKF(), UResPoly::handleNewData(), UClientFuncLaser::handleOdo(), UClientFuncLaser::handlePath(), UFunctionPoseHist::handlePoseHistCommand(), UFunctionAvoid::handlePoseToPose(), UFunctionLaser::handleScanGetCommand(), UFuncV360::handleV360Command(), UClientFuncLaser::handleWpf(), UFuncLinefinder::houghTest(), UAvoidPath2::insertNewPointAfter(), interpolatePoses(), UFunctionPoseHist::listPoses(), UResLocater::locate(), USmrOdoState::logState(), UPaintPolygon::makePolyCloud(), UResLocater::match_points(), UResPoseHist::methodCall(), UResLobst::methodCallV(), UResAvoid::methodCallV(), UResPoly::methodCallV(), UResRuleState::methodCallV(), UNavPaint::mousePan(), UProbPoly::moveToPose(), UPoseV::operator=(), operator=(), UPose2pose::operator=(), UPoseTime::operator=(), UPoseTVQ::operator=(), UAvoidPath2::outherTangent(), UNavPaint::paint(), UNavView::paint(), UPaintPoseHist::paint(), UClientFuncLaserGui::paintEkfData(), UImgProj::paintGrid(), UImgPolyProj::paintGrid(), UNavPaint::paintManData(), UClientFuncLaserGui::paintOdoData(), UNavPaint::paintOdoDataText(), UNavView::paintOdoDataText(), UClientFuncLaserGui::paintOdoDest(), UNavPaint::paintOdoGrid(), UClientFuncLaserGui::paintOdoGrid(), UNavView::paintOdoGrid(), UImgPolyProj::paintPath(), UImgProj::paintPath(), UClientFuncLaserGui::paintPathData(), UAvoidPath2::pointTangent(), USmrOdoState::print(), UFakeDevice::print(), UResV360::print(), UAvoidPoint::printPoses(), UNavPaint::printRefSystems(), UNavView::printRefSystems(), UReplayDevice::replayStep(), UPoseHistNotUsed::replayStep(), UResPoseHist::replayStep(), UFuncPpl::robotToOdoCooTransf(), UResLocater::rowEndDetect(), UResSmrCtl::run(), UPoseHistNotUsed::saveToLog(), UResPoseHist::saveToLog(), UFuncEfLine::sendBoxPose(), UResSmrCtl::sendNewManoeuvreToSMR(), set(), UPoseTVQ::set(), UResLocater::set_state(), UResLocater::set_utmstate(), ULaserPathResult::setFromTag(), UResVarPool::setLocalVarPose(), UVarPool::setLocalVarPose(), UAvoidPath2::setMidPoint(), UVariable::setPose(), UResPoseHist::setPoseResult(), UAvoidPath2::setPreStopPoint(), UPoseTime::setPt(), UFuncView::setRobotPose(), UReactivePath::setRouteStats(), UResRoadDrive::setTarget(), UResLaserIfScan::snprint(), snprint(), UPoseV::snprint(), UPoseTVQ::snprint(), testDriveonEst(), UFuncLobst::testMethodCall(), testPose2Pose(), testPoseDist(), UNavPaint::toPixels(), UFuncStraightLine::toRobot(), UFuncStraightLine::toWorld(), UFuncTracking::TrackObjects(), UAvoidPath2::turnCentreCrossing(), Funcavoid::undersoeg(), UV360Scan::update(), UResRoadLine::update(), updateDisplacement(), UFuncLoca2::updateDisplacement(), UResGps::updateVars(), UResAuEf::updateWalls(), UPose(), UAvoidPath2::validNewClosePoint(), and UResLocater::varprint().


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