Tekkotsu Homepage | Demos | Overview | Downloads | Dev. Resources | Reference | Credits |
WheeledWalkMC Class ReferenceProvides a 'WalkMC' implementation for wheeled robots (diff-drive or theoretically holonomic configurations as well). More...
Inheritance diagram for WheeledWalkMC:
Detailed DescriptionProvides 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.
Constructor & Destructor Documentation
constructor Definition at line 35 of file WheeledWalkMC.h. Member Function Documentation
Definition at line 70 of file WheeledWalkMC.h.
Definition at line 68 of file WheeledWalkMC.h.
Definition at line 69 of file WheeledWalkMC.h.
Returns the current angular velocity in radians/sec. Definition at line 78 of file WheeledWalkMC.h.
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.
Returns the current x and y velocities in mm/sec. Definition at line 75 of file WheeledWalkMC.h.
the amount of time (ms) we have been travelling the current vector Definition at line 72 of file WheeledWalkMC.h.
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" ;)
Implements MotionCommand.
not used by MotionManager at the moment, but could be used to reduce recomputation, and you may find it useful
Implements MotionCommand. Definition at line 60 of file WheeledWalkMC.h.
reset and reload configuration settings, implies call to updateWheelConfig() Referenced by WheeledWalkMC().
Definition at line 57 of file WheeledWalkMC.h.
Specify body displacement and speed.
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
Specify the desired body velocity in x and y (millimeters per second) and angular velocity (radians per second), and amount of time before stopping. Specify the desired body velocity in x and y (millimeters per second) and angular velocity (radians per second); does not stop automatically.
called after this is added to MotionManager; don't override this, use doStart instead Reimplemented from MotionCommand.
called after this is removed from MotionManager; don't override this, use doStop instead Reimplemented from MotionCommand.
is called once per update cycle, can do any processing you need to change your priorities or set output commands on the MotionManager
Implements MotionCommand.
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.
updates WheelInfo::targetVel values based on targetVel and targetAngVel
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
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.
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.
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.
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().
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 |