Skip to content

IK Service Example

Rob Linsalata edited this page May 1, 2013 · 9 revisions

Summary

The IK Test example shows the very basics of calling the on-robot Inverse-Kinematics (IK) Service to obtain a joint angles solution for a given endpoint Cartesian point & orientation.

Quickstart

From an RSDK shell, run the ik_test.py demo from the inverse_kinematics package, with an argument of 'left' or 'right' arm, Ex:
bash $ rosrun inverse_kinematics ik_test.py left The test will call the IK Service for a hard-coded Cartesian Pose for the given arm. The response will then be printed to the screen with the found joint solution and a True/False if the solution is a valid configuration for Baxter's arm.

Overview

The 'inverse_kinematics' test code is an example of how to communicate with a robot-side ROS node that provides an Inverse-Kinematics (IK) service. Normal arm control is done using joint angles or states; for instance, position joint control allows the user to set the position in radians for each shoulder, elbow, and wrist joint. Often in robotics manipulation, it can be useful to work in the Cartesian space of the arm's endpoint. Inverse Kinematics is used to convert between the Cartesian (x,y,z, roll, pitch, yaw) space representation, to actual controllable 7-DOF joint states.

The example script simply calls the service for a canonical Cartesian point + orientation for either the left or right arm and as such merely provides the most basic example of how to use this service. Note that we provide this service just to have some out of the box method for IK. The complicated nature of 7-DOF Inverse Kinematics control, usually means the best IK implementations are customized for a specific use case. The node is not a complete Cartesian control solution, just a rudimentary solver exposed for convenience in elementary situations.

For anything needing high-performance IK, it makes a lot more sense to implement it on the development machine.

For more information on Arm Control, see Using the Arms.

Interfaces

ROS APIs

See the API Reference page for details.

  • IK Solver Service: /sdk/robot/limb/<limb>/solve_ik_position

baxter_interface APIs

None used.

Using the IK Solution Response

The format of the SolvePositionIK Service Response is an array of [baxter_msgs/JointPositions][baxter_msgs-JointPositions] solutions and a boolean array that return if the solution is valid. To use the SolvePositionIK response to control the arm joints, you can use the values returned in the JointPositions ROS message to command the arm via the Limb interface.

As a rudimentary learning example, try building off the inverse_kinematics python example by adding a Limb interface and using the set_positions() function. By extracting the arrays of joint names and positions into a dictionary, you can pass in the found angles to set_positions() to move the arm joints to the desired solution, with something along the lines of:

    ...
    ikreq.pose_stamp.append(poses[limb])
    try:
        resp = iksvc(ikreq)
    ...
    # reformat the solution arrays into a dictionary
    joint_solution = dict(zip(resp.joints[0].names, resp.joints[0].angles))
    # set arm joint positions to solution
    arm = baxter_interface.Limb(limb)
    while not rospy.is_shutdown():
        arm.set_positions(joint_solution)
        rospy.sleep(0.01)

Note: This is not a complete solution, as you will also need to add code to enable the robot, as is done in other arm control examples. Check out the main function of the 'joint_positions' file_playback.py example for reference.

Troubleshooting

For common issues using examples with Baxter, check out the Troubleshooting page.

  [baxter_msgs-JointCommandMode0]: </RethinkRobotics/sdk-docs/wiki/api/doc/baxter_msgs/html/classbaxter__msgs_1_1JointCommandMode.html> [baxter_msgs-JointCommandMode1]: </RethinkRobotics/sdk-examples/blob/master/baxter/baxter_msgs/msg/JointCommandMode.msg> [baxter_msgs-JointCommandMode]: http://github.com/RethinkRobotics/sdk-examples/blob/master/baxter/baxter_msgs/msg/JointCommandMode.msg [baxter_msgs-JointPositions]: http://github.com/RethinkRobotics/sdk-examples/blob/master/baxter/baxter_msgs/msg/JointPositions.msg [baxter_msgs-JointTorques]: http://github.com/RethinkRobotics/sdk-examples/blob/master/baxter/baxter_msgs/msg/JointTorques.msg [baxter_msgs-JointVelocities]: http://github.com/RethinkRobotics/sdk-examples/blob/master/baxter/baxter_msgs/msg/JointVelocities.msg [baxter_msgs-LSCores]: http://github.com/RethinkRobotics/sdk-examples/blob/development/baxter/baxter_msgs/srv/LSCores.srv [baxter_msgs-RMCores]: http://github.com/RethinkRobotics/sdk-examples/blob/development/baxter/baxter_msgs/srv/RMCores.srv

Clone this wiki locally