Tekkotsu Homepage
Demos
Overview
Downloads
Dev. Resources
Reference
Credits

WheeledWalkMC Class Reference

Provides a 'WalkMC' implementation for wheeled robots (diff-drive or theoretically holonomic configurations as well). More...

#include <WheeledWalkMC.h>

Inheritance diagram for WheeledWalkMC:

Detailed Description

Provides a 'WalkMC' implementation for wheeled robots (diff-drive or theoretically holonomic configurations as well).

Uses kinematic description to determine location and orientation of wheels and computes appropriate wheel velocities to produce a target motion. Can handle skid-steer (diff drive) type motion, including holonomic wheels, but does not handle ackerman style (steered) configurations.

Also does not handle 'slanted' wheels optimally: Assumes wheels are perpendicular to the ground, that the base frame Z axis is perpendicular to the ground frame. This could be added with a bit more math when computing wheel positions.

This motion command also assumes that wheels are commanded by mm/sec ground speed, not rad/sec rotational speed.

For simulation in Mirage, make sure all wheels are marked by adding a Velocity=true entry in the ControllerInfo of the corresponding kinematics configuration, and that the x and y dimensions of the collision model are set for the wheel radius.

TODO: Test on a holonomic platform, should handle it, but originally only tested on diff-drive like Create. Also, perhaps add config settings to override rotationCenter and a flag to have updateWheelConfig called before each updateOutputs.

Definition at line 32 of file WheeledWalkMC.h.

List of all members.

Classes

struct  WheelInfo
 stores information about the configuration and current target state of each wheel More...

Public Member Functions

 WheeledWalkMC ()
 constructor
void resetConfig ()
 reset and reload configuration settings, implies call to updateWheelConfig()
void setDirty ()
virtual int updateOutputs ()
 is called once per update cycle, can do any processing you need to change your priorities or set output commands on the MotionManager
virtual int isDirty ()
 not used by MotionManager at the moment, but could be used to reduce recomputation, and you may find it useful
virtual int isAlive ()
 used to prune "dead" motions from the MotionManager
virtual void start ()
 called after this is added to MotionManager; don't override this, use doStart instead
virtual void stop ()
 called after this is removed from MotionManager; don't override this, use doStop instead
virtual void zeroVelocities ()
 Posts a LocomotionEvent and sets velocities to zero. Also forces an output frame setting wheel velocities to zero; needed because if we remove a motion command there may be nothing left to zero the velocities.
float getMaxXVel () const
float getMaxYVel () const
float getMaxAVel () const
unsigned int getTravelTime ()
 the amount of time (ms) we have been travelling the current vector
const fmat::Column< 2 > & getTargetVelocity () const
 Returns the current x and y velocities in mm/sec.
float getTargetAngVelocity () const
 Returns the current angular velocity in radians/sec.
virtual void getTargetVelocity (float &xvel, float &yvel, float &avel)
 Specify the desired body velocity in x and y (millimeters per second) and angular velocity (radians per second).
virtual void setTargetVelocity (float xvel, float yvel, float avel)
 Specify the desired body velocity in x and y (millimeters per second) and angular velocity (radians per second); does not stop automatically.
virtual void setTargetVelocity (float xvel, float yvel, float avel, float time)
 Specify the desired body velocity in x and y (millimeters per second) and angular velocity (radians per second), and amount of time before stopping.
virtual void setTargetDisplacement (float xdisp, float ydisp, float adisp, float time=0)
 Specify the desired body displacement in x and y (millimeters) and a (radians).
void setTargetDisplacement (float xdisp, float ydisp, float adisp, float xvel, float yvel, float avel)
 Specify body displacement and speed.
virtual void updateWheelConfig ()
 Recomputes wheel positions and orientations. Automatically called by constructor, but may need to recall if wheel positions are actuated.

Public Attributes

plist::Primitive< floatpreferredXVel
 optimal X velocity for unspecified displacements
plist::Primitive< floatpreferredYVel
 optimal Y velocity for unspecified displacements
plist::Primitive< floatpreferredAngVel
 optimal angular velocity for unspecified displacements

Protected Member Functions

void updateWheelVels ()
 updates WheelInfo::targetVel values based on targetVel and targetAngVel

Protected Attributes

fmat::Column< 2 > targetVel
 the requested xy velocity of the body (ignoring parameterized body motion, like sway or surge), millimeters per second
float targetAngVel
 the requested angular velocity of the body, radians per second
unsigned int targetDur
 duration in msecs for the current displacement
float targetDist
 forward distance we want to travel
float targetAngDist
 angular distance we want to travel
fmat::Column< 2 > maxVel
 maximum velocity in x,y
float maxAngVel
 maximum angular velocity
fmat::Column< 2 > rotationCenter
 point to use as center of rotations, defaults to center of wheels
bool displacementMode
 If true, velocity will be set to 0 when desired displacement is achieved.
unsigned int travelStartTime
 the time of the last call to setTargetVelocity - handy to check the time we've been traveling current vector
float travelStartDist
 The forward odometry reading in millimeters at the time of the last call to setTargetVelocity.
float travelStartAngle
 The angular odometry reading in radians at the time of the last call to setTargetVelocity.
bool dirty
 set to true by updateWheelVels(), cleared up updateOutputs()
WheelInfo wheels [NumWheels]

Static Protected Attributes

static constexpr float EPSILON = 1e-4f

Constructor & Destructor Documentation

WheeledWalkMC::WheeledWalkMC (  ) 

constructor

Definition at line 35 of file WheeledWalkMC.h.


Member Function Documentation

float WheeledWalkMC::getMaxAVel (  )  const

Definition at line 70 of file WheeledWalkMC.h.

float WheeledWalkMC::getMaxXVel (  )  const

Definition at line 68 of file WheeledWalkMC.h.

float WheeledWalkMC::getMaxYVel (  )  const

Definition at line 69 of file WheeledWalkMC.h.

float WheeledWalkMC::getTargetAngVelocity (  )  const

Returns the current angular velocity in radians/sec.

Definition at line 78 of file WheeledWalkMC.h.

virtual void WheeledWalkMC::getTargetVelocity ( float xvel,
float yvel,
float avel 
) [virtual]

Specify the desired body velocity in x and y (millimeters per second) and angular velocity (radians per second).

Definition at line 81 of file WheeledWalkMC.h.

const fmat::Column<2>& WheeledWalkMC::getTargetVelocity (  )  const

Returns the current x and y velocities in mm/sec.

Definition at line 75 of file WheeledWalkMC.h.

unsigned int WheeledWalkMC::getTravelTime (  ) 

the amount of time (ms) we have been travelling the current vector

Definition at line 72 of file WheeledWalkMC.h.

virtual int WheeledWalkMC::isAlive (  )  [virtual]

used to prune "dead" motions from the MotionManager

note that a motion could be "paused" or inactive and therefore not dirty, but still alive, biding its time to "strike" ;)

Returns:
zero if the motion is still processing, non-zero otherwise

Implements MotionCommand.

virtual int WheeledWalkMC::isDirty (  )  [virtual]

not used by MotionManager at the moment, but could be used to reduce recomputation, and you may find it useful

Returns:
zero if none of the commands have changed since last getJointCmd(), else non-zero

Implements MotionCommand.

Definition at line 60 of file WheeledWalkMC.h.

void WheeledWalkMC::resetConfig (  ) 

reset and reload configuration settings, implies call to updateWheelConfig()

Referenced by WheeledWalkMC().

void WheeledWalkMC::setDirty (  ) 

Definition at line 57 of file WheeledWalkMC.h.

void WheeledWalkMC::setTargetDisplacement ( float  xdisp,
float  ydisp,
float  adisp,
float  xvel,
float  yvel,
float  avel 
)

Specify body displacement and speed.

virtual void WheeledWalkMC::setTargetDisplacement ( float  xdisp,
float  ydisp,
float  adisp,
float  time = 0 
) [virtual]

Specify the desired body displacement in x and y (millimeters) and a (radians).

Corresponding velocity will be limited to max velocity, so setting time=0 implies max speed

virtual void WheeledWalkMC::setTargetVelocity ( float  xvel,
float  yvel,
float  avel,
float  time 
) [virtual]

Specify the desired body velocity in x and y (millimeters per second) and angular velocity (radians per second), and amount of time before stopping.

virtual void WheeledWalkMC::setTargetVelocity ( float  xvel,
float  yvel,
float  avel 
) [virtual]

Specify the desired body velocity in x and y (millimeters per second) and angular velocity (radians per second); does not stop automatically.

virtual void WheeledWalkMC::start (  )  [virtual]

called after this is added to MotionManager; don't override this, use doStart instead

Reimplemented from MotionCommand.

virtual void WheeledWalkMC::stop (  )  [virtual]

called after this is removed from MotionManager; don't override this, use doStop instead

Reimplemented from MotionCommand.

virtual int WheeledWalkMC::updateOutputs (  )  [virtual]

is called once per update cycle, can do any processing you need to change your priorities or set output commands on the MotionManager

Returns:
zero if no changes were made, non-zero otherwise
See also:
RobotInfo::NumFrames
RobotInfo::FrameTime

Implements MotionCommand.

virtual void WheeledWalkMC::updateWheelConfig (  )  [virtual]

Recomputes wheel positions and orientations. Automatically called by constructor, but may need to recall if wheel positions are actuated.

Includes a call to updateWheelVels() in case wheel positions change.

void WheeledWalkMC::updateWheelVels (  )  [protected]

updates WheelInfo::targetVel values based on targetVel and targetAngVel

virtual void WheeledWalkMC::zeroVelocities (  )  [virtual]

Posts a LocomotionEvent and sets velocities to zero. Also forces an output frame setting wheel velocities to zero; needed because if we remove a motion command there may be nothing left to zero the velocities.


Member Data Documentation

bool WheeledWalkMC::dirty [protected]

set to true by updateWheelVels(), cleared up updateOutputs()

Definition at line 129 of file WheeledWalkMC.h.

Referenced by isDirty(), and setDirty().

If true, velocity will be set to 0 when desired displacement is achieved.

Definition at line 125 of file WheeledWalkMC.h.

constexpr float WheeledWalkMC::EPSILON = 1e-4f [static, protected]

Definition at line 131 of file WheeledWalkMC.h.

maximum angular velocity

Definition at line 122 of file WheeledWalkMC.h.

Referenced by getMaxAVel().

maximum velocity in x,y

Definition at line 121 of file WheeledWalkMC.h.

Referenced by getMaxXVel(), and getMaxYVel().

optimal angular velocity for unspecified displacements

Definition at line 111 of file WheeledWalkMC.h.

Referenced by WheeledWalkMC().

optimal X velocity for unspecified displacements

Definition at line 109 of file WheeledWalkMC.h.

Referenced by WheeledWalkMC().

optimal Y velocity for unspecified displacements

Definition at line 110 of file WheeledWalkMC.h.

Referenced by WheeledWalkMC().

point to use as center of rotations, defaults to center of wheels

Definition at line 124 of file WheeledWalkMC.h.

angular distance we want to travel

Definition at line 120 of file WheeledWalkMC.h.

the requested angular velocity of the body, radians per second

Definition at line 117 of file WheeledWalkMC.h.

Referenced by getTargetAngVelocity(), and getTargetVelocity().

forward distance we want to travel

Definition at line 119 of file WheeledWalkMC.h.

unsigned int WheeledWalkMC::targetDur [protected]

duration in msecs for the current displacement

Definition at line 118 of file WheeledWalkMC.h.

the requested xy velocity of the body (ignoring parameterized body motion, like sway or surge), millimeters per second

Definition at line 116 of file WheeledWalkMC.h.

Referenced by getTargetVelocity().

The angular odometry reading in radians at the time of the last call to setTargetVelocity.

Definition at line 128 of file WheeledWalkMC.h.

The forward odometry reading in millimeters at the time of the last call to setTargetVelocity.

Definition at line 127 of file WheeledWalkMC.h.

unsigned int WheeledWalkMC::travelStartTime [protected]

the time of the last call to setTargetVelocity - handy to check the time we've been traveling current vector

Definition at line 126 of file WheeledWalkMC.h.

Referenced by getTravelTime().

WheelInfo WheeledWalkMC::wheels[NumWheels] [protected]

Definition at line 141 of file WheeledWalkMC.h.


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

Tekkotsu v5.1CVS
Generated Mon May 9 04:59:18 2016 by Doxygen 1.6.3