Tag Archives: gait

Walking gait smoothing and tuning

I added some exponential smoothing to the original walking gaits, to smooth the edges of the trajectories and create a more natural movement.

I then added a ±30° pitching motion to what best approximates the ‘ankle’ (4th joint), to emulate the heel off and heel strike phases of the gait cycle.

b9780323039895000213_f014-019-9780323039895

The range of motion of the right ankle joint. Source: Clinical Gate.


I realised however that applying the pitch to the foot target is not exactly the same as applying the pitch to the ankle joint. This is because, in the robot’s case, the ‘foot target’ is located at the centre of the lowest part of the foot, that comes into contact with the ground, whereas the ankle is higher up, at a distance of two link lengths (in terms of the kinematics, that’s a4+a5). The walking gait thus does not ends up producing the expected result (this is best explained by the animations are the end).

To account for this, I simply had to adjust the forward/backward and up/down position of the target, in response to the required pitch.

With some simple trigonometry, the fwd/back motion is adjusted by -A*sin(pitch), while the up/down motion is adjusted by +A*(1-cos(pitch)), where A is the distance a4+a5 noted previously.

Here are the details showing how the targets are adjusted for one particular phase in the creep walk gait (numbers involving translations are all normalised because of the way the gait code currently works):

Pitch Adjustments Graph

Creep walk gait, 25-step window where the foot target pitch oscillates between ±30°. Original target translations (fwd/back, up/down) are shown compared to the ones adjusted in response to the pitch.


The final results of the foot pitching, with and without smoothing, are shown below:

This slideshow requires JavaScript.

This slideshow requires JavaScript.

This slideshow requires JavaScript.

 

Walking and steering inputs

Some slow progress lately, but progress nonetheless. First, I have updated the walking gaits with additional target values. Second, I have added a new input mode which allows the predefined walking gaits to be scrolled through via the keyboard or controller inputs. In effect, this means the controller can be used to “remote-control” the walking of the robot! The walking gaits still need a lot of tuning, but the basic function is now implemented.

I have updated the CSV spreadsheet for gait data, so that it now includes the 5 possible degrees-of-freedom of each foot (XYZ and Roll/Pitch), the 6 DoF of the base, and the 2 spine joints.

Gait_Values_Walk

The walking gait’s updated list of foot target values (first 50 out of 100).

Gait_Graph_Walk

The foot target values visualised (base and spine joints not shown).


In Python, all the CSV data is loaded into an array. One of the keyboard/controller inputs can now also be used to update an index, that scrolls forwards/backwards through the array’s rows.

Next, to get the robot to turn, a second input controls a deflection value which adjusts one of the spine joints and the base orientation (as was mentioned in this past post). The deflection slowly decreases back to 0, if the input is also 0.

By doing this, the walking gait can be controlled at will by the two inputs, and hopefully make the robot walk and turn. Next comes the fine-tuning and testing!

All the latest code can be found on the Quadbot17 GitHub project page as usual.

 

Four legs built – New videos and images

With the hardware for all four legs gathered, I have assembled the first standalone version of the quadruped. The MakerBeam XL aluminium profiles were adopted as before, to create a temporary chassis.

The fact that the robot can now stand on its four feet meant I could quickly give the walking gaits a test on the real hardware: The Python test software reads the up/down and forward/back position of each leg for a number of frames that make up a walking gait, the IK is solved, and the resulting joint values are streamed via serial over to the Arbotix-M, which simply updates the servo goal positions. No balancing or tweaking has been done whatsoever yet, which is why in the video I have to hold on to the back of the robot to prevent it from tipping backwards.

I took some time to make a video of the progress so far on this robot project:


A chance for some new photos:

 


Finally, here is an older video showing the Xbox One controller controlling the IK’s foot target position, and a simple serial program on the ArbotiX-M which receives the resulting position commands for each motor (try to overlook the bad video quality):


In the next stage I will start building the robot’s body, as per the CAD design, which is for the most part 3D printed parts and aluminium sheets, combined with the 2 DoF “spine” joints.

Kinematics x4

I have updated the quadruped kinematics program to display all four legs and calculate their IK. I have also started working on the ways various walking gates can be loaded and executed. I found an interesting creeping walk gait from this useful quadruped robot gait study article, and replicated it below for use with my robot:


Creep_Gait


As you can see, the patterns are replicated in quadrants, in order to complete a full gait where each leg is moved forward once. In my test program, I use the up/down and forward/back position of each leg, to drive the foot target for each leg, as was done previously with the GUI sliders and gamepad.

The lateral swing of each leg (first joint) is not changed, but this can be looked at later. The “ankle” (last two joints) is controlled such that the leg plane is always parallel to the ground.

This is what the current state of the program looks like:


Quadbot 17 Quad Kinematics_002


The foot target values are loaded from a CSV into the Python program, and the IK is run for each leg, going through the whole gait sequence:


testQuadGait


I have also added the option to interrupt and run another gait sequence at any point. The reason for this is to try and experiment how to best switch or blend from one gait to another. For now, if a new gait is loaded, the program will stop the current gait, and compare the current pose to all poses in the new gait. The new gait will then start at the pose which most closely matches the current pose, by using a simple distance metric.
If the 8 values of up/down/fwd/back for all legs are in an array LastPose for the last pose the robot was in, and CurrPose for the current pose of interest from the new gait, then the pseudocode looks something like this:

DistanceMetric = 0
for i = 0 to 7
{
  d[i] = abs(CurrPose[i] - LastPose[i])
  if d[i] > threshold
  d[i] += penalty
  DistanceMetric += d[i]
}

If the distance in any particular direction is larger than some threshold, then an arbitrary penalty value can be added. This will bias the calculation against outliers: a pose with evenly distributed distances will be preferred over a pose with an overall small distance but large distance in one direction. This may not actually be of much use in practice, but can be tweaked or removed later.

The above pose switching idea will be expanded on, so that the robot can seemlessly blend between predefined walking gaits, e.g. when in order to turn left and right or speed up and down.

The next step is to start porting all this test code onto the Arbotix, which has a few minor challenges: Ideally the IK matrix operations need to be done efficiently without extra overhead from additional libraries. The gait values which are loaded from a CSV file need to be hard-coded, however this should be simple to do, since as shown above a gait uses the same target values rearranged across quadrants.


Until next time!