Tekkotsu Homepage | Demos | Overview | Downloads | Dev. Resources | Reference | Credits |
WalkMC Class Reference#include <WalkMC.h>
Inheritance diagram for WalkMC:
![]() Detailed DescriptionA 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 70 of file WalkMC.h.
Member Typedef Documentation
Member Enumeration Documentationused to specify value for acc_style
Constructor & Destructor Documentation
Member Function Documentation
calculates current positions of the paws
Implements MotionCommand. Reimplemented in WaypointWalk< MAX_WAY >. Definition at line 311 of file WalkMC.cc. Referenced by WaypointWalk< MAX_WAY >::updateOutputs().
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 127 of file WalkMC.cc. Referenced by updateOutputs().
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.
Implements LoadSave.
Load from a saved buffer in memory.
Implements LoadSave.
Save to a given buffer in memory.
Implements LoadSave.
initiate opening of the specified file and loading/saving of all appropriate information.
Reimplemented from LoadSave. Definition at line 257 of file WalkMC.cc. Referenced by init(), WaypointWalk< MAX_WAY >::LoadWalkMCFile(), and LoadWalkControl::selectedFile().
initiate opening of the specified file and loading/saving of all appropriate information.
Reimplemented from LoadSave. Definition at line 260 of file WalkMC.cc. Referenced by WaypointWalk< MAX_WAY >::SaveWalkMCFile(), and SaveWalkControl::takeInput().
set the direction to walk
Definition at line 264 of file WalkMC.cc. Referenced by setTargetDisplacement(), and WaypointWalk< MAX_WAY >::updateOutputs().
returns the velocity we're actually moving (subject to clipping at max_accel_xya), doesn't reflect value of getPaused()...
returns the time at which we started traveling along the current vector
Definition at line 160 of file WalkMC.h. Referenced by getTravelTime().
returns the amount of time we've been traveling along the current vector
Definition at line 162 of file WalkMC.h. Referenced by updateOutputs().
recalculates the target velocity so steps are of a given length to achieve the specified displacement in n steps
returns remaining steps (step_count) (negative means infinite)
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 603 of file WalkMC.cc. Referenced by init(), and updateOutputs().
converts in to calibration parameters and multiplies through the calibration matrix
Definition at line 637 of file WalkMC.cc. Referenced by updateOutputs().
Member Data Documentation
==180 mm/sec
Definition at line 218 of file WalkMC.h. Referenced by WalkMC::CalibrationParam::CalibrationParam(), and updateOutputs().
==140 mm/sec
Definition at line 219 of file WalkMC.h. Referenced by WalkMC::CalibrationParam::CalibrationParam(), and updateOutputs().
==1.8 rad/sec
Definition at line 220 of file WalkMC.h. Referenced by WalkMC::CalibrationParam::CalibrationParam(), and updateOutputs().
maximum acceleration of x, y, and a velocity
Definition at line 222 of file WalkMC.h. Referenced by updateOutputs().
holds current joint commands
Definition at line 226 of file WalkMC.h. Referenced by updateOutputs().
true if we are paused
Definition at line 235 of file WalkMC.h. Referenced by getPaused(), isDirty(), and setPaused().
current walking parameters (note that it's not static - different WalkMC's can have different setting, handy...
Definition at line 237 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().
calibration parameters for current walk.
Definition at line 238 of file WalkMC.h. Referenced by getBinSize(), getCP(), loadBuffer(), saveBuffer(), setTargetVelocity(), and updateOutputs().
current state of each leg
Definition at line 239 of file WalkMC.h. Referenced by init(), and updateOutputs().
current position of each leg
Definition at line 240 of file WalkMC.h. Referenced by resetLegPos(), and updateOutputs().
position each of the feet was last lifted
Definition at line 243 of file WalkMC.h. Referenced by updateOutputs().
position each of the feet is next going to be set down
Definition at line 244 of file WalkMC.h. Referenced by updateOutputs().
lets you switch between finite or infinite acceleration models
Definition at line 246 of file WalkMC.h. Referenced by getAccelerationStyle(), setAccelerationStyle(), and updateOutputs().
number of steps to take before stopping; if negative, walk forever.
Definition at line 248 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 249 of file WalkMC.h. Referenced by getStepThreshold(), setStepThreshold(), and updateOutputs().
where the walk is in it its cycle, updated at the end of each call to updateOutputs()
Definition at line 251 of file WalkMC.h. Referenced by updateOutputs().
the time of the last call to setTargetVelocity - handy to check the time we've been traveling current vector
Definition at line 256 of file WalkMC.h. Referenced by DoStart(), DoStop(), getStartTravelTime(), and updateOutputs().
time of last call to updateOutputs() (scaled by slowmo)
Definition at line 257 of file WalkMC.h. Referenced by updateOutputs().
time to pretend passes between each call to updateOutputs() - usually RobotInfo::FrameTime
Definition at line 258 of file WalkMC.h. Referenced by updateOutputs().
scales time values to make the walk move in slow motion for analysis (or fast forward)
Definition at line 259 of file WalkMC.h. Referenced by getSlowMo(), setSlowMo(), and updateOutputs().
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 267 of file WalkMC.h. Referenced by updateOutputs().
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 275 of file WalkMC.h. Referenced by updateOutputs().
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 278 of file WalkMC.h. Referenced by updateOutputs().
the current velocity we're moving
Definition at line 281 of file WalkMC.h. Referenced by getCurVelocity(), isDirty(), and updateOutputs().
the velocity that was requested
Definition at line 282 of file WalkMC.h. Referenced by DoStart(), getTargetVelocity(), isDirty(), setTargetVelocity(), and updateOutputs().
the velocity that was last sent to motion
Definition at line 283 of file WalkMC.h. Referenced by updateOutputs().
The documentation for this class was generated from the following files: |
Tekkotsu v4.0 |
Generated Thu Nov 22 00:58:47 2007 by Doxygen 1.5.4 |