Tag Archives: dynamics

Walking in semi-rugged terrain

While testing the improved gait sequencing for the quad A1 I got some footage of it traversing a few different types of outdoor semi-rugged terrain.

Tree roots

The first clip shows it walking over some tree roots. In this particular instance, it just uses a high stepping gait, which allows the feet to get on top of the root. The gait sequencing doesn’t handle walking over the taller part of the root very well yet… the robot can get “high centered” on two legs, with the other two flailing in the air.

Gravel

In the second clip the robot runs across some loose gravel and leaves. Here each foot fall skids around a fair amount and kicks up loose debris, but otherwise wasn’t too challenging.

Raised pavers

For the third clip, the quad A1 walks through some grass and over some pavers, which are around 1-3″ raised above the baseline grass level. Here raised steps allow the robot to move at nearly the same speed over the pavers as it can move over the grassy terrain.

Loose bricks

In the final clip, it walks over some loose bricks. With each footfall, the gait sequencing is looking for when contact is made with the ground. That allows the robot to stop pushing once contact is made. The current formulation does attempt to get the legs back to their “average” Z position at the end of each cycle, which is sufficient for this type of terrain, although a longer-term outlook would allow it to tackle even tougher terrain.

Stable gait sequencing

In the last post, I described the newer gait engine which takes a desired command and produces a set of gait parameters. At that point, the gait engine needs to implement those gait parameters in a way that is stable with respect to disturbances and keeps the two legs properly out of phase with one another.

The gait variables that the gait selection procedure emits are as follows, each “leg” is actually a pair of legs.

  • swing time: This is the amount of time between when a leg lifts off the ground, and when it lands again.
  • one leg time: This is the amount of time spent with only a single leg on the ground.
  • two leg time: The amount of time with both legs on the ground.
  • flight time: The amount of time with no legs on the ground.

I’ve chosen to implement this for now with two controllable variables, when to pick up the next leg to begin its swing phase and how far out to place the foot when landing. When in flight, the swing time is fixed to be exactly what the gait engine selected. When on the ground, the leg position and velocity are fixed in the world frame to match the current command. This results in the other three parameters, one leg, two leg, and flight time, being approximated as best as possible.

When to lift

When there is no flight time, then the heuristic for when to lift the leg is identical to that described in “Balancing gait in 2D“. The trailing leg is lifted when the opposing leg is half of a swing time away from crossing the balance point.

When there is a flight time present, we have to add a corrective term to that heuristic, otherwise the two legs can lose their phase synchronization. If the correct out of phase relationship is being held, then the leg will be lifted when the alternate leg is in flight and has the “flight time” remaining in its swing cycle. The correction for that leg is calculated as a difference in time around that point such that the correction is positive before that point and negative after scaling in a linear manner. This has the desired property that the two legs are kept out of phase, without enforcing a strict leg cycle time.

Where to place

Once again, when there is no flight time, the placement location is the same as before. When there is a flight time, then the placement location is even simpler. Now it is just a position forward of the balance point by one half of the “one leg time”. This results in the machine spending roughly half of its time on each side of the balance point.

Further work

I’ve got one further enhancement to this technique to describe, at which point I think I’ll have basically exhausted its promise. Further advances will likely have to come from using an optimization based controller rather than a heuristic driven approach.

Higher speed gait formulation

As hinted in my earlier video I’ve been working towards some higher speed gaits with the quad A1. To accomplish that, I had to restructure the gait sequencing logic to permit changing cycle times and allow flight phases.

For now, I’ve tentatively broken down the trot gait into 5 regimes, based on how fast the machine is moving:

  1. At the slowest speeds, the flight legs swing through a step in the configured maximum flight time. The interval between flight times is fixed at a configured maximum. Here the speed is determined by how far the flight legs move.
  2. Once the flight legs are moving through their maximum allowed distance, then the amount of time spent with both legs on the ground is reduced in order to increase speed.
  3. At the point when both legs are not on the ground at the same time, then there begins to be a flight phase. Increasing the length of the flight phase increases the speed.
  4. When the flight phase reaches a configured maximum, then the swing time is decreased until it reaches a configured minimum.
  5. When the swing time is at a configured minimum, the flight time is at a configured maximum, and the legs are moving through their maximum range, then the machine is moving at its maximum speed.

Depending upon the current commanded rotation rate and translation velocity, the distance available for the legs to travel through may change. This uses the same mechanism from the step selection technique to determine the maximum distance at each update cycle, then selects which of the above regimes is active based on the commanded speed.

For a given maximum distance the legs can move through, that results in key gait parameters changing with speed as in the plot below:

Next up I’ll cover the heuristics used to implement any given set of gait parameters in a stable manner.

Operating on sloped surfaces

Not too long ago, I ran some outdoor experiments, and while piloting the quad A1 around, realized that it wasn’t going to get very far if it was restricted to just flat ground.

Since the control algorithms are completely ignorant of slopes, the center of gravity of the machine can easily get too close to the support polygon when resting, and similarly fails to stay balanced over the support line during the trot gait.

To get started tackling this, I stuck a configurable ramp in the simulator:

And yes, it fails just as much on the ramp as it did in real life.

Balancing gait in 2D

After getting a gait which looked like it could balance across the leg support line in 1D, I needed to extend that to 2D and try it out on the robot.

Extension to 2D

Extending this to two dimensions wasn’t too bad. I just did a bunch of geometry to follow the path traced out by a given 2 dimensional velocity and rotation rate, intersected with a line segment:

Given this function, the logic to select a swing target is basically the same as in the 1 dimensional case. We now create two “virtual legs”, which consist of two feet ganged together and produce a single support line. At each time instant when all legs are in stance, we look at the time remaining until each of the virtual legs would cross the center of mass at the current velocity. As soon as one hits the half-swing point, we start a swing.

As part of this, I extended tplot2 to be able to render the target location of each swing.

Remaining niggles

Once I had an actual robot to test it out on, I found a few other minor problems. When selecting the target for a foot swing, the 1 dimensional case just used the current velocity to move the leg far enough past the pickup point. That doesn’t work out all that well in heavy acceleration though, resulting in very short stance times. What worked much better was to use the expected velocity at the end of the next stance window. That provided much more consistent stance spacings even when accelerating or decelerating.

I still haven’t come up with a great solution for turning in place, for which the entire concept of estimating distance to the balance point doesn’t make sense. Right now, I just rely on the maximum stance time to ensure the legs eventually step in that scenario and don’t extend beyond their physical limits. I’ll probably eventually add a “time to infeasible geometry” criteria to handle that.

Testing it out

While there is still a lot of remaining work, this increased the maximum possible speed of the machine by at least a factor of 2, and the feasible acceleration by a factor of 10 or so. In the video below, I’ve got some clips of the robot walking around at 0.5m/s. That’s not too fast, but is more than a body length per second which counts for something.