Monthly Archives: May 2013

Designing a Quadruped Robot – Part 2

In this post I’m going to discuss the mathematics behind moving the legs of the robot correctly. But first, another quick video of the robot roaming free on battery power:

The key to getting a robot like this to move is finding a way to tell each foot exactly where you want it in 3D space. In order to do this, each joint in the leg needs to be rotated at exactly the right angle. The joint angles are calculated using inverse kinematics. In the case of this robot, each leg has three joints:

quadruped_leg_diagram

In order to simplify this from a 3D problem to a 2D problem, find the angle of the coxa joint first:

\theta_{coxa} = \arctan \left( \dfrac{y_{foot}}{x_{foot}} \right)

Find the distance from the femur joint to the foot, ignoring the coxa length. This gives the x position of the foot for the simplified 2DOF problem:

x_{simplified} = \sqrt{x_{foot}^2+y_{foot}^2}-l_{coxa}

Find the length of the imaginary leg in the 2DOF problem:

l_{imaginary} = \sqrt{x_{simplified}^2+z_{foot}^2}

Find the angle of the imaginary leg in the 2DOF problem:

\theta_{imaginary} = - \arctan \left( \dfrac{z_{foot}}{x_{simplified}} \right)

Use the law of cosines to find the tibia joint angle:

\theta_{tibia} = \arccos \left( \dfrac{l_{femur}+l_{tibia}-l_{imaginary}}{2(l_{femur})(l_{tibia})} \right)

Use the law of cosines to find the angle between the imaginary leg and the femur, and then subtract out the imaginary leg angle to get the femur joint angle:

\theta_{femur} = \arccos \left( \dfrac{l_{femur}+l_{imaginary}-l_{tibia}}{2(l_{femur})(l_{imaginary})} \right) -\theta_{imaginary}

Now we have the three joint angles for the leg: \theta_{coxa}\theta_{tibia}, and \theta_{femur}. All that’s left to do is convert the angle to something the servo understands. Since the Dynamixel AX-12A servos accept a value from 0 to 1023 and have a range from 0 to 300 degrees, the following equation can be used to convert radians to a dynamixel value:

position = \dfrac{3069\theta_{joint}}{5\pi}

And that’s it for the leg IK equations. Simply plug the x, y, and z coordinate values into the above equations and solve. Plug the resulting angles into the last equation to get the position values for the servos, and the foot will move to the desired position.

Next time I’m going to explain how to use this to make the robot walk forward.