Phase 4: Foot Trajectory Planning and Gait Sequencing Part I

Thanks to my handy IK engine, I no longer need to think in terms of joint angles. All i need to do is move the tip of the foot around in 3D space using the footPos.x, footPos.y, and footPos.z variables.   Stepping is really as simple as looping and incrementing them in such a way to produce the desired movement. Incrementing X moves the foot in the forward X direction. Incrementing X and Y at the same time moves the foot on that diagonal, etc.

I’ve been putting this post off for awhile because I keep changing how I’m implementing the foot stepping. I’ll go through the history for learning’s sake.

At first I was using linear equations to “draw” straight lines with the foot. A foot would step diagonally up and forward, down and forward, then pull back along the ground in the shape of a triangle.


            switch (caseStep[legNum]){

                case 1: //forward raise

                    leg[legNum].footPos.x = ((long)(speedX + strideRotOffsetX[legNum])*tick*SERVO_UPDATE_PERIOD)/duration - (speedX + strideRotOffsetX[legNum])/4;
                    leg[legNum].footPos.y = ((long)(speedY + strideRotOffsetY[legNum])*tick*SERVO_UPDATE_PERIOD)/duration - (speedY + strideRotOffsetY[legNum])/4;
                    leg[legNum].footPos.z = ((long)height*tick*SERVO_UPDATE_PERIOD)/(duration/4);

                    if( tick >= numTicks-1 ) caseStep[legNum] = 2;
                    break;

                case 2: // forward lower

                    leg[legNum].footPos.x = ((long)(speedX + strideRotOffsetX[legNum])*tick*SERVO_UPDATE_PERIOD)/duration;
                    leg[legNum].footPos.y = ((long)(speedY + strideRotOffsetY[legNum])*tick*SERVO_UPDATE_PERIOD)/duration;
                    leg[legNum].footPos.z = height - ((long)height*tick*SERVO_UPDATE_PERIOD)/(duration/4);

                    if( tick >= numTicks-1 ) caseStep[legNum] = 3;
                    break;

                case 3: // down pull back

                    leg[legNum].footPos.x = -((long)(speedX + strideRotOffsetX[legNum])*tick*SERVO_UPDATE_PERIOD)/duration + (speedX + strideRotOffsetX[legNum])/4;
                    leg[legNum].footPos.y = -((long)(speedY + strideRotOffsetY[legNum])*tick*SERVO_UPDATE_PERIOD)/duration + (speedY + strideRotOffsetY[legNum])/4;
                    leg[legNum].footPos.z = 0;

                    if( tick >= numTicks-1 ) caseStep[legNum] = 4;
                    break;

                case 4: // down pull back

                    leg[legNum].footPos.x = -((long)(speedX + strideRotOffsetX[legNum])*tick*SERVO_UPDATE_PERIOD)/duration;
                    leg[legNum].footPos.y = -((long)(speedY + strideRotOffsetY[legNum])*tick*SERVO_UPDATE_PERIOD)/duration;
                    leg[legNum].footPos.z = 0;

                    if( tick >= numTicks-1 ) caseStep[legNum] = 1;
                    break;

          }// end of case statement

This worked well and was fast to process on the Arduino, but it had a couple of issues. First, the leg movement looked a little rigid and unnatural. Sort of jerky with the sudden direction changes. Second and most importantly, the robot wasn’t walking smoothly forward. It would sort of stutter as it moved continuously in a direction. I realized that this was because the foot was coming down and hitting the ground in the opposite direction to travel. This caused a momentary halt in the forward momentum before the foot began to pull backwards. The foot should at least be coming straight down toward the ground before pulling back. I’ll explain how I do this once its ready for prime time.

To be continued in Part II!

Jump back to the beginning of Project B.E.T.H.

Leave a Reply

Your email address will not be published. Required fields are marked *