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.

Advertisements

Posted on May 17, 2013, in Robotics. Bookmark the permalink. 4 Comments.

  1. Hi,

    I’m impressed by the work you had done on the quadruped.

    I’m in dire need of your help to seek some valuable solutions.
    I’ve been seeking solutions for the last 6 months to solve the kinematics of the hexapod with no positive results.. I managed to find equations for all of the servo angles with the body parallel to the floor, but unable to do so with the body tilted to one side. Appreciate if you would be able to help 🙂

    Regards
    Gary

    • Hello Gary, Thank you for taking a look and I’m sorry for the late reply. I plan to write about this in the next couple of weeks, but I’ll admit in advance that my solution isn’t perfect. Keep an eye out for a post on this soon.

  2. Hey,
    Good job with the kinematic !
    I’m in a hurry to get to this point with my hexapod 😉

    Maybe I will come back to one day for kinematic advice xD

    Bye

  1. Pingback: Designing a Quadruped Robot – Part 3 | Justin Woodman

Leave a Reply

Fill in your details below or click an icon to log in:

WordPress.com Logo

You are commenting using your WordPress.com account. Log Out / Change )

Twitter picture

You are commenting using your Twitter account. Log Out / Change )

Facebook photo

You are commenting using your Facebook account. Log Out / Change )

Google+ photo

You are commenting using your Google+ account. Log Out / Change )

Connecting to %s

%d bloggers like this: