Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Increase stability for warm / worn-out robots #1414

Open
Narcha opened this issue Jul 21, 2024 · 4 comments
Open

Increase stability for warm / worn-out robots #1414

Narcha opened this issue Jul 21, 2024 · 4 comments

Comments

@Narcha
Copy link
Contributor

Narcha commented Jul 21, 2024

This is a large but important topic. I'd argue we could have gotten 2nd place in RC24 if we hadn't had as severe problems with walking stability on worn-out hardware. Feel free to add your own ideas, comments, or to-dos.

@philipniklas-r
Copy link

Small Idea Input from my side:

https://github.com/bhuman/BHumanCodeRelease/blob/50c83c6a8826ed2c08bc7400d9e9d76e48b343a9/Src/Modules/MotionControl/WalkingEngine/WalkLibs/WalkLearnerProvider.cpp#L58

What we did back in 2019 was that we let the robot "optimize" the gyro balancing parameters for the walking.

Our default ankle pitch gyro balancing values are 0.05.
Back then, the slightly worn out robots would automatically get higher balancing values during the games. The cool thing is, that once the robots reached a heating state (atleast one leg joints with > 76°C) the gyro balancing parameters would quickly increase to (I think) 0.08 - 0.1.

If interesting I can write some information how the optimization works. We also still use it, even tho I dont know if it is still needed (dont break a working system 🤷 )

@philipniklas-r
Copy link

philipniklas-r commented Jul 23, 2024

A few other ideas:

If the robot is tilted too far back, the interpolation for the feet can be slowed down

As a simplified example the interpolation of the walk variables can be done with two values: the current time in the step tWalk and the step duration duration. tWalk is normally increased in each execution frame by 12 ms (cycle time of motion), and the interpolation factor for the walk variables is done by dividing both values: ratio = tWalk / duration (with ratio being clipped into the range of 0 and 1).

What we do (we got the idea from HTWK: https://github.com/NaoHTWK/HTWKMotion/blob/master/walking_engine.cpp#L297), is that we slow down this interpolation, by increasing tWalk slower if the robot is tilted too far back: https://github.com/NaoHTWK/HTWKMotion/blob/master/walking_engine.cpp#L297

tWalk += Constants::motionCycleTime * (1.f - engine.balanceParameters.slowdownFactor * Rangef::ZeroOneRange().limit((engine.theInertialData.angle.y() + engine.balanceParameters.slowdownTorsoOffset + armCompensationTilt[0]) / -engine.balanceParameters.minTorsoRotation));
=>
tWalk += 12 ms * (1 - 0.5 * (TorsoAngleY + 5deg + TorsoTiltFromArms) / -5deg

So if the robot is tilted too far back, we don't increase tWalk by 12 ms, but with only half of it.
NOTE: we use tWalk for the x-translation (forward/backward). Turning and side steps are interpolated normally. But feel free to use it as needed.

Reduced walk speed for non-strikers

Only for the robots that want to play the ball the maximum (allowed) walking speed is used. (*In the ready state and when searching the ball in a corner kick the maximum is used for all robots). All other robots use a smaller walking speed. The forward speed is reduced down to 175 mm/s. Turn and side speed are as much reduced as the forward speed is percentage wise reduced.

Reduce walk speed for worn-out robots

We calculate a value for worn-out robot dynamically while the robots walk. The value is between 1 and 0, 1 for good robots and 0 for worn-out ones. With it we can reduce the maximum walk speed of the robots to ensure stability. In theory we can also scale some balancing parameters.
From the RoHOW 2022: https://www.youtube.com/watch?v=hqjZJ4hgCGA
The file:

https://github.com/bhuman/BHumanCodeRelease/blob/master/Src/Modules/Sensing/JointPlayProvider/JointPlayProvider.cpp

Dynamically adjusting the gyro balancing

Since 2019 we dynamically adjust the gyro balancing parameters in the walk. For a few walking steps nothing is adjusted and we just measure the peaks of the y-gyro. Afterwards we repeat it with a sligthly reduced balancing value and slightly increased one. The size of change is random, but within a given range.
Afterwards we can compare the gyro peaks for all three time windows and use the balancing values, which resulted in the overall smallest peaks.

With it we noticed, that 0.05 for the gyro values seem to be a good fit for all most robots (new ones and slightly worn-out). But also, once the joints heat up and reach a threshold where the stiffness is reduced by the robots software (at about 76°C), the gyro balancing values are increased in a short time, to something between 0.075 and 0.1. This helped a lot back in 2019 to keep playing with warm robots.

More standing still

Our robots stand still a lot. Here the energy saving mode can reduce the currents in the joints to a minimum and prevent heating up further. In the round robin games after every first half all robots were below 60°C (except one, which did a lot of walking work). The goalie was always < 45°C and the defenders around the 50°C mark. This made it possible to change the goalie and one of the field players (inclusiv jersey number), e.g. the goalie became a field player and the field player the goalie for the second half.

Increase the interpolation time of the step height

The step height is a parabolic curve (from rUNSWift. I think you still use it too?). What we do it interpolate to the maximum after 125 ms (half of the default step duration of 250 ms). But for side steps, but also for worn-out robots, we increase the duration, so the step height it reduce a bit slower than normally. This prevents the swing foot (especially the tip of the toe) colliding with the ground too early. Increasing the time is done automatically with the value to decide how worn-out a robot is.

Side hip shift

For side steps we shift the hip away from the support leg if the legs are moving together again. Otherwise the momentum is often too large and the robot either falls sideways/diagonally, or needs to stabilize itself for a few steps. This hip shifting is also the reason why our robots can kick the ball without a problem after large side steps. In previous years we often had the problem that the leg would not even reach the ball because it would collide with the ground too early.
NOTE: this is only a shift in the y-axis (left/right).

Reset the start variables of the walk

After each walk step we do a sligth reset of the walk parameters. For example the translations have a starting value like forwardL0, forwardR0, sideL0 and sideR0 (same as rUNSWift). Those define where the translations of the feet are at the beginning of the walk step.

What we do it to use the measured positions of the soles. In specific situations we reset the starting positions to the measured positions. This is partially helpful for errors in the x-translation (forward/backward) after the robot was struggling (e.g. was close to falling backward or forward). But this is very helpful with side walking and turning. Worn-out robots like to have large errors in the hip rolls. If you reset the requested positions closer to the measured ones, the legs start to move more like as if it was a new robot.

A video for comparision is shown below (sorry for back quality, there is a 10 MB limit :( ) The robot in the top half is really struggling to not fall, as the joints do not as requested. The same robot in the bottom half still has some struggles, but walks a lot better, because the code accepts that the joints did not as requested and resets the starting variables.
https://github.com/user-attachments/assets/ee4e3a41-76c4-42a2-97dc-db6f25276f90

*NOTE: we have a convertion function from joint positions to walk variables. Otherwise the kind of reset would not work.

Stretch swing foot

This feature is a "bit" overengineering. Based on the center of mass position in the soles, we decide at the start of a walk phase whether the robot might fall to the side of the swing, if we would not pull the leg together. In such a case we quickly stretch the leg out (in case the kinematic allows for it). This prevents a large amount of falls when walking close to other robots, as those often give smalles pushes from the side. Below is an example from the impact:

WalkDelaySide2.mp4

Other smaller differences

We use a walk height of 230 mm (from sole/ground to origin of the robot between the hips). Also our lift height is 13 mm.
Your walk height is something like 220 mm (my assumption from just looking at your robots playing) and you use a higher lift height. The smaller height helps with stabilizing (as the center of mass is closer to the ground), but I still assume the joints (especially the knees) heat up a lot faster because of it. Also the higher lift height could result in a more unstable walk. Here I can only assume, that once the robot is tilting too much forward or backward, the swing foot will touch the ground later while still being more pulled together. If the lift height would be smaller, the robot would fall less "far" on the swing foot (because the ground collision will occure earlier). I recommend to use video recording to see why robots might fall more after changing it (under the assumption they even fall more). I assume the tip of the toe might collide more often when walking forward, or the heels when walking backwards. But this could still be more stable. For it you could add some artifical bumps on the fields (I used very thin wood from the so called "Baumarkt") to test if the walk is more stable is stress situations. Otherwise just letting the robot walk normally over the field could be too random, as this stresses the robot not enough. But bringing the robot in a stress situation is ideal to see if a change is helpful or more harmful.

image

@Narcha
Copy link
Contributor Author

Narcha commented Jul 23, 2024

Thanks for the input! @philipniklas-r

@philipniklas-r
Copy link

Another thing I noticed, after watching one of the games, is that you seem to have either no acceleration limit, or there is a bug that the robot is allowed to execute a large backward step after walking forward.

I recommend a restriction to force the robot to execute a step with 0 x-translation size when changing the walk direction, or reduce it down to a minimum (which we are doing). Additionally check if a acceleration for the x-translation is actually used (which also could be scaled based on the robot worn-out state).

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
Status: Open
Development

No branches or pull requests

2 participants