Skip to content

Motion Control

In the motion part of B-Human exist multiple important modules, which can be configured with parameters in a huge variety. In this chapter a subset of parameters are explained in more detail, to help in the development and working with such modules. Also editing features are described, to create new motions more easily.

WalkingEngine

Here the module Modules\MotionControl\WalkingEngine\WalkingEngine.h 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 needed adjustments for different robots more often and are therefore separated into an own configuration file for more readability. Currently all our robots use the same parameters. Also for competitions we use higher walking speeds. The parameter for those are explained below.

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 WalkStepAdjustment 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.
  • footStepping.useSteppingOnOpponentFootBehavior: Activates the balancing behavior when stepping on another robots foot. We recommend to not use it, because of too many false positives in the detection.
  • balanceParameters: The gyro balancing parameters.

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

  • maxAcceleration: The allowed forward and sideways acceleration between steps. In case of a worn out robot the forward acceleration might need to be reduced. The side acceleration is currently ignored.
  • 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.

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. Normally, we use the given maxSpeed and minSpeed values. Only at competitions like the GORE 2022 or RoboCup 2022 we set the following values:

maxSpeed = { rotation = 120deg; translation = { x = 300; 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; }; }

We also measured the actual executed speeds, and the robots will walk always a bit faster, sometimes even worn out robots with a speed of 250 mm/s forward will still walk 300 mm/s. For the sidewards direction the actual speed varies between 230 and 280 mm/s.

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 calculation 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 requested for the MotionRequest are shown in the console to easily let the robot walk in one direction.

call Calibrators/Walk

Currently Known Problems

This is a list of currently known problems with the walking:

  • Worn out robots cannot walk backwards. Our behavior / walk generators try to prevent such walking direction as much as possible.
  • The camera shakes a lots
  • Worn out robots like to do crazy steps, which are not healthy for the joints. Overall the wear of the gears are still minimal and only once a joint is very loose, it starts to gain more wear and eventually breaks.
  • Sometimes the robots stumble and will not fall, but will need a few seconds to stabilize again
  • When walking to the ball, the robots tend to walk closer than commanded.
  • Walking with a forward speed of over 300 mm/s is possible, but mostly only on completely new robots. Otherwise the robots tend to get stuck with the swing foot in the ground and just fall. If the parameter useFootSupportSwitchPrediction is set to false, this improves by a lot. We still recommend to not use higher walking speeds.
  • Side walking speeds of over 300 mm/s are possible (and were used 2021 in the passing challenge). But the robots tend to get a lot more unstable if used while walking around. Also they rotate a lot more unintentionally.
  • Walking close to the ball often results in unstable situations, because the walk step adjustment tries to avoid touching the ball. This can currently only be reduced by changing the threshold, which is used to determine how much the walk step adjustment is clipped near the ball.

KeyframeMotionEngine

Keyframe motions are hardcoded interpolations from a start to goal joint configuration, with multiple intermediate steps. They are used for getting up, but also for special postures like goal keeper motions. They can be configured with a handful parameters, to fulfill the need for a simple motion like waving or getting up from the ground even under harsh conditions. The parameters can be found in Config\Robots\Default\keyframeMotionEngine.cfg. Additionally it exist Config\Robots\Default\keyframeMotionParameters.cfg, which contains the parameters for the balancing behavior.

Note

When the robot is trying to get up, you can touch the head sensors to stop the motion. The robot will immediately interpolate into a stand pose. If held upright or standing on the ground, the WalkingEngine takes over, otherwise the robot will start a new get up try.

Keyframe Parameters

An example of a keyframe motion is shown below:

// [...] config entries left out
motions = {
  recoverGeneric = {
    keyframes = [recover];
    balanceOut = false;
    keyframeEndRequest = {energySavingLegs = none; energySavingArms = none; isStandHigh = false;};
    isMotionStable = false;
    startAsNextPhaseMotion = [
      {
        startAsNextPhase = front;
        conditions = [
          {
            variable = InertialDataAngleY;
            range = {min = 0; max = 2000;};
            isNot = false;
          }
        ];
        isAndCondition = false;
      },
      {
        startAsNextPhase = back;
        conditions = [
          {
            variable = InertialDataAngleY;
            range = {min = 0; max = 2000;};
            isNot = true;
          }
        ];
        isAndCondition = false;
      }
    ];
  };
// [...] config entries left out
keyframeBlock = {
  stand = {
    baseLimbStiffness = [40, 75, 75, 75, 75];
    keyframes = [
      {
        phase = UnknownPhase;
        duration = 200;
        goalCom = {x = 0; y = 0;};
        setLastCom = false;
        forbidWaitBreak = false;
        interpolationType = Default;
        jointCompensation = [
          {
            jointCompensationParams = [
              {
                jointDelta = lHipYawPitch;
                hipPitchDifferenceCompensation = false;
                range = {min = 1deg; max = 10deg;};
                jointPairs = [
                  {joint = lHipPitch; scaling = 1;},
                  {joint = rHipPitch; scaling = 1;}
                ];
                predictJointDiff = false;
              }
            ];
            reduceFactorJointCompensation = 0.2;
          }
        ];
        waitConditions = [];
        keyframeBranches = [
          {
            blockID = front;
            motionID = [restartFront];
            initStiffness = true;
            removeCurrentBlock = true;
            preCondition = {
              conditions = [
                {
                  variable = ShoulderPitchLeft;
                  range = {min = 50; max = 2000;};
                  isNot = false;
                },
                {
                  variable = ShoulderPitchRight;
                  range = {min = 50; max = 2000;};
                  isNot = false;
                },
                {
                  variable = ShoulderRollLeft;
                  range = {min = -2000; max = 20;};
                  isNot = false;
                },
                {
                  variable = ShoulderRollRight;
                  range = {min = -20; max = 2000;};
                  isNot = false;
                }
              ];
              isAnd = false;
            };
            useEarlyEntrance = false;
            earlyEntranceCondition = {conditions = []; isAnd = true;};
            maxNumberOfLoopsBlockID = -1;
            maxNumberOfLoopsMotionID = 1;
          }
        ];
        balanceWithJoints = {jointY = []; jointX = [];};
        singleMotorStiffnessChange = [];
        angles = {
          head = [0deg, -30deg];
          positions = {
            leftArm = [-13.9deg, 68.2deg, -122.2deg, -11.1deg, -90deg, 0deg];
            rightArm = [-13.5deg, -67.9deg, 121.9deg, 8deg, 90deg, 0deg];
            leftLeg = [-3.9deg, -0.2deg, -84.6deg, 123.7deg, -52.9deg, 2.3deg];
            rightLeg = [-3.9deg, -0.7deg, -80.2deg, 122deg, -47.9deg, 2.2deg];
          };
        };
        robotPoses = [];
        torsoAngleBreakUpEnd = {
          pitchDirection = {min = -10deg; max = 2000deg;};
          rollDirection = {min = -2000deg; max = 2000deg;};
        };
        torsoAngleBreakUpStart = [];
      },

The configuration file contains two list: motions and keyframeBlock. In motions you can find all higher level motions, while in keyframeBlock you can find motion-parts, which can be recycled for different usages.

Following are some parameters explained for motions:

  • keyframes: List of keyframeBlock motions. They will be executed one after another.
  • keyframeEndRequest: Flags for the energy saving mode, to prevent overheating.
  • startAsNextPhaseMotion: After this motion is finished, you can set different follow up motions. Like after a goal keeper catch motion, the robot can do a special get up motion if it is still upright.

Following are some parameters explained for the keyframeBlock:

  • phase: Defines which balancing parameters shall be used
  • interpolationType: Defines the kind of interpolation, like linear oder sinus curve based.
  • jointCompensation: Sets parameters for the joint compensation. If a joint in this list gets stuck, the error will be used to apply offsets on the given compensation joints, to keep the robot in a stable position.
  • keyframeBranches: To allow branches in the keyframe execution, like condition extra keyframe or breaking up and starting a completely different motion, you can define a blockID, which is a motion from the motions list, or a motionID, which is a motion from the keyframeBlock list. if motionID is set, blockID is ignored. The flag removeCurrentBlock is used, to decide if the current motion shall be removed, or still be executed afterwards. preCondition and earlyEntranceCondition are used as conditional checks, whether the branch shall be executed and if the checks are, then all the time (earlyEntranceCondition) or only at the end of the keyframe interpolation (preCondition).
  • balanceWithJoints: Defines which joints shall be used for the balancing.
  • angles: The target positions of the joints.
  • robotPoses: Currently unused and not fully implemented. If set, replaces angles with Cartesian space positions, which are converted into target joint positions.
  • torsoAngleBreakUpEnd: Constraints for the torso orientation. If the torso orientation is outside those boundaries, the motion is aborted.
  • torsoAngleBreakUpStart: Start value for the constraints of the torso orientation. Will interpolate to torsoAngleBreakUpEnd over the keyframe duration.

Balancing Parameters

An example of the balancing parameters are shown below:

Split = {
  balanceFactor = {
    maxValAdditionalScaling = {
      pitchDirection = {min = 1; max = 3;};
      rollDirection = {min = 1; max = 1;};
    };
    exponentFactorScaling = {
      pitchDirection = {min = 2; max = 2;};
      rollDirection = {min = 2; max = 2;};
    };
    pidPPitchParameter = {baseValue = 4; maxAdditionalValue = 5;};
    pidPRollParameter = {baseValue = 1; maxAdditionalValue = 0;};
    pidDPitchParameter = {baseValue = 1; maxAdditionalValue = 1;};
    pidDRollParameter = {baseValue = 1; maxAdditionalValue = 0;};
  };
  comDiffBase = {
    pitchDirection = {min = -50; max = 20;};
    rollDirection = {min = -20; max = 60;};
  };
};

Following are the parameters explained:

  • balanceFactor: Contains parameters for the PID-Controller, which is used for the balancing. This controller is separated into forwards/backwards (pitch) and sideways (roll) balancing. Both directions use different balancing values, to compensate with the leg structure and the design of the feet sole, eg. as balancing against a forward tilt is different than against a backward tilt.
  • pid[P|D][Pitch|Roll]Parameter: Base values for the PID-Controller.
  • maxValAdditionalScaling: Max additional scaling for the PID-Controller parameters.
  • exponentFactorScaling: Defines how fast the maxValAdditionalScaling is applied.
  • comDiffBase: The value range for the CoM. The range from 0 to the border values is used to scale the PID-Controller parameters.

Adding New Keyframe Motions

Despite the available motions, you may add further ones to the file following the same structure under a new id. The new id has to be appended of the enumeration KeyframeMotionListID within the file Src/Modules/MotionControl/KeyframeMotionEngine/KeyframeMotionLibs/KeyframePhaseBase.h. Also the new motion must be added in keyframeMotionEngine.cfg. Here it is recommended to copy an existing motion or start SimRobot, load a scene (e.g. BHFast.ros2) and save the parameters with the console with the command save parameters:KeyframeMotionEngine.

To add a new keyframeBlock you need to add the new id in the same file in the enumeration KeyframeMotionBlockID.

If the new motion shall be used as a special motion, like a goal keeper jump, which shall be callable from the behavior, you also need to add an id in the file Src/Representation/MotionControl/KeyframeMotionRequest.h in the enumeration KeyframeMotionID. For ball catching motions, you also need to add a new id in the enumeration Src/Representation/MotionControl/MotionRequest.h Dive::Request and add a conversion in Src/Representation/MotionControl/KeyframeMotionRequest.cpp.

Note

We currently have no tools to design new keyframe motions. For "some" debugging information, you can look into the representation KeyframeMotionGenerator. Feel free to extend this representation.

Current Problems

Here we list current problems:

  • Some transitions between different keyframe blocks are longer than needed.
  • Some conditional branches, like the restart for the front motion, could have better thresholds. They are executed too often.
  • The keyframe structure was rebuild to allow more "catch" motions, like when falling backward to use the genuflect or when falling forward to use a front catch motion. Both did not work great and were removed after the first day of the RoboCup 2022. They are planned to be added back in the future.
  • The joint compensation is sometimes too much, if the joints used to compensate are stuck. This can result in an overcompensation and the robot falls to the opposite direction.
  • The break up thresholds could be improved.

WalkKickEngine

For in walk kicks the WalkKickEngine uses lots of parameters to define how specific kicks are executed.

Parameters

An example of a subset of the parameters, which can be found in Config\Robots\Default\WalkKickEngine.cfg are shown below:

[...]
walkKicksWithRestrictedStart = [forward, turnOut, forwardAlternative, forwardLong];
[...]
forward = {
  maxXDeviation = {min = -100; max = 40;};
  maxYDeviation = {min = -40; max = 40;};
  additionalXDeviation = {min = 0; max = 10;};
  additionalYDeviation = {min = -25; max = 25;};
  additionalXDeviationJustHitTheBall = {min = -20; max = 20;};
  additionalYDeviationJustHitTheBall = {min = -25; max = 90;};
  maxAngleDeviation = 6deg;
  maxClipBeforeAbortX = {min = -200; max = 80;};
  maxClipBeforeAbortY = {min = -15; max = 15;};
  maxClipBeforeAbortRot = {min = -6deg; max = 6deg;};
  maxClipBeforeAbortJustHitTheBallX = {min = -200; max = 80;};
  maxClipBeforeAbortJustHitTheBallY = {min = -50; max = 50;};
  maxClipBeforeAbortJustHitTheBallRot = {min = -8deg; max = 8deg;};
  sideDeviationScalingBasedOnLastStep = {min = -0.2; max = 0.2;};
  kickKeyFrame = [
    {
      [...]
      useSlowSupportFootHeightAfterKickInterpolation = false;
      useSlowSwingFootHeightInterpolation = 0;
      overrideOldSwingFoot = none;
      overrideOldSupportFoot = none;
      numOfBalanceSteps = 0;
      keyframes = [
        {
          relativePositionToBallMax = {x = -150; y = -100;};
          relativePositionToBallMin = {x = -150; y = -100;};
          offsetSwingFootMax = {x = 0; y = 0;};
          offsetSwingFootMin = {x = 0; y = 0;};
          [...]
          directionRatio = 1;
          reachPositionRatio = 0.5;
          speedUpSwingPositionScaling = {min = 1; max = 1;};
          useDefaultReachPositionRatio = false;
          [...]
        },
        [...]
      jointOffsets = [
        {
          joint = lHipPitch;
          offset = -15deg;
          minRatio = 0.25;
          middleRatio = 0.65;
          maxRatio = 1;
          minimumRatio = 0.25;
          shiftByKeyFrame = -1;
        },
        {
          joint = lAnklePitch;
          offset = 10deg;
          minRatio = 0.4;
          middleRatio = 0.65;
          maxRatio = 1.2;
          minimumRatio = 0.5;
          shiftByKeyFrame = -1;
        },
        {
          joint = lKneePitch;
          offset = -10deg;
          minRatio = 0.5;
          middleRatio = 0.65;
          maxRatio = 0.85;
          minimumRatio = 0.5;
          shiftByKeyFrame = -1;
        }
      ];

Following are the parameters explained:

  • walkKicksWithRestrictedStart: List of all kicks, that have restricted starting conditions. This is done because the robots are not able to change their walking direction immediately, therefore standing still for one or two walking steps are needed to ensure that the kick is executed correctly. This is mainly due the constraint, that each walking step has a duration of 250 ms, which is not enough to execute every kick from every starting state. If in the MotionRequest the field alignPrecisely is set to justHitTheBall, then those restrictions are ignored.
  • walkKicksList: Contains all kicks, with forward used as an example.
  • max[X|Y]Deviation: Describes the max allowed deviation to the ball, compared to the planned position in kickInfo.cfg. Otherwise the robot might try to kick a ball that is still too far away and not even reachable. These deviations are additionally increased with the parameters additional[X|Y]Deviation and additional[X|Y]DeviationJustHitTheBall, based on the alignPrecisely field in the MotionRequest.
  • maxClipBeforeAbort[JustHitTheBall][X|Y|Rot]: Describes the max allowed clipping of the planned step sizes to the to be used ones. Are the difference higher than the values in those parameters, the kick is aborted (or not even started).
  • kickKeyFrame: Contains the steps of the kick.
  • useSlowSupportFootHeightAfterKickInterpolation: Let the last support foot interpolate its height slower back to zero than normal. This is important for strong kicks like forwardLong.
  • useSlowSwingFootHeightInterpolation: The WalkingEngine increases the step height duration interpolation based on the side step size. This value is used to replace the side step size to increase the step height duration. This helps to prevent for stronger kicks an early ground contact.
  • overrideOld[Swing|Support]Foot: Defines if feet positions of either foot shall be set based on the last joint request or last measured joints, not neither of both. Again this is important for strong kicks, as those result in a huge difference between what was requested and what the robot actually did.
  • numOfBalanceSteps: Sets how many walking steps after the kick the WalkingEngine shall calculate more stable step sizes.
  • keyframes: Contains the keyframes for the current step. In theory this allows for more curved walking steps.
  • relativePositionToBall[Max|Min]: Describes the relative position to the ball, which is used to determine the needed step size. Min and max are used to interpolate based on the requested kick power.
  • offsetSwingFoot[Max|Min]: Shifts the step size in a way, that it is not symmetrical distributed 50 % on the support foot and 50 % on the swing foot, but asymmetrical. The shift is used with the relativePositionToBall[Max|Min]. Once again based on the kick power the shift is interpolated.
  • directionRatio: Defines how much the requested rotation shall be converted. This allows that if more than one keyframe is used, the goal rotation is not reached within the first keyframe, but distributed over all keyframes.
  • reachPositionRatio: Is the interpolation factor for the keyframes. This one is only used if useDefaultReachPositionRatio is set true. Otherwise a dynamically calculated one is used.
  • speedUpSwingPositionScaling: Factor to interpolate the swing foot faster.
  • The jointOffsets are a list of additional offset, to force specific joints to move in a specific way. For example the joint lHipPitch shall gain an offset of -15°, interpolated with a sinus function from 25 % of the walk step (minRatio) to 100 % at a ratio of 65 % of the walk step (middleRatio). Afterwards the offset is interpolated back to 0° until the walk step ratio of 100 % (maxRatio). These interpolation values can be dynamically shifted based on the current keyframes (shiftByKeyFrame), to ensure some synchronicity between the offsets and the executed walk step. To allow this shift, shiftByKeyFrame must be set to the keyframe which shall be used as reference.

Adding new Kicks

To add new kicks, you need to add two different ones. First in the file Representation\Configuration\KickInfo.h you need to add the new kick for the left and right foot and also add them in the configuration file kickInfo.cfg. These two kicks are used from the behavior to select your new kick. The actual new kick must be added in Tools\Motion\WalkKickType.h. Last but not least you need to add the new kick in Config\Robots\Default\WalkKickEngine.cfg. You can also skip the last step and simply load a scene in the simulation and use the command save parameters:WalkKickEngine.

Note

All kicks are defined with the left leg being the kick leg.

Current Problems

Here we list the current problems:

  • The kicks are unreliable, because the supporting foot often slips, which results in the swing foot not reaching the ball
  • The forward and turn kick are interpolating to slow. Therefore the robot will just barley touch the ball. This causes the robot to dribble only a small distance of 50 to 300 mm, but 750 mm are actually planned.
  • The turn kick slips in the second part (after the pre step, in the kick step) which causes the robot to not turn correctly and miss the ball.
  • The mode justHitTheBall causes the robot to do unstable kicks. It is only used in duels with other robots.
  • The mode justHitTheBall causes the robot to execute kicks, which are unable to hit the ball.
  • At the start of a walk kick phase, the difference between the measured swing foot position and the starting requested one can be large, which lets the swing foot move unintentionally backwards before kicking the ball.

Arm Motions

For arm only motions the ArmKeyFrameEngine is used. It can only be active while walking or standing. We only use this engine to move the arm on the back to avoid colliding other robots.

Arm motions are configured in the file Config\Robots\Default\armKeyFrameEngine.cfg.

Parameters

An example is listed below

allMotions = [
  {
  id = back;
  states = [
    {
      angles = [119.5deg, 10deg, 75deg, -10deg, -90deg, 0deg]; // ShoulderPitch, ShoulderRoll, ElbowYaw, ElbowRoll, WristYaw, Hand
      stiffness = [90, 60, 80, 90, 90, 90];
      duration = 800;
      interpolation = linear;
    },
    [...]
  • allMotions: Contains the list of all arm motions, except reverse.
  • id: The name of the arm motions.
  • states: The keyframes
  • angles: The target joints.
  • stiffness: The stiffness values.
  • duration: Interpolation duration.
  • interpolation: The interpolation type, like linear or sinus.

Adding new Arm Motions

Despite the available motions, you may add further ones to the file following the same structure under a new id. The new id has to be appended to the end of the enumeration ArmKeyFrameId within the representation Src\Representation\MotionControl\ArmKeyFrameRequest.h. The new id must be listed after default but before reverse.

It is important to know that all motions will only be declared for the left arm.

Replay Walk Request

Sometimes a robot fell in a test or competition game. To better analyze if this was just bad luck or an actual weakness of the current walk or walk kicks, the ReplayWalkRequest can be used to analyze such an event of interest (EoI).

To use this module, start the ReplayRobot scene and load a log file of interest. Afterwards use the command

call Calibrators/ReplayWalkRequest

Skip to the EoI. We recommend to start a few seconds before the EoI. Afterwards use the following command to start recording the walk steps

set module:ReplayWalkRequestProvider:startRecord true

After the EoI occurred, use the following commands to stop recording and save the informations

set module:ReplayWalkRequestProvider:startRecord false
save parameters:ReplayWalkRequestProvider

The recording can be found in Config\Robots\Default\replayWalkRequestProvider.cfg. The recording will be listed last with an unknown description. You can change it with a name of your choice. To replay the recording on the real NAO (or in the simulation), deploy the robot with the scenario ReplayWalk. Afterwards bring the robot into the penalize state and use the foot bumpers to switch between all recording. The robot will say the description. When switching to the playing state, the robot will start replaying the selected recording.

Note

The robot must be deployed after creating a new recording. We recommend to add two walk steps by hand with a step size of 0.1 for the x-translation. This forces the robot to walk in place before starting to replay the recording. You can also add a few steps at the end to ensure the robot keeps walking after the EoI. If the robot stops walking, even though the replay is not finished yet, it is because of a false foot support switch. If this occurs every time, you may want to edit the parameter isLeftPhaseStart or the y-translation of the first few steps. A left phase can only execute ≥ 0 y-translations and the right phase only ≤ 0 y-translations. This check is used to abort the replay.