Skip to content

Motion Excurs

In the motion part in B-Human exist multiple important modules, which can be configurated 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 walkingEngineCommon.cfg are those, that needed adjustments for different robots more often and are therefore seperated into an own configuration file for more readability.

Parameters

The most important parameters in 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.
  • noTranslationYFromRotationFastInner and 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.
  • minXForwardTranslationFast: When walking near the ball, the minimal allowed forward step size is equal to this value.
  • minXBackwardTranslationFast: When walking near the ball, the minimal allowed backward step size is equal to this value.
  • odometryScale: The steps are not executed perfectly. With this parameter you can tune the odometry.
  • useFootSupportSwitchPrediction: The representation FootSupport can predict a support foot switch. With this flag you can decide if you want to use it.
  • desiredFootArea: The thresholds for the step adjustment. Defines the percent area in the feet in which the COM should be.
  • maxVelForward: Defines the max allowed translation speed for the step adjustment.
  • useSteppingOnOpponentFootBehavior: Activates the balancing behavior when stepping on another robots foot.

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

  • maxSpeed: The maximum walking speed allowed. For worn out robots you might want to reduce these values.
  • gyro[Forward|Backward|Sideways]BalanceFactor: Gyro balance factors for the ankle.

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.

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 configurated 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
fromSplit = {
  baseLimbStiffness = [30, 40, 40, 100, 100];
  lines = [
    [..]
    {
      phase = Split;
      duration = 100;
      goalCom = {x = -10; y = 0;};
      setLastCom = false;
      optionalLineAnds = false;
      isElseBlock = false;
      isPartOfPreviousOptionalLine = false;
      forbidWaitBreak = false;
      interpolationType = Default;
      jointCompensation = [
        {
          jointCompensationParams = [
            {
              jointDelta = lHipYawPitch;
              hipPitchDifferenceCompensation = false;
              minVal = 0;
              maxVal = 15;
              jointPairs = [
                {joint = lHipPitch; addValue = 0.53;},
                {joint = lAnkleRoll; addValue = 0.53;},
                {joint = rAnklePitch; addValue = 0.467;},
                {joint = rAnkleRoll; addValue = -0.53;}
              ];
              predictJointDif = false;
            }
          ];
          reduceFactorJointCompensation = 0.2;
        }
      ];
      waitConditions = [];
      conditions = [];
      balanceWithJoints = {
        jointY = [
          {joint = lAnklePitch; factor = 1;},
          {joint = rAnklePitch; factor = 1;}
        ];
        jointX = [];
      };
      balancerActive = true;
      singleMotorStiffnessChange = [
        {joint = lShoulderPitch; s = 20;},
        {joint = lShoulderRoll; s = 20;},
      ];
      head = [0, 0];
      leftArm = [90, 30, -50, 0, -90, 0];
      rightArm = [90, -30, 50, 0, 90, 0];
      leftLeg = [-40, 6.5, -60, 123, -33, -10];
      rightLeg = [-40, -15, -87, 123, -17, 10];
    }
  ];
  odometryOffset = {
    rotation = 0deg;
    translation = {x = 50; y = 70;};
  };
  balanceOut = true;
  continueTo = decideAutomatic;
  clipAngle = 0deg;
  energySavingLegs = false;
  energySavingArms = false;
  isMotionStable = false;
  interpolationType = Linear;
}

fromSplit is the name of the motion. baseLimbStiffness is the default stiffness for each limb, in the sequence head, left arm, right arm, left leg, right leg. lines are the keyframes. phase is the type of the keyframe. With it the corresponding balancing parameters are used. duration is the duration of the keyframe. goalCom is the reference COM that shall be reached at the end of the keyframe. setLastCom uses the previous reference COM or the measured one as a start value. optionalLineAnds relation between the conditions (condition and waitConditions) as AND or OR. isElseBlock is the keyframe part of an else block. isPartOfPreviousOptionalLine is the keyframe part of the previous if block. forbidWaitBreak if a waitCondition is given, can the wait time be aborted early. interpolationType the interpolation type for the keyframe. Default used the defined one for the motion. jointCompensation defines which joint is compensate with which joints and their compensation factor. waitConditions condition that must be true to start the next keyframe. conditions conditions that must be true to execute this keyframe, otherwise this one is skipped. balanceWithJoints the joints and their factors to balance with. balancerActive is the balancer active. singeMotorStiffnessChange changes the stiffness of a single specific joint. head, leftArm, rightArm, leftLeg and rightLeg define the joint positions (in degree). odometryOffset is the odometry. balanceOut activates the balance feature of \cf\cref{s:getupengine:misc.continueTois the follow up motion. If it is set todecideAutomaticthen the motion finished.clipAngleoverrides the break up angles, at which the motion is aborted.energySavingLegsandenergySavingArmsactivates the energy saving mode for the joints to prevent overheating.isMotionStableis used for the perception, if set to false no image processing is allowed.interpolationType` is the default interpolation type for this motion.

Every keyframe can have conditions (located in the parameter conditions), which must be true to result in an execution of this keyframe. Otherwise, it is skipped. Also following keyframes can be linked together, so a block of keyframes is only executed if their conditions are fulfilled (linked with the parameter isPartOfPreviousOptionalLine). This way we can have if and else blocks of keyframes (else blocks are marked with the parameter isElseBlock). Also, every keyframe can have waiting conditions (located in the parameter waitConditions). If a keyframe finished, then the motion is stopped for a given time until the waiting condition is fulfilled. Every condition value is represented as a number and a condition is fulfilled if this number lies between two given thresholds. Additionally, wait conditions have a time parameter. If the delay exceeds the time threshold, the waiting process is aborted and the motion is continued as normal. Currently there exist nine different conditions:

  • InertialDataAngleY: Checks for the y rotation orientation of the torso.
  • BrokenLeftArm: Checks for the left shoulder pitch difference of the requested and measured position.
  • BrokenRightArm: Checks for the right shoulder pitch difference of the requested and measured position.
  • WaitTime: Checks for a specific wait duration
  • FrontHack: Checks of a specific if-block of keyframes should be active for the front get up motion.
  • IsSitting: Checks for position of the knee angles
  • HYPDifference: Checks for the hip yaw pitch difference of the the requested and measured position.
  • FootSupportVal: Checks which foot has more pressure weight.

We use the waiting conditions to ensure that specific motion processes like letting the robot tilt over from a lying position to an upright position are not interrupted too early and result in a robot, that keeps lying on the ground, or after the robots reached a sitting position to let it wait a moment to balance out disturbances, to ensure they don't fall over when interpolating into a standing position. The conditions BrokenLeftArm and BrokenRightArm are used to check for problems when starting a get up try, like incorrectly positioned arms.

Balancing Parameters

An example of the balancing parameters are shown below:

Split = {
  balanceFactor = {
    increaseFactorCapFront = {
      x = 3;
      y = 1;
    };
    increaseFactorCapBack = {
      x = 1;
      y = 1;
    };
    powDegreeFront = {
      x = 2;
      y = 2;
    };
    powDegreeBack = {
      x = 2;
      y = 2;
    };
    borderPIDPX = {
      x = 4;
      y = 5;
    };
    borderPIDPY = {
      x = 1;
      y = 0;
    };
    borderPIDDX = {
      x = 1;
      y = 1;
    };
    borderPIDDY = {
      x = 1;
      y = 0;
    };
  };
  backwardCOMDif = {
    x = -50;
    y = -20;
  };
  backwardAngleBreakUp = {
    x = -40deg;
    y = -70deg;
  };
  forwardCOMDif = {
    x = 20;
    y = 60;
  };
  forwardAngleBreakUp = {
    x = 40deg;
    y = 70deg;
  };
};

balanceFactor contains parameters for the PID-Controller, which is used for the balancing. This controller is separated into forwards/backwards and sideways (left/right) balancing. Both directions each 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. Also the PID-Controller increases the control value exponentially, based on the P-Value (powDegreeFront and powDegreeBack). The borderPID[P|D][X|Y] parameters also clip the output, to prevent too high balancing values, which would result in a oscillation or worse a self destruction of the joints. [backward|forward]AngleBreakUp are used to abort a keyframe if the torso rotation is outside the value range. x represents a min and y the max angle.

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 KeyframeMotionID within the representation Src/Representations/MotionControl/KeyframeMotionRequest.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.

Using call Calibrators/EditKeyframes in the simulation is also useful to editing an existing keyframe motion.

Testing New Keyframe Motions for Getting Up

If a new motion was added which shall be used for getting up, you can use call Calibrators/GetUpJointFailureBehavior in the simulation. The command provide the possibility to request for a specific keyframe line of the motion to simulate joint problems. An example is as follows:

echo set module:KeyframeMotionEngine:setLineCounterFailureStart 5
echo set module:KeyframeMotionEngine:setRatioFailureStart 0.32
echo set module:KeyframeMotionEngine:setLineCounterFailureEnd 6
echo set module:KeyframeMotionEngine:setRatioFailureEnd 0.95
echo set module:KeyframeMotionEngine:setMotionIDFailure fromSplit
echo set module:KeyframeMotionEngine:setJointFailure lHipYawPitch
echo dr module:KeyframeMotionEngine:addMotionFailure

For the motion fromSplit the keyframe number 5 is requested, to simulate a problem, starting from 32 % of the executed keyframe until keyframe number 6 when reaching 95% of its execution. The joint lHipYawPitch is used. As a result, in this time frame the lHipYawPitch joint request is not changed anymore, eg. if the last request was 40 degrees, but at time stamp keyframe number 6 95 % the request would be 0 degree, then the request is still 40 degrees but the KeyFrameMotionEngine thinks it requested 0 degrees and there might compensate the lHipYawPitch joint. Afterwards the lHipYawPitch is interpolated back to the desired requested over just a few motion frames.

WalkKickEngine

For in walk kicks the WalkKickEngine uses lots of parameters to define how specific kicks are executed. 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.

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];
walkKicksList = {
  sidewardsOuter = {
    maxXDeviation = {min = -80; max = 60;};
    maxYDeviation = {min = -100; max = 50;};
    additionalXDeviation = {min = 0; max = 10;};
    additionalYDeviation = {min = 0; max = 0;};
    maxAngleDeviation = 3deg;
    maxClipBeforAbortX = {min = -20; max = 20;};
    maxClipBeforAbortY = {min = -100; max = 60;};
    maxClipBeforAbortRot = {min = -6deg; max = 6deg;};
    [...]
    kickKeyFrame = [
      {
        [...]
        useSlowFootHeightInterpolation = false;
        overrideOldSwingFoot = none;
        overrideOldSupportFoot = request;
        numOfBalanceSteps = 0;
        keyframes = [
          {
            relativePositionToBallMax = {x = -80; y = -150;};
            relativePositionToBallMin = {x = -80; y = -150;};
            offsetSwingFootMax = {x = 0; y = -10;};
            offsetSwingFootMin = {x = 0; y = -10;};
            [...]
            directionRatio = 1;
            reachPositionRatio = 0.5;
            speedUpSwingPositionScaling = {min = 1; max = 1;};
            useDefaultReachPositionRatio = false;
            [...]
          },
          [...]
        ];
        jointOffsets = [
          {
            joint = rAnkleRoll;
            offset = -5deg;
            minRatio = 0;
            middleRatio = 0.1;
            maxRatio = 0.25;
            [...]
            shiftByKeyFrame = -1;
          },
          [...]
        ];
      }
    ];
  };
  [...]
}

walkKicksWithRestrictedStart list 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. walkKicksList contains all kicks, with sidewardsOuter used as an example. max[X|Y]Deviation describe 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, because the robot is able to align its feet to the ball faster, when for example the robot is walking forward and the kicking foot is not parallel to the supporting foot and therefor has more distance to the ball to adjust. maxClipBeforAbort[X|Y|Rot] describe 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. useSlowFootHeightInterpolation lets the last support foot interpolate its height slower back to zero than normal. This is important for strong kicks like forwardLong. 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 robot 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] describe 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, with useDefaultReachPositionRatio defining of this default ratio shall be used or a dynamically calculated one. The jointOffsets are a list of additional offset, to force specific joints to move in a specific way. For example the joint rAnkleRoll shall gain an offset of -5 degrees, interpolated with a sinus function from 0 % of the walk step (minRatio) to 100 % at a ratio of 10 % of the walk step (middleRatio). Afterwards the offset is interpolated back to 0 degrees until the walk step ratio of 25 % (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, eg. the offset shall reach the maximum in the moment the ball is touched.

Odometry

The walkingEngine uses a parameter called odometryScale. It is used to make sure, that when the robot executes a certain step size, the odometry model and the localisation know much fast the robot walks in a certain direction, as he might walk slower or faster than intended, eg. resulting from sliding on in the field.

To set appropriate values, use SimRobot to connect to the robot and use the following commands:

mr RobotPose OdometryOnlySelfLocator cognition
set module:OdometryOnlySelfLocator:basePose rotation = 0deg; translation = { x = 0; y = 0; };
dr module:OdometryOnlySelfLocator:resetReferenceOdometry

For the set module:OdometryOnlySelfLocator:basePose command use the position on the field on which you will let the robot start walking. We recommand to use easy to know location like the center circle or the penalty mark. Afterwards just let the robot walk, eg. let him play with a ball. After a certain distance let the robot stop, eg. you may use the stand button in the simulator. Afterwards compare where the robots thinks he is standing (WorldState or use get representation:RobotPose) and where it actually is standing. Configurate the odometryScale parameter until both positions are similar enough to fulfill your needs.