joint_trajectory_file_playback.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Copyright (c) 2013-2014, Rethink Robotics
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions are met:
00008 #
00009 # 1. Redistributions of source code must retain the above copyright notice,
00010 #    this list of conditions and the following disclaimer.
00011 # 2. Redistributions in binary form must reproduce the above copyright
00012 #    notice, this list of conditions and the following disclaimer in the
00013 #    documentation and/or other materials provided with the distribution.
00014 # 3. Neither the name of the Rethink Robotics nor the names of its
00015 #    contributors may be used to endorse or promote products derived from
00016 #    this software without specific prior written permission.
00017 #
00018 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00019 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00020 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00021 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00022 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00023 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00024 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00025 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00026 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00027 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00028 # POSSIBILITY OF SUCH DAMAGE.
00029 """
00030 Baxter RSDK Joint Trajectory Example: file playback
00031 """
00032 
00033 import argparse
00034 import operator
00035 import sys
00036 
00037 from bisect import bisect
00038 from copy import copy
00039 from os import path
00040 
00041 import rospy
00042 
00043 import actionlib
00044 
00045 from control_msgs.msg import (
00046     FollowJointTrajectoryAction,
00047     FollowJointTrajectoryGoal,
00048 )
00049 from trajectory_msgs.msg import (
00050     JointTrajectoryPoint,
00051 )
00052 
00053 import baxter_interface
00054 
00055 from baxter_interface import CHECK_VERSION
00056 
00057 
00058 class Trajectory(object):
00059     def __init__(self):
00060         #create our action server clients
00061         self._left_client = actionlib.SimpleActionClient(
00062             'robot/limb/left/follow_joint_trajectory',
00063             FollowJointTrajectoryAction,
00064         )
00065         self._right_client = actionlib.SimpleActionClient(
00066             'robot/limb/right/follow_joint_trajectory',
00067             FollowJointTrajectoryAction,
00068         )
00069 
00070         #verify joint trajectory action servers are available
00071         l_server_up = self._left_client.wait_for_server(rospy.Duration(1.0))
00072         r_server_up = self._right_client.wait_for_server(rospy.Duration(1.0))
00073         if not l_server_up or not r_server_up:
00074             msg = ("Action server not available."
00075                    " Verify action server availability.")
00076             rospy.logerr(msg)
00077             rospy.signal_shutdown(msg)
00078             sys.exit(1)
00079         #create our goal request
00080         self._l_goal = FollowJointTrajectoryGoal()
00081         self._r_goal = FollowJointTrajectoryGoal()
00082 
00083         #limb interface - current angles needed for start move
00084         self._l_arm = baxter_interface.Limb('left')
00085         self._r_arm = baxter_interface.Limb('right')
00086 
00087         #gripper interface - for gripper command playback
00088         self._l_gripper = baxter_interface.Gripper('left', CHECK_VERSION)
00089         self._r_gripper = baxter_interface.Gripper('right', CHECK_VERSION)
00090 
00091         # Verify Grippers Have No Errors and are Calibrated
00092         if self._l_gripper.error():
00093             self._l_gripper.reset()
00094         if self._r_gripper.error():
00095             self._r_gripper.reset()
00096         if (not self._l_gripper.calibrated() and
00097             self._l_gripper.type() != 'custom'):
00098             self._l_gripper.calibrate()
00099         if (not self._r_gripper.calibrated() and
00100             self._r_gripper.type() != 'custom'):
00101             self._r_gripper.calibrate()
00102 
00103         #gripper goal trajectories
00104         self._l_grip = FollowJointTrajectoryGoal()
00105         self._r_grip = FollowJointTrajectoryGoal()
00106 
00107         #param namespace
00108         self._param_ns = '/rsdk_joint_trajectory_action_server/'
00109 
00110         #gripper control rate
00111         self._gripper_rate = 20.0  # Hz
00112 
00113     def _execute_gripper_commands(self):
00114         start_time = rospy.get_time()
00115         r_cmd = self._r_grip.trajectory.points
00116         l_cmd = self._l_grip.trajectory.points
00117         pnt_times = [pnt.time_from_start.to_sec() for pnt in r_cmd]
00118         end_time = pnt_times[-1]
00119         rate = rospy.Rate(self._gripper_rate)
00120         now_from_start = rospy.get_time() - start_time
00121         while(now_from_start < end_time + (1.0 / self._gripper_rate) and
00122               not rospy.is_shutdown()):
00123             idx = bisect(pnt_times, now_from_start) - 1
00124             if self._r_gripper.type() != 'custom':
00125                 self._r_gripper.command_position(r_cmd[idx].positions[0])
00126             if self._l_gripper.type() != 'custom':
00127                 self._l_gripper.command_position(l_cmd[idx].positions[0])
00128             rate.sleep()
00129             now_from_start = rospy.get_time() - start_time
00130 
00131     def _clean_line(self, line, joint_names):
00132         """
00133         Cleans a single line of recorded joint positions
00134 
00135         @param line: the line described in a list to process
00136         @param joint_names: joint name keys
00137 
00138         @return command: returns dictionary {joint: value} of valid commands
00139         @return line: returns list of current line values stripped of commas
00140         """
00141         def try_float(x):
00142             try:
00143                 return float(x)
00144             except ValueError:
00145                 return None
00146         #convert the line of strings to a float or None
00147         line = [try_float(x) for x in line.rstrip().split(',')]
00148         #zip the values with the joint names
00149         combined = zip(joint_names[1:], line[1:])
00150         #take out any tuples that have a none value
00151         cleaned = [x for x in combined if x[1] is not None]
00152         #convert it to a dictionary with only valid commands
00153         command = dict(cleaned)
00154         return (command, line,)
00155 
00156     def _add_point(self, positions, side, time):
00157         """
00158         Appends trajectory with new point
00159 
00160         @param positions: joint positions
00161         @param side: limb to command point
00162         @param time: time from start for point in seconds
00163         """
00164         #creates a point in trajectory with time_from_start and positions
00165         point = JointTrajectoryPoint()
00166         point.positions = copy(positions)
00167         point.time_from_start = rospy.Duration(time)
00168         if side == 'left':
00169             self._l_goal.trajectory.points.append(point)
00170         elif side == 'right':
00171             self._r_goal.trajectory.points.append(point)
00172         elif side == 'left_gripper':
00173             self._l_grip.trajectory.points.append(point)
00174         elif side == 'right_gripper':
00175             self._r_grip.trajectory.points.append(point)
00176 
00177     def parse_file(self, filename):
00178         """
00179         Parses input file into FollowJointTrajectoryGoal format
00180 
00181         @param filename: input filename
00182         """
00183         #open recorded file
00184         with open(filename, 'r') as f:
00185             lines = f.readlines()
00186         #read joint names specified in file
00187         joint_names = lines[0].rstrip().split(',')
00188         #parse joint names for the left and right limbs
00189         for name in joint_names:
00190             if 'left' == name[:-3]:
00191                 self._l_goal.trajectory.joint_names.append(name)
00192             elif 'right' == name[:-3]:
00193                 self._r_goal.trajectory.joint_names.append(name)
00194 
00195         def find_start_offset(pos):
00196             #create empty lists
00197             cur = []
00198             cmd = []
00199             dflt_vel = []
00200             vel_param = self._param_ns + "%s_default_velocity"
00201             #for all joints find our current and first commanded position
00202             #reading default velocities from the parameter server if specified
00203             for name in joint_names:
00204                 if 'left' == name[:-3]:
00205                     cmd.append(pos[name])
00206                     cur.append(self._l_arm.joint_angle(name))
00207                     prm = rospy.get_param(vel_param % name, 0.25)
00208                     dflt_vel.append(prm)
00209                 elif 'right' == name[:-3]:
00210                     cmd.append(pos[name])
00211                     cur.append(self._r_arm.joint_angle(name))
00212                     prm = rospy.get_param(vel_param % name, 0.25)
00213                     dflt_vel.append(prm)
00214             diffs = map(operator.sub, cmd, cur)
00215             diffs = map(operator.abs, diffs)
00216             #determine the largest time offset necessary across all joints
00217             offset = max(map(operator.div, diffs, dflt_vel))
00218             return offset
00219 
00220         for idx, values in enumerate(lines[1:]):
00221             #clean each line of file
00222             cmd, values = self._clean_line(values, joint_names)
00223             #find allowable time offset for move to start position
00224             if idx == 0:
00225                 start_offset = find_start_offset(cmd)
00226             #add a point for this set of commands with recorded time
00227             cur_cmd = [cmd[jnt] for jnt in self._l_goal.trajectory.joint_names]
00228             self._add_point(cur_cmd, 'left', values[0] + start_offset)
00229             cur_cmd = [cmd[jnt] for jnt in self._r_goal.trajectory.joint_names]
00230             self._add_point(cur_cmd, 'right', values[0] + start_offset)
00231             cur_cmd = [cmd['left_gripper']]
00232             self._add_point(cur_cmd, 'left_gripper', values[0] + start_offset)
00233             cur_cmd = [cmd['right_gripper']]
00234             self._add_point(cur_cmd, 'right_gripper', values[0] + start_offset)
00235 
00236     def start(self):
00237         """
00238         Sends FollowJointTrajectoryAction request
00239         """
00240         self._left_client.send_goal(self._l_goal)
00241         self._right_client.send_goal(self._r_goal)
00242         self._execute_gripper_commands()
00243 
00244     def stop(self):
00245         """
00246         Preempts trajectory execution by sending cancel goals
00247         """
00248         if (self._left_client.gh is not None and
00249             self._left_client.get_state() == actionlib.GoalStatus.ACTIVE):
00250             self._left_client.cancel_goal()
00251 
00252         if (self._right_client.gh is not None and
00253             self._right_client.get_state() == actionlib.GoalStatus.ACTIVE):
00254             self._right_client.cancel_goal()
00255 
00256         #delay to allow for terminating handshake
00257         rospy.sleep(0.1)
00258 
00259     def wait(self):
00260         """
00261         Waits for and verifies trajectory execution result
00262         """
00263         #create a timeout for our trajectory execution
00264         #total time trajectory expected for trajectory execution plus a buffer
00265         last_time = self._r_goal.trajectory.points[-1].time_from_start.to_sec()
00266         time_buffer = rospy.get_param(self._param_ns + 'goal_time', 0.0) + 1.5
00267         timeout = rospy.Duration(last_time + time_buffer)
00268 
00269         l_finish = self._left_client.wait_for_result(timeout)
00270         r_finish = self._right_client.wait_for_result(timeout)
00271         l_result = (self._left_client.get_result().error_code == 0)
00272         r_result = (self._right_client.get_result().error_code == 0)
00273 
00274         #verify result
00275         if all([l_finish, r_finish, l_result, r_result]):
00276             return True
00277         else:
00278             msg = ("Trajectory action failed or did not finish before "
00279                    "timeout/interrupt.")
00280             rospy.logwarn(msg)
00281             return False
00282 
00283 
00284 def main():
00285     """RSDK Joint Trajectory Example: File Playback
00286 
00287     Plays back joint positions honoring timestamps recorded
00288     via the joint_recorder example.
00289 
00290     Run the joint_recorder.py example first to create a recording
00291     file for use with this example. Then make sure to start the
00292     joint_trajectory_action_server before running this example.
00293 
00294     This example will use the joint trajectory action server
00295     with velocity control to follow the positions and times of
00296     the recorded motion, accurately replicating movement speed
00297     necessary to hit each trajectory point on time.
00298     """
00299     epilog = """
00300 Related examples:
00301   joint_recorder.py; joint_position_file_playback.py.
00302     """
00303     arg_fmt = argparse.RawDescriptionHelpFormatter
00304     parser = argparse.ArgumentParser(formatter_class=arg_fmt,
00305                                      description=main.__doc__,
00306                                      epilog=epilog)
00307     parser.add_argument(
00308         '-f', '--file', metavar='PATH', required=True,
00309         help='path to input file'
00310     )
00311     parser.add_argument(
00312         '-l', '--loops', type=int, default=1,
00313         help='number of playback loops. 0=infinite.'
00314     )
00315     # remove ROS args and filename (sys.arv[0]) for argparse
00316     args = parser.parse_args(rospy.myargv()[1:])
00317 
00318     print("Initializing node... ")
00319     rospy.init_node("rsdk_joint_trajectory_file_playback")
00320     print("Getting robot state... ")
00321     rs = baxter_interface.RobotEnable(CHECK_VERSION)
00322     print("Enabling robot... ")
00323     rs.enable()
00324     print("Running. Ctrl-c to quit")
00325 
00326     traj = Trajectory()
00327     traj.parse_file(path.expanduser(args.file))
00328     #for safe interrupt handling
00329     rospy.on_shutdown(traj.stop)
00330     result = True
00331     loop_cnt = 1
00332     loopstr = str(args.loops)
00333     if args.loops == 0:
00334         args.loops = float('inf')
00335         loopstr = "forever"
00336     while (result == True and loop_cnt <= args.loops
00337            and not rospy.is_shutdown()):
00338         print("Playback loop %d of %s" % (loop_cnt, loopstr,))
00339         traj.start()
00340         result = traj.wait()
00341         loop_cnt = loop_cnt + 1
00342     print("Exiting - File Playback Complete")
00343 
00344 if __name__ == "__main__":
00345     main()


baxter_examples
Author(s): Rethink Robotics Inc.
autogenerated on Fri Oct 3 2014 16:37:39