Joint Position Example

Created by Rico Stodt, Modified on Fri, 11 Feb, 2022 at 8:43 AM by Rico Stodt

The joint position example (keyboard, joystick) demonstrates basic joint position control. The key or button mapped to either increasing or decreasing the angle of a particular joint on Sawyer´s arm. 


Contents


Introduction


Use a game controller or your dev machine's keyboard to control the angular joint positions of Sawyer's arm. If you would like to follow along with the actual source code for these examples on GitHub, it can be found through link for joint position joystick and link for joint position keyboard.


Usage


Start the joint position keyboard example program, ex:

 

$ rosrun intera_examples joint_position_keyboard.py

 

Start the joint position joystick example program, ex:

 

$ rosrun intera_examples joint_position_joystick.py

 

Upon startup, you will be prompted with the following:

 

Initializing node... 
Getting robot state... 
Enabling robot... 
[INFO] [WallTime: 1399575163.891211] Robot Enabled
Controlling joints. Press ? for help, Esc to quit.


Arguments


Important Arguments:

See the joint position example available arguments on the command line by passing:

 

$ rosrun intera_examples joint_position_keyboard.py -h

  

usage: joint_position_keyboard.py [-h] [-l LIMB]
 
RSDK Joint Position Example: Keyboard Control
    Use your dev machine's keyboard to control joint positions.
    Each key corresponds to increasing or decreasing the angle
    of a joint on Sawyer's arm. The increasing and descreasing
    are represented by number key and letter key next to the number.
    
 
optional arguments:
  -h, --help            show this help message and exit
  -l LIMB, --limb LIMB
                        Limb on which to run the joint position keyboard example

 

For joint position joystick example:

 

$ rosrun intera_examples joint_position_joystick.py -h

  

usage: joint_position_joystick.py [-h] [-l LIMB] [-j JOYSTICK]
 
SDK Joint Position Example: Joystick Control
    Use a game controller to control the angular joint positions
    of Sawyer's arms.
    Attach a game controller to your dev machine and run this
    example along with the ROS joy_node to control the position
    of each joint in Sawyer's arm using the joystick. Be sure to
    provide your *joystick* type to setup appropriate key mappings.
    Each stick axis maps to a joint angle; which joints are currently
    controlled can be incremented by using the mapped increment buttons.
    Ex:
      (x,y -> e0,e1) >>increment>> (x,y -> e1,e2)
 
required arguments:
  -j, --joystick        specify the type of joystick to use
 
optional arguments:
  -h, --help            show this help message and exit
  -l LIMB, --limb LIMB
                        Limb on which to run the joint position joystick example


Joint Position Keyboard Code Walkthrough


Now, let's break down the code.

  

"""
SDK Joint Position Example: keyboard
"""
import argparse

import rospy

import intera_interface
import intera_external_devices

from intera_interface import CHECK_VERSION

 

This imports the intera interface for accessing the limb and the gripper class. The intera_external_devices is imported to use its getch function, that captures the key presses on the keyboard. The CHECK_VERSION is imported to check if the software running on the robot would be compatible with this local version. It is not necessary to check the version in custom programs.

  

def map_keyboard(side):
    limb = intera_interface.Limb(side)
    
    try:
        gripper = intera_interface.Gripper(side)
    except:
        has_gripper = False
        rospy.logerr("Could not initalize the gripper.")
    else:
        has_gripper = True

    joints = limb.joint_names()

 

The instance of Limb class, limb and the instance of Gripper class, gripper are created. joint_names() method returns an array of joints of the limb.

  

    def set_j(limb, joint_name, delta):
        current_position = limb.joint_angle(joint_name)
        joint_command = {joint_name: current_position + delta}
        limb.set_joint_positions(joint_command)

    def set_g(action):
        if has_gripper:
            if action == "close":
                gripper.close()
            elif action == "open":
                gripper.open()
            elif action == "calibrate":
                gripper.calibrate()

 

The set_j() function is invoked whenever a valid key press occurs. The limb refers to the limb instance of Sawyer's limb. delta refers to the required displacement of the joint from its current position. The method joint_angle() returns the current position of that joint. Then the joint command message is updated for that corresponding joint to indicate the new position. set_joint_position() method publishes the joint commands to the position controller. The set_g function calls gripper action function(open(), or close() or calibrate()) when corresponding action is provided.

  

    bindings = {
        '1': (set_j, [limb, joints[0], 0.1], joints[0]+" increase"),
        'q': (set_j, [limb, joints[0], -0.1], joints[0]+" decrease"),
        '2': (set_j, [limb, joints[1], 0.1], joints[1]+" increase"),
        'w': (set_j, [limb, joints[1], -0.1], joints[1]+" decrease"),
        '3': (set_j, [limb, joints[2], 0.1], joints[2]+" increase"),
        'e': (set_j, [limb, joints[2], -0.1], joints[2]+" decrease"),
        '4': (set_j, [limb, joints[3], 0.1], joints[3]+" increase"),
        'r': (set_j, [limb, joints[3], -0.1], joints[3]+" decrease"),
        '5': (set_j, [limb, joints[4], 0.1], joints[4]+" increase"),
        't': (set_j, [limb, joints[4], -0.1], joints[4]+" decrease"),
        '6': (set_j, [limb, joints[5], 0.1], joints[5]+" increase"),
        'y': (set_j, [limb, joints[5], -0.1], joints[5]+" decrease"),
        '7': (set_j, [limb, joints[6], 0.1], joints[6]+" increase"),
        'u': (set_j, [limb, joints[6], -0.1], joints[6]+" decrease"),
        '8': (set_g, "close", side+" gripper close"),
        'i': (set_g, "open", side+" gripper open"),
        '9': (set_g, "calibrate", side+" gripper calibrate")
     }

 

The bindings is a dictionary that holds the set of characters in the keyboard and their corresponding joints.

  

    done = False
    print("Controlling joints. Press ? for help, Esc to quit.")
    while not done and not rospy.is_shutdown():
        c = intera_external_devices.getch()
        if c:
            #catch Esc or ctrl-c
            if c in ['\x1b', '\x03']:
                done = True
                rospy.signal_shutdown("Example finished.")

 

The done variable captures whether "esc" or "ctrl-c" was hit. The while loop iterates as long as the "esc" or "ctrl-c" is hit or ros-shutdown signal is given. c captures the keyboard input. If "esc" or "ctrl-c" is given then done gets updated as true, and a shutdown signal will be sent.

  

            elif c in bindings:
                cmd = bindings[c]
                if c == '8' or c == 'i' or c == '9':
                    cmd[0](cmd[1])
                    print("command: %s" % (cmd[2],))
                else:
                    #expand binding to something like "set_j(right, 'j0', 0.1)"
                    cmd[0](*cmd[1])
                    print("command: %s" % (cmd[2],))

 

The user inputted key is checked whether it is in the bindings dictionary. bindings[c] returns the value of the key c from the dictionary. The 0th index of the value refers to the function to be called and the next index holds the arguments to be sent along with that function. cmd[2] is the description of the joint command from the dictionary above.

  

            else:
                print("key bindings: ")
                print("  Esc: Quit")
                print("  ?: Help")
                for key, val in sorted(bindings.items(),
                                       key=lambda x: x[1][2]):
                    print("  %s: %s" % (key, val[2]))

 

This case is executed when the key pressed is not a valid input. So, the key is sorted and is printed along with its corresponding description.

  

def main():
    """RSDK Joint Position Example: Keyboard Control
    Use your dev machine's keyboard to control joint positions.
    Each key corresponds to increasing or decreasing the angle
    of a joint on Sawyer's arm. The increasing and descreasing
    are represented by number key and letter key next to the number.
    """
    epilog = """
See help inside the example with the '?' key for key bindings.
    """
    rp = intera_interface.RobotParams()
    valid_limbs = rp.get_limb_names()
    if not valid_limbs:
        rp.log_message(("Cannot detect any limb parameters on this robot. "
                        "Exiting."), "ERROR")
        return
    arg_fmt = argparse.RawDescriptionHelpFormatter
    parser = argparse.ArgumentParser(formatter_class=arg_fmt,
                                     description=main.__doc__,
                                     epilog=epilog)
    parser.add_argument(
        "-l", "--limb", dest="limb", default=valid_limbs[0],
        choices=valid_limbs,
        help="Limb on which to run the joint position keyboard example"
    )
    args = parser.parse_args(rospy.myargv()[1:])

    print("Initializing node... ")
    rospy.init_node("sdk_joint_position_keyboard")
    print("Getting robot state... ")
    rs = intera_interface.RobotEnable(CHECK_VERSION)
    init_state = rs.state().enabled

 

The node is initialized and then the software version is checked for compatiblity with the local version. init_state captures Sawyer's initial state. This is to make sure that Sawyer is sent back to the same state after the program exits.

  

    def clean_shutdown():
        print("\nExiting example.")
        if not init_state:
            print("Disabling robot...")
            rs.disable()
    rospy.on_shutdown(clean_shutdown)

 

As explained above, the robot is checked if it was initially disabled and if so, it is disabled upon the program's termination.

  

    rospy.loginfo("Enabling robot...")
    rs.enable()
    map_keyboard(args.limb)
    print("Done.")


if __name__ == '__main__':
    main()

 

The robot is enabled before the programs execution. It is important to note that Sawyer should be auto-enabled before trying to move its joints. map_keyboard() function captures the key input and moves the joint as explained above.


Joint Position Joystick Code Walkthrough


Now, let's break down the code.

  

import argparse

import rospy

import intera_interface
import intera_external_devices

from intera_interface import CHECK_VERSION

 

This imports the intera interface for accessing the limb and the gripper class. The intera_external_devices is imported to use its joystick function, that captures the key presses on the joystick. The CHECK_VERSION is imported to check if the software running on the robot would be compatible with this local version. It is not necessary to check the version in custom programs.

  

def rotate(l):
    """
    Rotates a list left.
    @param l: the list
    """
    if len(l):
        v = l[0]
        l[:-1] = l[1:]
        l[-1] = v

 

The rotate function rotates a list, it will be used in bindings. This moves all the elements in the list to one position to their left. So the element at 0th position moves to the nth position, element at nth position moves to (n-1)th position, and so on.

  

def set_j(cmd, limb, joints, index, delta):
    """
    Set the selected joint to current pos + delta.
    @param cmd: the joint command dictionary
    @param limb: the limb to get the pos from
    @param joints: a list of joint names
    @param index: the index in the list of names
    @param delta: delta to update the joint by
    joint/index is to make this work in the bindings.
    """
    joint = joints[index]
    cmd[joint] = delta + limb.joint_angle(joint)

 

joint_angle() method returns the current angle of the corresponding joint. This function builds the dictionary that is to be passed as a joint command. The last line assigns the new position which has an offset of delta from the current position.

  

def map_joystick(joystick, side):
    """
    Maps joystick input to joint position commands.
    @param joystick: an instance of a Joystick
    """
    limb = intera_interface.Limb(side)
    gripper = None
    try:
        gripper = intera_interface.Gripper(side)
    except:
        rospy.loginfo("Could not detect a connected electric gripper.")

 

The instance of Limb class and the instance of Gripper class are created. No gripper will raise could not detect gripper info.

  

    def set_g(action):
        if gripper is not None:
            if action == "close":
                gripper.close()
            elif action == "open":
                gripper.open()
            elif action == "calibrate":
                gripper.calibrate()

 

The set_g function calls gripper action function(open(), or close() or calibrate()) when corresponding action is provided.

  

    limb_cmd = {}

    #available joints
    joints = limb.joint_names()

    #abbreviations
    jhi = lambda s: joystick.stick_value(s) > 0
    jlo = lambda s: joystick.stick_value(s) < 0
    bdn = joystick.button_down
    bup = joystick.button_up

 

Create instance of joint names and abbreviations for joystick values, button up and button down. The joint_names() method returns a list of joints associated with the limb. The stick_value() method returns the dead-banded, scaled and offset value of the axis. The abbreviations for all these functions are created to be used within the bindings dictionary below.

  

    def print_help(bindings_list):
        print("Press Ctrl-C to quit.")
        for bindings in bindings_list:
            for (test, _cmd, doc) in bindings:
                if callable(doc):
                    doc = doc()
                print("%s: %s" % (str(test[1][0]), doc))

 

The information about the joystick buttons and the corresponding joints are displayed. This information is available in bindings_list as below. The doc refers to the last element of the tuple and it is checked if it is a callable function. So, if there is a lambda function that evaluates and returns a string, then that function is called. Finally, the results are displayed.

  

    bindings_list = []
    bindings = [
        ((jlo, ['leftStickHorz']), (set_j, [limb_cmd, limb, joints, 0, 0.1]),
            lambda: "Increase " + joints[0]),
        ((jhi, ['leftStickHorz']), (set_j, [limb_cmd, limb, joints, 0, -0.1]),
            lambda: "Decrease " + joints[0]),
        ((jlo, ['leftStickVert']), (set_j, [limb_cmd, limb, joints, 1, 0.1]),
            lambda: "Increase " + joints[1]),
        ((jhi, ['leftStickVert']), (set_j, [limb_cmd, limb, joints, 1, -0.1]),
            lambda: "Decrease " + joints[1]),
        ((jlo, ['rightStickHorz']), (set_j, [limb_cmd, limb, joints, 2, 0.1]),
            lambda: "Increase " + joints[2]),
        ((jhi, ['rightStickHorz']), (set_j, [limb_cmd, limb, joints, 2, -0.1]),
            lambda: "Decrease " + joints[2]),
        ((jlo, ['rightStickVert']), (set_j, [limb_cmd, limb, joints, 3, 0.1]),
            lambda: "Increase " + joints[3]),
        ((jhi, ['rightStickVert']), (set_j, [limb_cmd, limb, joints, 3, -0.1]),
            lambda: "Decrease " + joints[3]),
        ((bdn, ['leftBumper']), (rotate, [joints]), side + ": cycle joint"),
        ((bdn, ['function1']), (print_help, [bindings_list]), "help"),
        ((bdn, ['function2']), (print_help, [bindings_list]), "help"),
        ]
    if gripper:
        bindings.extend([
            ((bdn, ['rightTrigger']), (set_g, ['close'], gripper), side + " gripper close"),
            ((bup, ['rightTrigger']), (set_g, ['open'], gripper), side + " gripper open"),
            ((bdn, ['btnLeft']), (set_g, ['calibrate'], gripper), "right calibrate")
            ])
    bindings_list.append(bindings)

 

The first element of every tuple refers to the command that has to be executed. As indicated above set_j, bdn, bup, jhi and jlo refers to the function and their acronyms. The second tuple has a list that holds the list of arguments to be passed along with that function. The last element holds a string or a function that evaluates and forms a string to detail the joint under consideration.

  

    rate = rospy.Rate(100)
    print_help(bindings_list)
    print("Press Ctrl-C to stop. ")
    while not rospy.is_shutdown():
        for (test, cmd, doc) in bindings:
            if test[0](*test[1]):
                cmd[0](*cmd[1])
                if callable(doc):
                    print(doc())
                else:
                    print(doc)
        if len(limb_cmd):
            limb.set_joint_positions(limb_cmd)
            limb_cmd.clear()
        rate.sleep()
    return False

 

The test tuple holds the function that needs to be called for a particular value to be tested. For instance, the first tuple holds the abbreviation bdn and the parameter rightTrigger that is passed along. This test function checks whether the joystick's button_down is pressed. If this is true then the cmd, that refers to the second tuple (gripper.close,[]) is parsed as above. For the first binding, the expression cmd[0](*cmd[1]) returns the function call gripper.close([]). The next line checks if the last tuple is a function (lambda) or not (string). Since the joints being controlled are updated dynamically, the lambda function is used to retrieve the current joints rj[0] and rj[1]. The dictionaries limb_cmd hold the joint commands for the limb. These dictionaries get populated when the set_j method is called by the previous section of code.

  

def main():
    """SDK Joint Position Example: Joystick Control
    Use a game controller to control the angular joint positions
    of Sawyer's arms.
    Attach a game controller to your dev machine and run this
    example along with the ROS joy_node to control the position
    of each joint in Sawyer's arm using the joystick. Be sure to
    provide your *joystick* type to setup appropriate key mappings.
    Each stick axis maps to a joint angle; which joints are currently
    controlled can be incremented by using the mapped increment buttons.
    Ex:
      (x,y -> e0,e1) >>increment>> (x,y -> e1,e2)
    """
    epilog = """
See help inside the example with the "Start" button for controller
key bindings.
    """
    rp = intera_interface.RobotParams()
    valid_limbs = rp.get_limb_names()
    if not valid_limbs:
        rp.log_message(("Cannot detect any limb parameters on this robot. "
                        "Exiting."), "ERROR")
        return
    arg_fmt = argparse.RawDescriptionHelpFormatter
    parser = argparse.ArgumentParser(formatter_class=arg_fmt,
                                     description=main.__doc__,
                                     epilog=epilog)
    required = parser.add_argument_group('required arguments')
    required.add_argument(
        '-j', '--joystick', required=True,
        choices=['xbox', 'logitech', 'ps3'],
        help='specify the type of joystick to use'
    )
    parser.add_argument(
        "-l", "--limb", dest="limb", default=valid_limbs[0],
        choices=valid_limbs,
        help="Limb on which to run the joint position joystick example"
    )
    args = parser.parse_args(rospy.myargv()[1:])

    joystick = None
    if args.joystick == 'xbox':
        joystick = intera_external_devices.joystick.XboxController()
    elif args.joystick == 'logitech':
        joystick = intera_external_devices.joystick.LogitechController()
    elif args.joystick == 'ps3':
        joystick = intera_external_devices.joystick.PS3Controller()
    else:
        parser.error("Unsupported joystick type '%s'" % (args.joystick))

    print("Initializing node... ")
    rospy.init_node("sdk_joint_position_joystick")
    print("Getting robot state... ")
    rs = intera_interface.RobotEnable(CHECK_VERSION)
    init_state = rs.state().enabled

 

The type of joystick input is captured as entered by the user and an instance of the corresponding interface is created. The node is initialized and the robot is enabled.

  

    def clean_shutdown():
        print("\nExiting example.")
        if not init_state:
            print("Disabling robot...")
            rs.disable()
    rospy.on_shutdown(clean_shutdown)

    rospy.loginfo("Enabling robot...")
    rs.enable()

    map_joystick(joystick, args.limb)
    print("Done.")


if __name__ == '__main__':
    main()

 

The map_joystick() method performs the mapping and execution of the commands as explained above.


Was this article helpful?

That’s Great!

Thank you for your feedback

Sorry! We couldn't be helpful

Thank you for your feedback

Let us know how can we improve this article!

Select at least one of the reasons
CAPTCHA verification is required.

Feedback sent

We appreciate your effort and will try to fix the article