Enable the robot joint trajectory interface, parse a file created using the joint position recorder example, and send the resulting joint trajectory to the action server.


Contents


Overview


A commonly used ROS method for robot arm motion control is the joint trajectory action interface. The trajectory_controller and it's corresponding joint trajectory action server is the intera_interface implementation to support this action interface. This example shows usage for launching the joint trajectory action server, and parsing of a text file describing timestamped joint position goals into a joint trajectory action call to be commanded to the joint trajectory action server.


Introduction


This example demonstrates the usage of the Joint Trajectory Action server to command raw joint position commands. The main() creates and instance of the Trajectory class and calls the parse_file() method. This method is responsible for parsing the input file and packing them as Request message for the Joint Trajectory Action server. The start() method is then called, which sends the Request messages to the action server. Finally, wait() is then called, which verifies if the trajectory execution was successful. Action Servers - robot/limb/right/follow_joint_trajectory. If you would like to follow along with the actual source code for the example on GitHub, it can be found through this link for joint trajectory file playback example.


Usage


Verify that the robot is enabled from an SDK terminal session, if the robot is not enabled run:

 

$ rosrun intera_interface robot_enable.py

 

Record a joint position file using the joint_recorder.py example, ex:

 

$ rosrun intera_examples joint_recorder.py -f <position_file_name>

The recorder is now recording joint positions with corresponding timestamps for robot arm. Move the arms while holding the cuffs. If the position file name exists, the function will overwrite existing file.


NOTE: You can open and close the gripper while recording by using the robot's cuff buttons: Oval(lower) = Close, Circle(Upper) = Open

Start the joint trajectory controller, ex:

 

$ rosrun intera_interface joint_trajectory_action_server.py --mode velocity

 

In another RSDK terminal session, Run the joint trajectory playback example program, ex:

 

$ rosrun intera_examples joint_trajectory_file_playback.py -f <position_file_name>

 

The robot arm will then be commanded to repeat the trajectory recorded during the joint position recording. The difference between this example and the joint_position playback example is that the trajectory controller has the ability to honor the velocities (due to the timestamps) to more accurately repeating the recorded trajectory.


Arguments


Important Arguments: Arguments for joint_trajectory_action_server.py


See the trajectory controller's usage on the command line by passing trajectory_controller.py the -h, help argument:

 

$ rosrun intera_interface joint_trajectory_action_server.py -h

 

Intera SDK Joint Trajectory Controller
 
    Unlike other robots running ROS, this is not a Motor Controller plugin,
    but a regular node using the SDK interface.    
 
optional arguments:
  -h, --help            show this help message and exit
  -l {right}, --limb {right}
                        joint trajectory action server limb (default: right)
  -r RATE, --rate RATE  trajectory control rate (Hz) (default: 100.0)
  -m {position_w_id,position,velocity}, --mode {position_w_id,position,velocity}
                        control mode for trajectory execution (default:
                        position_w_id)

 

Important Arguments: Arguments for joint_trajectory_file_playback.py

 

See the joint_trajectory_file_playback's usage on the command line by passing joint_trajectory_file_playback.py the -h, help argument:

 

$ rosrun intera_interface joint_trajectory_file_playback.py -h

 

RSDK Joint Trajectory Example: File Playback
 
    Plays back joint positions honoring timestamps recorded
    via the joint_recorder example.
 
    Run the joint_recorder.py example first to create a recording
    file for use with this example. Then make sure to start the
    joint_trajectory_action_server before running this example.
 
    This example will use the joint trajectory action server
    with velocity control to follow the positions and times of
    the recorded motion, accurately replicating movement speed
    necessary to hit each trajectory point on time.
 
required arguments:
  -f FILE, --file FILE   path to input file
optional arguments:
  -h, --help            show this help message and exit
  -l LOOPS, --loops LOOPS
                         number of playback loops. 0=infinite. (default: 1)


Interfaces


ROS APIs:

See the API Reference page for details: ROS APIs

 

Joint Trajectory Action Server - /robot/limb/right/follow_joint_trajectory [control_msgs/FollowJointTrajectoryAction]

Intera_interface APIs:


JointTrajectoryActionServer class: joint_trajectory_action_server.py


Code Walkthrough


Now, let's break down the code.

  

import argparse
import operator
import sys
import threading

from bisect import bisect
from copy import copy
from os import path

import rospy

import actionlib

from control_msgs.msg import (
    FollowJointTrajectoryAction,
    FollowJointTrajectoryGoal,
)
from trajectory_msgs.msg import (
    JointTrajectoryPoint,
)

import intera_interface

from intera_interface import CHECK_VERSION

 

This imports the intera_interface for accessing the limb and the gripper class. The actionlib is imported to use its Action Server class.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.

  

class Trajectory(object):
    def __init__(self, limb="right"):
        #create our action server clients
        self._limb_client = actionlib.SimpleActionClient(
            'robot/limb/right/follow_joint_trajectory',
            FollowJointTrajectoryAction,
        )

        #verify joint trajectory action servers are available
        is_server_up = self._limb_client.wait_for_server(rospy.Duration(10.0))
        if not is_server_up:
            msg = ("Action server not available."
                   " Verify action server availability.")
            rospy.logerr(msg)
            rospy.signal_shutdown(msg)
            sys.exit(1)

 

Action server clients for the right limb is created. The existence of action server for right limb is checked with a timeout of 10 seconds. If it is not available, a shutdown signal is sent and the program exits.

  
        #create our goal request
        self.goal = FollowJointTrajectoryGoal()

        #limb interface - current angles needed for start move
        self.arm = intera_interface.Limb(limb)

        self.limb = limb
        self.gripper_name = '_'.join([limb, 'gripper'])
        #gripper interface - for gripper command playback
        try:
            self.gripper = intera_interface.Gripper(limb)
            self.has_gripper = True
        except:
            self.has_gripper = False
            rospy.loginfo("Did not detect a connected electric gripper.")
            
        #flag to signify the arm trajectories have begun executing
        self._arm_trajectory_started = False
        #reentrant lock to prevent same-thread lockout
        self._lock = threading.RLock()

 

The request message that will hold the goal position for right limbs' action server is created. The current joint is also captured. If there is a electric gripper connected, the gripper positions will be captured as well.

  

        # Verify Grippers Have No Errors and are Calibrated
        if self.has_gripper:
            if self.gripper.has_error():
                self.gripper.reboot()
            if not self.gripper.is_calibrated():
                self.gripper.calibrate()

            #gripper goal trajectories
            self.grip = FollowJointTrajectoryGoal()

            #gripper control rate
            self._gripper_rate = 20.0  # Hz

        # Timing offset to prevent gripper playback before trajectory has started
        self._slow_move_offset = 0.0
        self._trajectory_start_offset = rospy.Duration(0.0)
        self._trajectory_actual_offset = rospy.Duration(0.0)

        #param namespace
        self._param_ns = '/rsdk_joint_trajectory_action_server/'

 

The error() method returns whether or not the gripper is in an error state. The possible cause of errors might be over/under-voltage, over/under-current, motor faults, etc. The calibrated() method returns a boolean, true if the gripper is already calibrated. The request message that will hold the goal position for the gripper is created. The namespace is modified and the gripper's control rates is modified.

  

    def _execute_gripper_commands(self):
        start_time = rospy.get_time() - self._trajectory_actual_offset.to_sec()
        grip_cmd = self.grip.trajectory.points
        pnt_times = [pnt.time_from_start.to_sec() for pnt in grip_cmd]
        end_time = pnt_times[-1]
        rate = rospy.Rate(self._gripper_rate)
        now_from_start = rospy.get_time() - start_time
        while(now_from_start < end_time + (1.0 / self._gripper_rate) and
              not rospy.is_shutdown()):
            idx = bisect(pnt_times, now_from_start) - 1
            if self.has_gripper:
                self.gripper.set_position(grip_cmd[idx].positions[0])
            rate.sleep()
            now_from_start = rospy.get_time() - start_time

 

The grip_cmd variable holds the gripper' position that was parsed from the file. The corresponding time stamps are read into pnt_times variable. idx holds the index of the timestamp from the file, relative to the current one. It is important to note that the velocity at which the Joint Positions was traversed is preserved during the playback. The corresponding gripper's position is then commanded to the action server.

  

    def _clean_line(self, line, joint_names):
        """
        Cleans a single line of recorded joint positions

        @param line: the line described in a list to process
        @param joint_names: joint name keys

        @return command: returns dictionary {joint: value} of valid commands
        @return line: returns list of current line values stripped of commas
        """
        def try_float(x):
            try:
                return float(x)
            except ValueError:
                return None
        #convert the line of strings to a float or None
        line = [try_float(x) for x in line.rstrip().split(',')]
        #zip the values with the joint names
        combined = zip(joint_names[1:], line[1:])
        #take out any tuples that have a none value
        cleaned = [x for x in combined if x[1] is not None]
        #convert it to a dictionary with only valid commands
        command = dict(cleaned)
        return (command, line,)

 

This try_float() function replaces the contents of the variable passed with float and none values. Then, a tuple is constructed by zipping the names passed with the values from the variable line. This may contain valid values as well as none values . After removing the none values, a dictionary is constructed. This dictionary is then parsed to create valid Joint commands.

   

    def _add_point(self, positions, side, time):
        """
        Appends trajectory with new point

        @param positions: joint positions
        @param side: limb to command point
        @param time: time from start for point in seconds
        """
        #creates a point in trajectory with time_from_start and positions
        point = JointTrajectoryPoint()
        point.positions = copy(positions)
        point.time_from_start = rospy.Duration(time)
        if side == self.limb:
            self.goal.trajectory.points.append(point)
        elif self.has_gripper and side == self.gripper_name:
            self.grip.trajectory.points.append(point)

  

This method creates a request message of the JointTrajectoryPoint type and appends the goal position based on the side of the limb/gripper that is requesting. It compiles a list of Joint Positions as the trajectory.

  

    def parse_file(self, filename):
        """
        Parses input file into FollowJointTrajectoryGoal format

        @param filename: input filename
        """
        #open recorded file
        with open(filename, 'r') as f:
            lines = f.readlines()
        #read joint names specified in file
        joint_names = lines[0].rstrip().split(',')
        #parse joint names for right limb
        for name in joint_names:
            if self.limb == name[:-3]:
                self.goal.trajectory.joint_names.append(name)

 

The lines are split into a list with ',' as the delimiter to extract the joint names. The arm of the current joint, found by stripping the "_<joint>" (last three characters) from the joint_name, is checked and stored.

  

        def find_start_offset(pos):
            #create empty lists
            cur = []
            cmd = []
            dflt_vel = []
            vel_param = self._param_ns + "%s_default_velocity"
            #for all joints find our current and first commanded position
            #reading default velocities from the parameter server if specified
            for name in joint_names:
                if self.limb == name[:-3]:
                    cmd.append(pos[name])
                    cur.append(self.arm.joint_angle(name))
                    prm = rospy.get_param(vel_param % name, 0.25)
                    dflt_vel.append(prm)
            diffs = map(operator.sub, cmd, cur)
            diffs = map(operator.abs, diffs)
            #determine the largest time offset necessary across all joints
            offset = max(map(operator.div, diffs, dflt_vel))
            return offset

 

The first commanded position and the current position for all the joints are captured. The default values that were loaded into the param server are read. The largest time offset necessary across all the joints is calculated.

  

        for idx, values in enumerate(lines[1:]):
            #clean each line of file
            cmd, values = self._clean_line(values, joint_names)
            #find allowable time offset for move to start position
            if idx == 0:
                # Set the initial position to be the current pose.
                # This ensures we move slowly to the starting point of the
                # trajectory from the current pose - The user may have moved
                # arm since recording
                cur_cmd = [self.arm.joint_angle(jnt) for jnt in self.goal.trajectory.joint_names]
                self._add_point(cur_cmd, self.limb, 0.0)
                start_offset = find_start_offset(cmd)
                # Gripper playback won't start until the starting movement's
                # duration has passed, and the actual trajectory playback begins
                self._slow_move_offset = start_offset
                self._trajectory_start_offset = rospy.Duration(start_offset + values[0])
            #add a point for this set of commands with recorded time
            cur_cmd = [cmd[jnt] for jnt in self.goal.trajectory.joint_names]
            self._add_point(cur_cmd, self.limb, values[0] + start_offset)
            if self.has_gripper:
                cur_cmd = [cmd[self.gripper_name]]
                self._add_point(cur_cmd, self.gripper_name, values[0] + start_offset)

 

The non-float values are cleaned and a dictionary of valid Joint Commands is returned in the _clean_line() function as explained above. The time offset for move to start position is also calculated. The parsed set of recorded commands along with their recorded time is added to the goal list as well as gripper's command and time.

  

    def _feedback(self, data):
        # Test to see if the actual playback time has exceeded
        # the move-to-start-pose timing offset
        if (not self._get_trajectory_flag() and
              data.actual.time_from_start >= self._trajectory_start_offset):
            self._set_trajectory_flag(value=True)
            self._trajectory_actual_offset = data.actual.time_from_start

 

Called in start function, test to see if the actual playback time has exceeded the move-to-start-pose timing offset.

  

    def _set_trajectory_flag(self, value=False):
        with self._lock:
            # Assign a value to the flag
            self._arm_trajectory_started = value

    def _get_trajectory_flag(self):
        temp_flag = False
        with self._lock:
            # Copy to external variable
            temp_flag = self._arm_trajectory_started
        return temp_flag

 

Assign the value to the trajectory flag function and get the trajectory flag value function.

  

    def start(self):
        """
        Sends FollowJointTrajectoryAction request
        """
        self._limb_client.send_goal(self.goal, feedback_cb=self._feedback)
        # Syncronize playback by waiting for the trajectories to start
        while not rospy.is_shutdown() and not self._get_trajectory_flag():
            rospy.sleep(0.05)
        if self.has_gripper:
            self._execute_gripper_commands()

 

This function sends the FollowJointTrajectoryAction request message which includes the recorded positions and their corresponding time, to the Joint Trajectory Action Server.

  

    def stop(self):
        """
        Preempts trajectory execution by sending cancel goals
        """
        if (self._limb_client.gh is not None and
            self._limb_client.get_state() == actionlib.GoalStatus.ACTIVE):
            self._limb_client.cancel_goal()

        #delay to allow for terminating handshake
        rospy.sleep(0.1)

 

The Trajectory execution is stopped by sending cancel goals to the Joint trajectory action server.

  

    def wait(self):
        """
        Waits for and verifies trajectory execution result
        """
        #create a timeout for our trajectory execution
        #total time trajectory expected for trajectory execution plus a buffer
        last_time = self.goal.trajectory.points[-1].time_from_start.to_sec()
        time_buffer = rospy.get_param(self._param_ns + 'goal_time', 0.0) + 1.5
        timeout = rospy.Duration(self._slow_move_offset +
                                 last_time +
                                 time_buffer)

        finish = self._limb_client.wait_for_result(timeout)
        result = (self._limb_client.get_result().error_code == 0)

        #verify result
        if all([finish, result]):
            return True
        else:
            msg = ("Trajectory action failed or did not finish before "
                   "timeout/interrupt.")
            rospy.logwarn(msg)
            return False

 

This method waits for the completion of the trajectory execution by Joint trajectory action server.

  

def main():
    """RSDK Joint Trajectory Example: File Playback

    Plays back joint positions honoring timestamps recorded
    via the joint_recorder example.

    Run the joint_recorder.py example first to create a recording
    file for use with this example. Then make sure to start the
    joint_trajectory_action_server before running this example.

    This example will use the joint trajectory action server
    with velocity control to follow the positions and times of
    the recorded motion, accurately replicating movement speed
    necessary to hit each trajectory point on time.
    """
    epilog = """
Related examples:
  joint_recorder.py; joint_position_file_playback.py.
    """
    arg_fmt = argparse.RawDescriptionHelpFormatter
    parser = argparse.ArgumentParser(formatter_class=arg_fmt,
                                     description=main.__doc__,
                                     epilog=epilog)
    parser.add_argument(
        '-f', '--file', metavar='PATH', required=True,
        help='path to input file'
    )
    parser.add_argument(
        '-l', '--loops', type=int, default=1,
        help='number of playback loops. 0=infinite.'
    )
    # remove ROS args and filename (sys.arv[0]) for argparse
    args = parser.parse_args(rospy.myargv()[1:])

 

The name source file to read the Joint Position is captured along with the number of times the trajectory has to be looped from the command line.

 

    print("Initializing node... ")
    rospy.init_node("sdk_joint_trajectory_file_playback")
    print("Getting robot state... ")
    rs = intera_interface.RobotEnable(CHECK_VERSION)
    print("Enabling robot... ")
    rs.enable()
    print("Running. Ctrl-c to quit")

    traj = Trajectory()
    traj.parse_file(path.expanduser(args.file))
    #for safe interrupt handling
    rospy.on_shutdown(traj.stop)
    result = True
    loop_cnt = 1
    loopstr = str(args.loops)
    if args.loops == 0:
        args.loops = float('inf')
        loopstr = "forever"
    while (result == True and loop_cnt <= args.loops
           and not rospy.is_shutdown()):
        print("Playback loop %d of %s" % (loop_cnt, loopstr,))
        traj.start()
        result = traj.wait()
        loop_cnt = loop_cnt + 1
    print("Exiting - File Playback Complete")

if __name__ == "__main__":
    main()

 

The node is initialized. An instance of the Trajectory class is created. The parse_file() method is called to extract the recorded Joint Positions and their corresponding timestamps as explained above. The start() method is called to send the FollowJointTrajectory request message to the Joint Trajectory Action server. This loops for the user specified number of times.