Tekkotsu Homepage
Demos
Overview
Downloads
Dev. Resources
Reference
Credits

WalkMC Class Reference

A nice walking class from Carnegie Mellon University's 2001 Robosoccer team, modified to fit this framework, see their license More...

#include <WalkMC.h>

Inheritance diagram for WalkMC:

List of all members.

Classes

struct  CalibrationParam
 holds information to correct for slippage, non-idealities More...
struct  LegParam
 holds parameters about how to move each leg More...
struct  LegWalkState
 holds state about each leg's path More...
struct  WalkParam
 holds more general parameters about the walk More...

Public Types

enum  AccelerationStyle_t { CALIBRATION_ACCEL, INF_ACCEL, DEFAULT_ACCEL }
 

used to specify value for acc_style

More...
typedef SplinePath< vector3d,
float
splinepath
 for convenience
typedef HermiteSplineSegment
< vector3d, float
spline
 for convenience

Public Member Functions

 WalkMC (const char *pfile=NULL)
 constructor
virtual void start ()
 sends an activate LocomotionEvent
virtual void stop ()
 sends a deactivate LocomotionEvent
virtual int updateOutputs ()
 calculates current positions of the paws
virtual int isDirty ()
 Returns true if we are walking. This modified isDirty allows the AIBO to slow down to a stop rather than stopping immediately.
virtual int isAlive ()
 Will prune if we've taken the requested number of steps.
virtual unsigned int getBinSize () const
 Calculates space needed to save - if you can't precisely add up the size, just make sure to overestimate and things will still work.
virtual unsigned int loadBuffer (const char buf[], unsigned int len)
 Load from a saved buffer in memory.
virtual unsigned int saveBuffer (char buf[], unsigned int len) const
 Save to a given buffer in memory.
virtual unsigned int loadFile (const char *filename)
 initiate opening of the specified file and loading/saving of all appropriate information.
virtual unsigned int saveFile (const char *filename) const
 initiate opening of the specified file and loading/saving of all appropriate information.
void setTargetVelocity (double dx, double dy, double da, int n=-1)
 set the direction to walk
const vector3d & getTargetVelocity ()
 returns current velocity we're trying to go
const vector3d & getCurVelocity () const
 returns the velocity we're actually moving (subject to clipping at max_accel_xya), doesn't reflect value of getPaused()...
unsigned int getStartTravelTime ()
 returns the time at which we started traveling along the current vector, in milliseconds
unsigned int getTravelTime ()
 returns the amount of time we've been traveling along the current vector, in milliseconds
void setTargetDisplacement (double dx, double dy, double da, unsigned int n)
 recalculates the target velocity so steps are of a given length to achieve the specified displacement in n steps
int getRemainingSteps () const
 returns remaining steps (step_count) (negative means infinite)
float getStepThreshold () const
 returns the step threshold -- see step_threshold
void setStepThreshold (float st)
 sets the step threshold -- see step_threshold
void setPaused (bool p)
 if set to true, will stop moving
bool getPaused () const
 if is true, we aren't moving
void setHeight (double h)
 sets WalkParam::body_height of wp
double getHeight ()
 gets WalkParam::body_height of wp
void setAngle (double a)
 sets WalkParam::body_angle of wp
double getAngle ()
 gets WalkParam::body_angle of wp
void setHop (double h)
 sets WalkParam::hop of wp
double getHop ()
 gets WalkParam::hop of wp
void setSway (double h)
 sets WalkParam::sway of wp
double getSway ()
 gets WalkParam::sway of wp
void setPeriod (long p)
 sets WalkParam::period of wp
long getPeriod ()
 gets WalkParam::period of wp
void setSlowMo (float p)
 sets slowmo
floatgetSlowMo ()
 gets slowmo
virtual void setAccelerationStyle (AccelerationStyle_t acc)
 sets acc_style
virtual AccelerationStyle_t getAccelerationStyle () const
 returns acc_style
struct WalkParamgetWP ()
struct CalibrationParamgetCP ()
 returns the current walk parameter structure
void resetLegPos ()
 returns the current walk calibration parameter

Static Public Attributes

static const float MAX_DX = 225
 maximum forward velocity, for setTargetDisplacement
static const float MAX_DY = 0
 maximum sideways velocity, for setTargetDisplacement
static const float MAX_DA = 2.1f
 maximum angular velocity, for setTargetDisplacement
static const vector3d max_accel_xya
 maximum acceleration of x, y, and a velocity

Protected Member Functions

void init (const char *pfile)
 does some setup stuff, calls loadFile(pfile)

Static Protected Member Functions

static void applyCalibration (const float mat[3][11], const vector3d &in, vector3d &out)
 converts in to calibration parameters and multiplies through the calibration matrix

Protected Attributes

OutputCmd cmds [NumOutputs][NumFrames]
 holds current joint commands
bool isPaused
 true if we are paused
WalkParam wp
 current walking parameters (note that it's not static - different WalkMC's can have different setting, handy...
CalibrationParam cp
 calibration parameters for current walk.
LegWalkState legw [NumLegs]
 current state of each leg
vector3d legpos [NumLegs]
 current position of each leg
splinepath body_loc
 the path the body goes through while walking (?)
splinepath body_angle
 the path the body goes through while walking (?)
vector3d liftPos [NumLegs]
 position each of the feet was last lifted
vector3d downPos [NumLegs]
 position each of the feet is next going to be set down
AccelerationStyle_t acc_style
 lets you switch between finite or infinite acceleration models
int step_count
 number of steps to take before stopping; if negative, walk forever.
float step_threshold
 point in a leg's cycle where the step counter should be decremented; 0 - leg lift, .25 - mid-air, .5 - leg down, .75 - mid-ground
double last_cycle
 where the walk is in it its cycle, updated at the end of each call to updateOutputs()
vector3d pos_delta
 how much we've moved
float angle_delta
 how much we've turned
unsigned int travelTime
 the time of the last call to setTargetVelocity - handy to check the time we've been traveling current vector
int time
 time of last call to updateOutputs() (scaled by slowmo)
int TimeStep
 time to pretend passes between each call to updateOutputs() - usually RobotInfo::FrameTime
float slowmo
 scales time values to make the walk move in slow motion for analysis (or fast forward)
int CycleOffset
int TimeOffset
bool NewCycleOffset
vector3d target_disp_xya
 requested displacement
vector3d vel_xya
 the current velocity we're moving
vector3d target_vel_xya
 the velocity that was requested
vector3d last_target_vel_xya
 the velocity that was last sent to motion

Detailed Description

A nice walking class from Carnegie Mellon University's 2001 Robosoccer team, modified to fit this framework, see their license

Moves the feet through a looping path in order to walk - default parameters use a walk low to the ground so you don't walk over the ball.

There are around 50 parameters which control the walk - these are loaded from a file and can modify almost every aspect of the the gait. It's a binary file format, I recommend using our Walk Edit menu to edit the parameters in real time and get immediate feedback. It's a tricky job to find a good set of parameters.

And then, once you have it walking, there's a whole different problem of actually moving at the speed that's requested. That's what the calibration parameters do - map the requested target speed to the command to pass to the engine so the resulting motion will hopefully match what you asked for.

You'll probably want to take a look at the setTargetVelocity() function to control the direction of the walk.

This class is in some dire need of some cleanup - we (Tekkotsu) didn't write it, have none the less hacked around and added stuff on top of it. So pardon the mess, unless you're feeling ambitious to write your own ;)

This portion of the code falls under CMPack's license:

  =========================================================================
    CMPack'02 Source Code Release for OPEN-R SDK v1.0
    Copyright (C) 2002 Multirobot Lab [Project Head: Manuela Veloso]
    School of Computer Science, Carnegie Mellon University
  -------------------------------------------------------------------------
    This software is distributed under the GNU General Public License,
    version 2.  If you do not have a copy of this licence, visit
    www.gnu.org, or write: Free Software Foundation, 59 Temple Place,
    Suite 330 Boston, MA 02111-1307 USA.  This program is distributed
    in the hope that it will be useful, but WITHOUT ANY WARRANTY,
    including MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
  -------------------------------------------------------------------------
    Additionally licensed to Sony Corporation under the following terms:

    This software is provided by the copyright holders AS IS and any
    express or implied warranties, including, but not limited to, the
    implied warranties of merchantability and fitness for a particular
    purpose are disclaimed.  In no event shall authors be liable for
    any direct, indirect, incidental, special, exemplary, or consequential
    damages (including, but not limited to, procurement of substitute
    goods or services; loss of use, data, or profits; or business
    interruption) however caused and on any theory of liability, whether
    in contract, strict liability, or tort (including negligence or
    otherwise) arising in any way out of the use of this software, even if
    advised of the possibility of such damage.
  =========================================================================

Definition at line 75 of file WalkMC.h.


Member Typedef Documentation

typedef HermiteSplineSegment<vector3d,float> WalkMC::spline

for convenience

Definition at line 78 of file WalkMC.h.

typedef SplinePath<vector3d,float> WalkMC::splinepath

for convenience

Definition at line 77 of file WalkMC.h.


Member Enumeration Documentation

used to specify value for acc_style

Enumerator:
CALIBRATION_ACCEL 

use the acceleration specified by the calibration parameters

INF_ACCEL 

ignore calibration acceleration (attempt infinite acceleration)

DEFAULT_ACCEL 

reference the value of Config::motion_config::walk_acceleration

Definition at line 204 of file WalkMC.h.


Constructor & Destructor Documentation

WalkMC::WalkMC ( const char *  pfile = NULL  ) 

constructor

Definition at line 70 of file WalkMC.cc.


Member Function Documentation

void WalkMC::applyCalibration ( const float  mat[3][11],
const vector3d &  in,
vector3d &  out 
) [static, protected]

converts in to calibration parameters and multiplies through the calibration matrix

Definition at line 681 of file WalkMC.cc.

Referenced by updateOutputs().

virtual AccelerationStyle_t WalkMC::getAccelerationStyle (  )  const [virtual]

returns acc_style

Definition at line 210 of file WalkMC.h.

double WalkMC::getAngle (  ) 

gets WalkParam::body_angle of wp

Definition at line 193 of file WalkMC.h.

unsigned int WalkMC::getBinSize (  )  const [virtual]

Calculates space needed to save - if you can't precisely add up the size, just make sure to overestimate and things will still work.

getBinSize is used for reserving buffers during serialization, but does not necessarily determine the actual size of what is written -- the return value of saveBuffer() specifies that after the data actually has been written. If getBinSize overestimates, the extra memory allocation is only temporary, no extra filler bytes are actually stored.

Returns:
number of bytes read/written, 0 if error (or empty)

Implements LoadSave.

Definition at line 153 of file WalkMC.cc.

struct CalibrationParam& WalkMC::getCP (  )  [read]

returns the current walk parameter structure

Definition at line 218 of file WalkMC.h.

const vector3d& WalkMC::getCurVelocity (  )  const

returns the velocity we're actually moving (subject to clipping at max_accel_xya), doesn't reflect value of getPaused()...

Definition at line 163 of file WalkMC.h.

double WalkMC::getHeight (  ) 

gets WalkParam::body_height of wp

Definition at line 191 of file WalkMC.h.

double WalkMC::getHop (  ) 

gets WalkParam::hop of wp

Definition at line 195 of file WalkMC.h.

bool WalkMC::getPaused (  )  const

if is true, we aren't moving

Definition at line 189 of file WalkMC.h.

long WalkMC::getPeriod (  ) 

gets WalkParam::period of wp

Definition at line 199 of file WalkMC.h.

int WalkMC::getRemainingSteps (  )  const

returns remaining steps (step_count) (negative means infinite)

Definition at line 182 of file WalkMC.h.

float* WalkMC::getSlowMo (  ) 

gets slowmo

Definition at line 201 of file WalkMC.h.

unsigned int WalkMC::getStartTravelTime (  ) 

returns the time at which we started traveling along the current vector, in milliseconds

Definition at line 165 of file WalkMC.h.

Referenced by getTravelTime().

float WalkMC::getStepThreshold (  )  const

returns the step threshold -- see step_threshold

Definition at line 185 of file WalkMC.h.

double WalkMC::getSway (  ) 

gets WalkParam::sway of wp

Definition at line 197 of file WalkMC.h.

const vector3d& WalkMC::getTargetVelocity (  ) 

returns current velocity we're trying to go

Definition at line 161 of file WalkMC.h.

unsigned int WalkMC::getTravelTime (  ) 

returns the amount of time we've been traveling along the current vector, in milliseconds

Definition at line 167 of file WalkMC.h.

Referenced by updateOutputs().

struct WalkParam& WalkMC::getWP (  )  [read]

Definition at line 217 of file WalkMC.h.

void WalkMC::init ( const char *  pfile  )  [protected]

does some setup stuff, calls loadFile(pfile)

Definition at line 111 of file WalkMC.cc.

Referenced by WalkMC().

virtual int WalkMC::isAlive (  )  [virtual]

Will prune if we've taken the requested number of steps.

Implements MotionCommand.

Definition at line 144 of file WalkMC.h.

int WalkMC::isDirty (  )  [virtual]

Returns true if we are walking. This modified isDirty allows the AIBO to slow down to a stop rather than stopping immediately.

Implements MotionCommand.

Definition at line 135 of file WalkMC.cc.

Referenced by updateOutputs().

unsigned int WalkMC::loadBuffer ( const char  buf[],
unsigned int  len 
) [virtual]

Load from a saved buffer in memory.

Parameters:
buf pointer to the memory where you should begin loading
len length of buf available (this isn't necessarily all yours, there might be other things following your data)
Returns:
the number of bytes actually used

Implements LoadSave.

Definition at line 161 of file WalkMC.cc.

unsigned int WalkMC::loadFile ( const char *  filename  )  [virtual]

initiate opening of the specified file and loading/saving of all appropriate information.

Parameters:
filename the file to load/save
Returns:
number of bytes read/written, 0 if error (or empty)

Reimplemented from LoadSave.

Definition at line 261 of file WalkMC.cc.

Referenced by init(), and LoadWalkControl::selectedFile().

void WalkMC::resetLegPos (  ) 

returns the current walk calibration parameter

takes current leg positions from WorldState and tries to match the point in the cycle most like it

Definition at line 647 of file WalkMC.cc.

Referenced by init(), and updateOutputs().

unsigned int WalkMC::saveBuffer ( char  buf[],
unsigned int  len 
) const [virtual]

Save to a given buffer in memory.

Parameters:
buf pointer to the memory where you should begin writing
len length of buf available. (this isn't necessarily all yours, constrain yourself to what you returned in getBinSize() )
Returns:
the number of bytes actually used

Implements LoadSave.

Definition at line 221 of file WalkMC.cc.

unsigned int WalkMC::saveFile ( const char *  filename  )  const [virtual]

initiate opening of the specified file and loading/saving of all appropriate information.

Parameters:
filename the file to load/save
Returns:
number of bytes read/written, 0 if error (or empty)

Reimplemented from LoadSave.

Definition at line 264 of file WalkMC.cc.

Referenced by SaveWalkControl::takeInput().

virtual void WalkMC::setAccelerationStyle ( AccelerationStyle_t  acc  )  [virtual]

sets acc_style

Definition at line 209 of file WalkMC.h.

void WalkMC::setAngle ( double  a  ) 

sets WalkParam::body_angle of wp

Definition at line 192 of file WalkMC.h.

void WalkMC::setHeight ( double  h  ) 

sets WalkParam::body_height of wp

Definition at line 190 of file WalkMC.h.

void WalkMC::setHop ( double  h  ) 

sets WalkParam::hop of wp

Definition at line 194 of file WalkMC.h.

void WalkMC::setPaused ( bool  p  ) 

if set to true, will stop moving

Definition at line 188 of file WalkMC.h.

void WalkMC::setPeriod ( long  p  ) 

sets WalkParam::period of wp

Definition at line 198 of file WalkMC.h.

void WalkMC::setSlowMo ( float  p  ) 

sets slowmo

Definition at line 200 of file WalkMC.h.

void WalkMC::setStepThreshold ( float  st  ) 

sets the step threshold -- see step_threshold

Definition at line 186 of file WalkMC.h.

void WalkMC::setSway ( double  h  ) 

sets WalkParam::sway of wp

Definition at line 196 of file WalkMC.h.

void WalkMC::setTargetDisplacement ( double  dx,
double  dy,
double  da,
unsigned int  n 
)

recalculates the target velocity so steps are of a given length to achieve the specified displacement in n steps

Parameters:
dx length of displacement in millimeters along body's x axis
dy length of displacement in millimeters along body's y axis
da amount to turn in radians, counter-clockwise viewed from above
n number of steps to take step_count will be set to n, so if the required velocity is beyond the abilities of the robot, it will stop on the n'th step, regardless of distance remaining.
See also:
setTargetVelocity()

Definition at line 294 of file WalkMC.cc.

void WalkMC::setTargetVelocity ( double  dx,
double  dy,
double  da,
int  n = -1 
)

set the direction to walk

Parameters:
dx forward velocity (millimeters per second)
dy left velocity (millimeters per second)
da counterclockwise velocity (radians per second)
n steps to take (if unspecified or negative, walk forever) Using a non-negative step count disables software acceleration of velocities
See also:
setTargetDisplacement()

Definition at line 268 of file WalkMC.cc.

Referenced by setTargetDisplacement().

void WalkMC::start (  )  [virtual]

sends an activate LocomotionEvent

Reimplemented from MotionCommand.

Definition at line 93 of file WalkMC.cc.

void WalkMC::stop (  )  [virtual]

sends a deactivate LocomotionEvent

Reimplemented from MotionCommand.

Definition at line 101 of file WalkMC.cc.

int WalkMC::updateOutputs (  )  [virtual]

calculates current positions of the paws

Implements MotionCommand.

Definition at line 345 of file WalkMC.cc.


Member Data Documentation

lets you switch between finite or infinite acceleration models

Definition at line 254 of file WalkMC.h.

Referenced by getAccelerationStyle(), setAccelerationStyle(), and updateOutputs().

how much we've turned

Definition at line 262 of file WalkMC.h.

Referenced by updateOutputs().

the path the body goes through while walking (?)

Definition at line 250 of file WalkMC.h.

Referenced by init().

the path the body goes through while walking (?)

Definition at line 249 of file WalkMC.h.

Referenced by init().

OutputCmd WalkMC::cmds[NumOutputs][NumFrames] [protected]

holds current joint commands

Definition at line 234 of file WalkMC.h.

Referenced by updateOutputs().

calibration parameters for current walk.

Definition at line 246 of file WalkMC.h.

Referenced by getBinSize(), getCP(), loadBuffer(), saveBuffer(), setTargetVelocity(), and updateOutputs().

int WalkMC::CycleOffset [protected]

The CycleOffset variable is used to ensure that each time the AIBO starts walking, it starts at the same point in the walk cycle as where it stopped. This measure is intended to decrease the amount of jerking (and hence deviation) that occurs when the AIBO starts walking forward and then suddenly stops.

Definition at line 275 of file WalkMC.h.

Referenced by updateOutputs().

vector3d WalkMC::downPos[NumLegs] [protected]

position each of the feet is next going to be set down

Definition at line 252 of file WalkMC.h.

Referenced by updateOutputs().

bool WalkMC::isPaused [protected]

true if we are paused

Definition at line 243 of file WalkMC.h.

Referenced by getPaused(), isDirty(), and setPaused().

double WalkMC::last_cycle [protected]

where the walk is in it its cycle, updated at the end of each call to updateOutputs()

Definition at line 259 of file WalkMC.h.

Referenced by updateOutputs().

vector3d WalkMC::last_target_vel_xya [protected]

the velocity that was last sent to motion

Definition at line 292 of file WalkMC.h.

Referenced by updateOutputs().

vector3d WalkMC::legpos[NumLegs] [protected]

current position of each leg

Definition at line 248 of file WalkMC.h.

Referenced by resetLegPos(), and updateOutputs().

LegWalkState WalkMC::legw[NumLegs] [protected]

current state of each leg

Definition at line 247 of file WalkMC.h.

Referenced by init(), and updateOutputs().

vector3d WalkMC::liftPos[NumLegs] [protected]

position each of the feet was last lifted

Definition at line 251 of file WalkMC.h.

Referenced by updateOutputs().

const vector3d WalkMC::max_accel_xya [static]

maximum acceleration of x, y, and a velocity

Definition at line 230 of file WalkMC.h.

Referenced by updateOutputs().

const float WalkMC::MAX_DA = 2.1f [static]

maximum angular velocity, for setTargetDisplacement

Definition at line 225 of file WalkMC.h.

Referenced by WalkMC::CalibrationParam::CalibrationParam(), setTargetDisplacement(), and updateOutputs().

const float WalkMC::MAX_DX = 225 [static]

maximum forward velocity, for setTargetDisplacement

Definition at line 223 of file WalkMC.h.

Referenced by WalkMC::CalibrationParam::CalibrationParam(), setTargetDisplacement(), and updateOutputs().

const float WalkMC::MAX_DY = 0 [static]

maximum sideways velocity, for setTargetDisplacement

Definition at line 224 of file WalkMC.h.

Referenced by WalkMC::CalibrationParam::CalibrationParam(), and updateOutputs().

bool WalkMC::NewCycleOffset [protected]

Every time we stop, we know we'll have a new CycleOffset, and we'll need to compute a new TimeOffset. This boolean says as much.

Definition at line 286 of file WalkMC.h.

Referenced by updateOutputs().

vector3d WalkMC::pos_delta [protected]

how much we've moved

Definition at line 261 of file WalkMC.h.

Referenced by updateOutputs().

float WalkMC::slowmo [protected]

scales time values to make the walk move in slow motion for analysis (or fast forward)

Definition at line 267 of file WalkMC.h.

Referenced by getSlowMo(), setSlowMo(), and updateOutputs().

int WalkMC::step_count [protected]

number of steps to take before stopping; if negative, walk forever.

Definition at line 256 of file WalkMC.h.

Referenced by getRemainingSteps(), isAlive(), isDirty(), setTargetVelocity(), and updateOutputs().

point in a leg's cycle where the step counter should be decremented; 0 - leg lift, .25 - mid-air, .5 - leg down, .75 - mid-ground

Definition at line 257 of file WalkMC.h.

Referenced by getStepThreshold(), setStepThreshold(), and updateOutputs().

vector3d WalkMC::target_disp_xya [protected]

requested displacement

Definition at line 289 of file WalkMC.h.

Referenced by setTargetDisplacement(), and updateOutputs().

vector3d WalkMC::target_vel_xya [protected]

the velocity that was requested

Definition at line 291 of file WalkMC.h.

Referenced by getTargetVelocity(), isDirty(), setTargetVelocity(), start(), and updateOutputs().

int WalkMC::time [protected]

time of last call to updateOutputs() (scaled by slowmo)

Definition at line 265 of file WalkMC.h.

Referenced by updateOutputs().

int WalkMC::TimeOffset [protected]

Each CycleOffset corresponds to a different TimeOffset once the robot starts walking again. Consider this example: the robot stops 2/3 of the way through the cycle, then starts again 1/3 of the way through the cycle on the absolute clock. The time offset to advance the clock to the right part of the cycle is 1/3 of a cycle, so we set TimeOffset to 1/3 cycle and add that to every clock value used in the walk code.

Definition at line 283 of file WalkMC.h.

Referenced by updateOutputs().

int WalkMC::TimeStep [protected]

time to pretend passes between each call to updateOutputs() - usually RobotInfo::FrameTime

Definition at line 266 of file WalkMC.h.

Referenced by updateOutputs().

unsigned int WalkMC::travelTime [protected]

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

Definition at line 264 of file WalkMC.h.

Referenced by getStartTravelTime(), start(), stop(), and updateOutputs().

vector3d WalkMC::vel_xya [protected]

the current velocity we're moving

Definition at line 290 of file WalkMC.h.

Referenced by getCurVelocity(), isDirty(), and updateOutputs().

WalkParam WalkMC::wp [protected]

current walking parameters (note that it's not static - different WalkMC's can have different setting, handy...

Definition at line 245 of file WalkMC.h.

Referenced by getAngle(), getBinSize(), getHeight(), getHop(), getPeriod(), getSway(), getWP(), init(), loadBuffer(), resetLegPos(), saveBuffer(), setAngle(), setHeight(), setHop(), setPeriod(), setSway(), setTargetDisplacement(), and updateOutputs().


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

Tekkotsu v5.0CVS
Generated Thu Mar 18 06:35:40 2010 by Doxygen 1.6.3