Skip to content

Walking

The current walk is inspired by the rUNSWift walk1. It is based on three ideas:

  • As in all walks, the body swings from left to right and back during walking to shift away the weight from the swing foot, allowing it to be lifted above the ground. In contrast to many other walks, this is achieved without any roll movements in the leg’s joints (unless walking sideways), i. e. the swing foot is just lifted from the ground and set back down again, which is enough to keep the torso in a pendulum-like swinging motion
  • As a result, there is a clearly measurable event, when the weight of the robot is transferred from the support foot to the swing foot, which then becomes the new support foot. This event is detected by the pressure sensors under the feet of the robot. At the moment this weight shift is detected, the previous step is finished and the new step begins. This means that a transition between a step and its successor is not based on a model, but on a measurement, which makes the walk quite robust to external disturbances.
  • During each step, the body is balanced in the forward direction by the support foot. The approach is very simple but effective: the lowpass-filtered measurements of the pitch gyroscope are scaled by a factor and directly added to the pitch ankle joint of the support foot. As a result, the faster the torso turns forward, the more the support foot presses against this motion.

Smaller other ideas are added by us to further improve the robustness against disturbances. Those are listed in List of Design Decisions

The module corresponding for the walk is located in Modules/MotionControl/WalkingEngine/WalkingEngine.h. It contains lots of parameters, which are used either directly for generating the joint requests, or to generate the desired step size of a walking step. Note that not all parameters are explained, but only those that might need adjustments, depending on the robots hardware state. The parameters can be found in Config/Robots/Default/walkingEngine.cfg, respectively Config/Robots/Default/walkingEngineCommon.cfg. Parameters in walkingEngine.cfg are those, that need adjustments for different robots more often and are therefore separated into an own configuration file for more readability. Those different needs are more location and scenario depended, e.g. we use different parameters for testing and demos than for competitions. Therefore currently all our robots use the same parameters. Also for competitions we use higher walking speeds. The parameters for those are explained below. We highly recommend to only use higher walking speeds for competitions, to reduce the wear and tear of the robots.

Calculation Cycle

For the walking there consists two modes. A normal WalkPhase or a WalkDelayPhase. The WalkDelayPhase first does a short delay and holds the current position, while it stretches out the coming up swing foot. Afterwards the normal WalkPhase starts.

The WalkPhase itself consist of four parts. The original walk generating from the rUNSWift walk1 , the Walk Step Adjustment2, the JointSpeedControl (JointSpeedRegulation) and JointPositionCompensation (JointPlayOffsetRegulation)3.

The original walk generating part calculates the original target feet poses. The yaw rotation is modified by the JointSpeedControl. As this has an influence on the correct positioning for the feet in the translation space, those targets are adjusted. The Walk Step Adjustment corrects the feet poses in the pitch direction, to prevent walking in the opposite direction of a possible fall. The JointSpeedControl ensures that the support foot does not bring the robot in an even more unstable state, resulting from stuck joint positions, by reducing the maximum speed with which the joint positions can change. The JointPositionCompensation does a similar adjustment, but has the goal to actually compensate the errors in the joint positions and prevent those moving into the already existing joint play.

Walking Diagram

Parameters

The most important parameters in walkingEngineCommon.cfg are as follows:

  • stepSizeParameters.noTranslationYFromRotationFastInner and stepSizeParameters.noTranslationYFromRotationFastOuter: The reduction factor for the sideways translation based on the requested rotation. For worn out robots both might need to be reduced if they fall often when walking around the ball. Currently other parameters help us to prevent the need of adjustment for these parameters.
  • stepSizeParameters.minXForwardTranslationFast: When walking near the ball, the minimal allowed forward step size is equal to this value.
  • stepSizeParameters.minXBackwardTranslationFast: When walking near the ball, the minimal allowed backward step size is equal to this value.
  • stepSizeParameters.minXBackwardTranslationFastRange: When walking near the ball, allow bigger backwards steps (without needed acceleration). The size is scaled down for worn out robots. Otherwise they will fall more often when walking around the ball.
  • useFootSupportSwitchPrediction: The representation FootSupport can predict a support foot switch. With this flag you can decide if you want to use it. The prediction is not used, if the robot is walking backwards, because we noticed that worn out robots will then fall less often.
  • blockStoppingWithStepAdjustment: If set true, the Walk Step Adjustment will try to not walk into the ball as a balancing step.
  • walkStepAdjustmentParams.desiredFootArea: The thresholds for the step adjustment. Defines the percent area in the feet in which the COM should be.
  • walkStepAdjustmentParams.maxVelX: Defines the max allowed translation speed for the step adjustment.
  • balanceParameters: The gyro balancing parameters.
  • soleRotationParameter: The parameters for the swing foot leveling and back catch steps.
  • speedRegulatorParams: The parameters for the joint speed control.
  • walkDelayParameters: The parameters for the walk delay phase.
  • walkSpeedParamsWalkStep: The very maximum a walk step is allowed to do. This is not for regular walk, but to clip the Walk Step Adjustment.
  • sideStabilizeParameters: The parameters for the side hip shift to stabilize side walking.

Parameters of interest located in the file walkingEngine.cfg are as follows:

  • maxSpeed and minSpeed: The maximum and minimum walking speed allowed. Based on the value from the Representation JointPlay the walking will walk slower for worn out robots.
  • maxSpeedBackwards and minSpeedBackwards: The maximum and minimum backwards walking speed. Based on the value from the Representation JointPlay the walking will walk slower for worn out robots.
  • jointPlayOffsetParameters: The parameters for the joint play regulation.
  • walkSpeedParams: The very maximum a walk step is allowed to do. This is not for regular walking, but for e.g. in walk kicks and intercepting balls.

It must be noted, that currently changes to maxSpeed must be done in the configuration file and not in SimRobot over a view or the console. This parameter is loaded and converted when the B-Human process is started, so changes afterward will make no difference. A forced reload can be done with the following command:

dr module:WalkingEngine:init:parameters

Normally, we use the given maxSpeed and minSpeed values. Only at competitions like the GORE or RoboCup we set the following values:

maxSpeed = { rotation = 120deg; translation = { x = 270; y = 230; }; }
minSpeed = { rotation = 100deg; translation = { x = 250; y = 230; }; }

Otherwise the following values are used:

maxSpeed = { rotation = 120deg; translation = { x = 250; y = 200; }; }
minSpeed = { rotation = 100deg; translation = { x = 220; y = 180; }; }

Higher walking speeds are possible too, like 300 sideways ( y = 300 ) or 300 forwards ( x = 300 ). We plan on using those large side walking steps for intercepting balls but not for the regular walk. The walking steps are stable but do not look healthy for the robot. For the forward walking the higher walking speeds result in the robots being tilted more backwards, which in turn unintentionally rotate the robot around the yaw-axis on the field. As a result the robots need to correct their walking path and are walking slower on average. This is most likely a cause of the joint speed control, which balances too extreme at those higher walking speeds.

Note

We highly recommend to only use the higher walking speeds at competitions. Under those conditions, the robots will always first walk slower for the kick off and can actually measure their joint play. Under lab conditions the robots will always start and walk directly to the ball, which increases the risk of falling for worn out robots. Also we are currently analyzing if the higher walking speeds wear the gears faster. At least in edges cases, when the robots postpone a fall for a few walking steps, which happens at higher walking speeds more often, we currently assume a faster wear.

If you are further interested how we calculate the current step, you can find the calculation in the file WalkingEngine.cpp in the implementation of the method getTranslationPolygon. Further calculations like the walk direction are located in the generator modules WalkToPoseEngine, WalkToBallEngine, WalkToballAndKickEngine and DribbleEngine.

You can also use the following command, to see some plot views. They show the requested and measured translations for the feet, balancing values and the adjustment value of the walk step adjustment. Also the 3D drawing from the walk step adjustment are activated. Additionally some requests for the MotionRequest are shown in the console to easily let the robot walk in one direction.

call Calibrators/Walk

List of Design Decisions

For the walking lots of design decisions where made. Each improves the walking a tiny bit, but together result in a very stable and robust walk. A demonstration is uploaded on our youtube channel 5.

Ankle Pitch Balancing

Just like the rUNSWift walk1, we use the y-axis gyro values of the imu and add a portion of it on top of the supporting ankle pitch request. To prevent oscillation the gyro values are filtered by a lowpass filter. When standing both ankle pitches are used but with only half of the value. Also when standing the same process is done with the ankle rolls but with the x-axis gyro values. Note that this ankle roll balancing is not done while walking.

Foot Support

At the start of each control cycle while walking, e.g. whenever new sensor data is received, the FSR sensor data is processed in our module FsrDataProvider. Here we calibrate the 8 pressure sensors based on their individual highest and lowest measured pressure, updated once every 10 seconds while walking. The module FootSupportProvider takes those values, weights them similar to rUNSWift, e.g. giving the outer sensors more weight than the inner ones. Additionally we only accept support foot switches if the new support foot has a minimal measured pressure. This helps on edge cases like when robots walk on their heels to prevent rapidly changing the swing and support foot.

Wrong Support Foot Handling

After about 20-40 % of the walk step (depending on the corresponding code line) the Walk Step Adjustment will only hold the current swing foot position in the x-translation (and apply half of the correction on the support foot), if the swing sole measures pressure. Also all interpolations (except for the height) are frozen if the swing foot measured pressure.

This results in an extremely robust walk under external disturbances, like bumping into other robots.

Also, if the swing foot is detected as the support foot for a longer period of time, an ealier support foot switch will be executed than normally allowed.

Walk Height Duration Increase

The original rUNSWift walk increases the step duration for larger side steps, e.g. from 250 ms to something like 320 ms. As we do not want longer step durations, we keep the 250 ms when side walking. Instead we interpolate the swing foot height slower back to 0, e.g. the side translation is done with the 250 ms, but the height interpolation with the 320 ms. This prevents the swing foot to collide prematurely with the ground.

This is also done for our InWalkKicks. Here the swing foot is often requested to move so fast forward that is would otherwise collide with the ground before touching the ball.

Side Walking Hip Shift

As our walk is allowed to do large diagonal walking steps, we have a big balancing problem: the leftover momentum when closing the feet together after a larger side step pushes the robot in the original side walking direction, even if it just walking straight afterwards. As a result the robot will often fall sidewards or diagonally.

To counteract the problem, we do a sidewards hip shift. After a side step when the feet move close together again, we shift the hip sideways by up to 2 cm, based on the size of the previous and current side step. This trick improves the side walk by a large margin and allows us to walk diagonal with large walking steps like 270 mm/s forward and 230 mm/s sideways within one step, which results in a diagonal walking speed of up to 350 mm/s. Larger side steps like 300 mm/s are possible too. Those are stable but look unhealthy for the robot, whereby we only used it in the dynamic ball handling challenge 2023.

Slow Down Based On Torso Tilt

Similar to HTWK Robots we reduce the interpolation speed of the forward and rotational components when the robot is tilted backwards. This improves the walk at higher walking speeds and gives the robot (and the balancing approaches) more time to react to disturbances.

Special Knee And Hip Gyro Balancing

When walking it can sometimes occur, especially after side or diagonal steps, that the robot has some leftover momentum and will have a significant longer step duration than planned. In those situations the joints of the support foot will at some point overreact and tilt the robot more forward or backward, based on the swinging motion of the torso. This can also occur when the robot is pushed, as seen in the video below.

To stabilize the torso we apply, similar to the ankle pitch balancing, the y-axis gyro values on top of the hip and knee pitches. But the used factor is very small, because we only want to compensate for expected errors of the motor control, which we can not change or overwrite ourself.

Walk Delay Phase

When colliding with other robots, a huge problem is that after a support foot switch the new swing foot will contract in its height. As the robot is still pushed by the other robot, the now swing foot is actually still the support foot. By reducing the height the robot has no support and will just fall in the direction of the swing foot. After the swing foot reaches its max contraction the robot will stop falling, but the damage is already done. The build up momentum is enough to let the robot fall sideways and no balancing technique can prevent that from happening.

Therefore, to prevent this effect from occurring in the first place, we start a so called WalkDelayPhase, if the center of mass (CoM) is to much sideways in the coming up swing foot. For example if the left foot will be the swing foot and the CoM position is more left than normal, the special motion phase will start.

The WalkDelayPhase will expand the new swing foot in its height to push it away from the ground. This is done only for a very short moment, like 36 ms. Afterwards the normal WalkPhase can start. This small push is enough to prevent the robot from falling from the push of the other robot, as the swing foot can finish its walk step and reach its default height again before it touches the ground again.

An example for a very extreme case can be seen below.

Joint Position Resets

A huge problem with the NAO robots is that all the motion control is done by sending requests of joint positions. On all robots, no matter whether new or worn-out (but worse for worn-out ones), the requested positions and measured positions will differ. While a walking step is executed this is not a huge problem and only costs some precision. But once a support foot switch occurs these differences, when too big, can destabilize the robot by a lot. To work with this problem, we use the last JointRequest (from the previous walk step) as a baseline and change the values if necessary closer to the measured positions. To prevent destabilization or jumps some preview calculation is done:

  • Use the last JointRequest to initialize the walking parameters, e.g. starting translations and rotations.
  • Compute the expected sole poses after one motion frame. This includes the WalkStepAdjustment, but not the

Walk Start

For the very first walk step after standing, the maximum height for the swing foot is halved. Until 2019 we noticed that if the robots use the full height interpolation for the first step, the durations of the following steps will be much longer and the robots are walking less stable. With the reduced height this effect does not occur.

As an exception to this are side steps. Based on the executed side step size, for the first walk step the maximum height is interpolated to the normal height, the bigger the side step is.

Automatic Calibration Of The Height Interpolation Duration

For very worn-out robots a huge problem is that the step durations will be often too short. This is because the swing foot has so much joint play, that it can not execute the height correctly and also has some rotational error, which lets the tip of the toe collide prematurely with the ground. An easy trick to work with this problem is to measure and filter the duration of the previous walking steps. In case they were too short the interpolation duration of the swing height is increased, so it reduces the height slower back to 0.

As a side effect the robot will now also walk more unstable in general, as the feet can now move further apart, because they will no longer collide with the ground prematurely. Without a good balancing technique other problems occur. Our Joint Speed Control[ReichenbergRoefer2024] does the much needed balancing to keep the robot upright.

Note

We do not recommend to use this trick, unless good working balancing approaches are used too (like the Walk Step Adjustment with the Joint Speed Control). Otherwise the robot will fall over more often at higher walking speeds. Without the robot will automatically walk slower and fall less often. This was at least the state for our 2021 and 2022 walk.

Back Catch Steps

Under specific conditions the robots will execute a back catching step. Once activated the correction values, which are normally for the swing sole leveling, are used to rotate the swing sole requested 3D pose around the knee joint. This causes the swing sole to rapidly move backwards with a large height above the ground to reduce the risk of a fall. This version was tested as a prototype back in 2022 and is now active in the current version of the walk. For the original prototype see the video below:

For the prototype the catch steps went active the moment the Walk Step Adjustment interfered. This was good for the video but not applicable for actually playing soccer. Therefore we use some conditions to ensure that there are as few false positives (e.g. situations in which it was not necessary) as possible. Also from testing we noticed that the robots would often fall sideways afterwards. To counteract this effect the robot is forced to do a small side step too to spread out the feet to better handle the disruption in the swinging of the torso.

  • Y-Gyro: The gyro must be negative and measure a minimal value. It is also used as a scaling for the other thresholds
  • Walk Step Adjustment delta: The center of mass must be a minimal value outside of the defined safe supporting area
  • Torso pitch rotation: The torso must have a minimal rotation

We currently have no physics model of the robot about how it will behave. We assume a modeling of the velocity of the robot would already be enough to change those conditions into a smooth interpolation between the current motion behavior and the final back catch step. But for now it already prevented a handful of falls at the RoboCup 2023 competition.

An example from testing at the RoboCup 2023 is shown below:

Interpolation Freeze

After some time in the walk step, currently for us after 35 % of the step duration, we stop the translation interpolation for the forward, side and rotational movement, if the swing foot measures ground contact. The height interpolation is not effected by this. This smooths out our walking and puts less stress on the joints when doing a foot support switch. Also it prevents unintentionally walking in the opposite direction when the wrong sole gets ground contact, which often happens when colliding with other robots.

Note

This is only possible, because we filter and calibrate the FSR data of the soles while walking. Without it this approach has lots of false positive detections and is not recommended.

Intercepting Ball

If the behavior set the flag shouldInterceptBall in the MotionRequest, then the current executed walk step is partially overwritten in the function updateDynamicStep().

In that case, the InterceptBallGenerator is used to calculate a new intercepting step. This one is not fully used, but interpolated into. Also different balancing values are updated afterwards. This is done to ensure stability and preventing the feet to move faster than normally intended.

Note

This intercepting update is only execute if the paramter dynamicStepUpdate from the WalkingEngine (found in walkingEngineCommon.cfg) is set to true. We recommend to only use this feature in competitions. As the robot will suddenly change the walking direction with a large side steps (larger than normally while walking), this will put more stress on the robot than usual and wear down the joints faster.

Note

The size of those intercepting walk steps can be configured with the parameter walkSpeedParams in walkingEngine.cfg.

Safe Usage with Humans

To reduce the risk by human intervention, the robot behaves different when picked up or losing ground contact. The stiffness is reduced from 100 to 30 percent, the gyro balancing is reduced to 0 and the Walk Step Adjustment can only hold the feet positions but not move them anymore. Also a new step will only start after a few seconds and force the robot to return to the 0 step, which means 0 rotation and 0 translation.

Note

Once the robot loses the ground contact the fall protection is no longer active. Only the stiffness of the robot is reduced to prevent most harm.

Walk Step Adjustment

The Walk Step Adjustment2 is not described here and we refere to our paper, which gives a deeper look into how it works. Here we only give a short summary about the key ideas. The implementation can be found at Modules/MotionControl/WalkingEngine/WalkLibs/WalkStepAdjustment.cpp.

The Walk Step Adjustment consists of two parts. Part one ensures the robot does not walk in the opposite direction of a potentional fall. For example if the robot is tilting backwards and there risks falling back, the planned sole positions are overwritten and the adjustment drags the swing foot back. Same goes when the robot is tilting forward and risks falling to the front, the swing foot is dragged forward. To prevent the robot to just shift the torso as a result, half of the applied position change is added on top of the support sole too. This procedure forces the robot to walk in the direction of an expected fall. Note that this is only done in the x-axis, the forward and backward direction, but not to the side. From experiments this axis is more unstable and disturbances to the sides are less of a problem.

The second part is the compensation of the swing foot sole rotation. From observations and evaluating logs we noticed that the motor controls show large errors when the robot is disturbed or walking unstable, as seen below. Left a robot under normal circumstances, right the robot with errors in the supporting sole (right sole), which results in the swing foot (left foot, red line) colliding with the ground (green line) prematurely. Different joints tend to move too fast, too low, lag behind or are not moving at all. This tilts the robot more forward or backward. As the planned walk expects the soles to move parallel to the ground, a few degree tilting error are enough to let the swing foot collide prematurely with the ground, which in turn destabilizes the robot even further. Our compensation handles the problem by using the rotational error of the supporting foot and applying it on top of the swing foot. As this compensation is only helpful while the walk step is executed, but would let the robot fall even further after a support foot switch, it is reduced back to 0 after 75 % of the step duration.

Motion Framework

Joint Speed Control

The Joint Speed Control3 is not described in detail here and we refere to our paper. The implementation can be found in multiple files. Modules/MotionControl/WalkingEngine/WalkLibs/WalkPhaseBase.cpp implements the function applyJointSpeedRegulation(). Here the actual object jointSpeedRegulator is called, which implements the control. Also in Modules/MotionControl/WalkingEngine/WalkingEngine.cpp in the function calcJoints() the jointSpeedRegulator is used multiple times to apply the control. Note that the jointSpeedRegulator needs to be initialized for each walk step, which is done in additional functions. Apart from the speed control, the joint play is also handled afterwards by the object jointPlayOffsetRegulator, also called in the function calcJoints(). The implementations of both regulators can be found in Tools/Motion/JointPlayOffsetRegulator.cpp and Tools/Motion/JointSpeedRegulator.cpp.

The short summary of the control is that we expect the motors to be not sufficient enough for the NAO, based on years of experience with the robot. Therefore we assume joints to slow down or became stuck in their last position when experience disturbances or walking unstable. Our Joint Speed Control uses this assumption to synchronize the requested positions with the real positions of the support leg and compensates errors while the walk step is being executed. This is different to our joint position reset, which is done once when a support foot switch occurs.

The resynchronization is done in two steps. First the position changes are seen as velocities, which are regulated as follows:

  • Calculate the maximum position change for each support leg joint that is expected to happen in the next walk step. Add a small bonus on top of it
  • Based on the y-axis rotational error of the support sole and the position of the center of mass (com) in the support sole, determine a value between 0 and 1 for the forward/positive direction and the backward/negative direction.
    • Forward direction describes the com position and is 1 if it is at the toe (or further) and 0 if it is at the heel (or further).
    • Positive and negative describes the rotational error of the support sole.
    • These values are combined into two factors, one to described the risk to fall forward and one to described the risk falling backward.
  • In each motion frame the planned change in the position request for the support leg joints are reduced based on this calculated values.
    • If the position change results in no destabilization, the change is clipped to the previously maximum allowed position change
    • If the position change results in further destabilization, the change is clipped down to a minimum configured value.
    • For all cases in between an interpolation is used.

As an example, when the robot is walking forward, the ankle pitch of the support sole will need to steer up for a more negative position. This is due the kinematic of the robot. Under normal circumstances this needs no further attention. But when the calculated control values represent that the robot risks falling forward, we assume some other joints will slow down or become stuck. In such a scenario this tilting of the ankle pitch will tilt the sole of the robot, which in turn will tilt the whole robot and it might fall forward. Joint Speed Control will use the control values to reduce the speed which is used to let the ankle pitch occupy a more negative position. This regulates the rotational error of the support sole and also the com position. The resulting translational error, which can become quite large, is an accepted compromise. A stable walk is more desirable than exact walking steps, because those exact executions do not matter when the robot falls.

In a second step the the joint position errors are directly handled. Because of worn-out joints and the so called joint play it can happen that the real joint already reached a position which will be requested in the near future (like in a few motion frames). Once again due to observation of the real robots and many experiments we use the assumption that the joint will keep moving based on the requested position change, even if it would need to move in the opposite direction to reach the actually requested position. Therefore we use a prediction of the future joint position4 and the requested one to determine an error. This is then used to reduced the planned position change.

  • For example (no unites to simplify): The measured ankle pitch is at position 10, the prediction at 9, the last request at 12 and the current at 11.5. Only the change of both requests (12 and 11.5) of -0.5 is reduced down to 0, even though the difference between the prediction (9) and the current request (11.5) is larger (-2.5). The new request is therefore still 12.
  • Another example: The measured ankle pitch is at position 10, the prediction at 9, the last request at 12 and the current at 13. Here no change is applied and the new request remains at 13.
  • Another one: The measured ankle pitch is at position 10, the prediction at 9, the last request at 12 and the current at 8. Here the planned request change of -4 is reduced to -1. The difference between the prediction (9) and the request (8) is 1. Here we highly assume that if we change the requested position from 12 to 11, the real ankle pitch will also change by a difference of -1 from 9 to 8, which is our true target.

Note

This is only a simplification of the idea. We refere to our paper and the actual implementation for more details.

Currently Known Problems

  • The camera shakes a lot.
  • When walking to the ball, the robots tend to walk closer than commanded.
    • This effect occurs mostly on worn-out robots (which B-Human has plenty of).
    • When stopping, the robot tilts forward from the previous forward momentum. The joint play takes this opportunity and the Walk Step Adjustment forces the robot to walk a bit more forward.
    • This effect can be reduced by using slower walking speeds near the ball.
    • A video of this problem is shown below.
    • If the head is tilted down near the ball, the center of mass is moved forward.
  • Walking with a forward speed of over 300 mm/s is possible even on worn out robots, but the joint speed control regulates too extremely.
    • As a result, the robots are tilted too much backwards most of the time. This causes the robots to rotate more unintentionally. The walking path needs to be corrected, this results in an overall slower walk.
  • In-walk kicks have three precision types. The type justHitTheBall results in most falls when kicking the ball.
    • After a side walk step, those kicks can hit the ball as intended because of our side hip shift. This side shift of the hip needs to be remained to reduce the occurrence those falls.


  1. Bernhard Hengst. - rUNSWift Walk2014 report. Technical report, School of Computer Science & Engineering University of New South Wales, Sydney 2052, Australia, 2014. 

  2. Philip Reichenberg, Thomas Röfer - Step Adjustment for a Robust Humanoid Walk. In RoboCup 2021: Robot World Cup XXIV, volume 13132 of Lecture Notes in Artificial Intelligence, pages 28-39, Springer, 2022 Best Paper Award Finalist. 

  3. Philip Reichenberg, Thomas Röfer - Dynamic Joint Control For A Humanoid Walk. RoboCup 2023: Robot World Cup XXVI, Lecture Notes in Artificial Intelligence, Springer, 2024, to appear. 

  4. Jan Fiedler, Tim Laue - Neural Network-Based Joint Angle Prediction for the NAO Robot. RoboCup 2023: Robot World Cup XXVI, Lecture Notes in Artificial Intelligence, Springer, 2024, to appear 

  5. Robust Walk Demonstration: https://www.youtube.com/watch?v=NKo7-wrIHlU 


Last update: October 26, 2024