00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029 """
00030 Baxter RSDK Joint Trajectory Example: file playback
00031 """
00032
00033 import argparse
00034 import operator
00035 import sys
00036 import threading
00037
00038 from bisect import bisect
00039 from copy import copy
00040 from os import path
00041
00042 import rospy
00043
00044 import actionlib
00045
00046 from control_msgs.msg import (
00047 FollowJointTrajectoryAction,
00048 FollowJointTrajectoryGoal,
00049 )
00050 from trajectory_msgs.msg import (
00051 JointTrajectoryPoint,
00052 )
00053
00054 import baxter_interface
00055
00056 from baxter_interface import CHECK_VERSION
00057
00058
00059 class Trajectory(object):
00060 def __init__(self):
00061
00062 self._left_client = actionlib.SimpleActionClient(
00063 'robot/limb/left/follow_joint_trajectory',
00064 FollowJointTrajectoryAction,
00065 )
00066 self._right_client = actionlib.SimpleActionClient(
00067 'robot/limb/right/follow_joint_trajectory',
00068 FollowJointTrajectoryAction,
00069 )
00070
00071
00072 l_server_up = self._left_client.wait_for_server(rospy.Duration(10.0))
00073 r_server_up = self._right_client.wait_for_server(rospy.Duration(10.0))
00074 if not l_server_up or not r_server_up:
00075 msg = ("Action server not available."
00076 " Verify action server availability.")
00077 rospy.logerr(msg)
00078 rospy.signal_shutdown(msg)
00079 sys.exit(1)
00080
00081 self._l_goal = FollowJointTrajectoryGoal()
00082 self._r_goal = FollowJointTrajectoryGoal()
00083
00084
00085 self._l_arm = baxter_interface.Limb('left')
00086 self._r_arm = baxter_interface.Limb('right')
00087
00088
00089 self._l_gripper = baxter_interface.Gripper('left', CHECK_VERSION)
00090 self._r_gripper = baxter_interface.Gripper('right', CHECK_VERSION)
00091
00092
00093 self._arm_trajectory_started = False
00094
00095 self._lock = threading.RLock()
00096
00097
00098 if self._l_gripper.error():
00099 self._l_gripper.reset()
00100 if self._r_gripper.error():
00101 self._r_gripper.reset()
00102 if (not self._l_gripper.calibrated() and
00103 self._l_gripper.type() != 'custom'):
00104 self._l_gripper.calibrate()
00105 if (not self._r_gripper.calibrated() and
00106 self._r_gripper.type() != 'custom'):
00107 self._r_gripper.calibrate()
00108
00109
00110 self._l_grip = FollowJointTrajectoryGoal()
00111 self._r_grip = FollowJointTrajectoryGoal()
00112
00113
00114 self._slow_move_offset = 0.0
00115 self._trajectory_start_offset = rospy.Duration(0.0)
00116
00117
00118 self._param_ns = '/rsdk_joint_trajectory_action_server/'
00119
00120
00121 self._gripper_rate = 20.0
00122
00123 def _execute_gripper_commands(self):
00124 start_time = rospy.get_time()
00125 r_cmd = self._r_grip.trajectory.points
00126 l_cmd = self._l_grip.trajectory.points
00127 pnt_times = [pnt.time_from_start.to_sec() for pnt in r_cmd]
00128 end_time = pnt_times[-1]
00129 rate = rospy.Rate(self._gripper_rate)
00130 now_from_start = rospy.get_time() - start_time
00131 while(now_from_start < end_time + (1.0 / self._gripper_rate) and
00132 not rospy.is_shutdown()):
00133 idx = bisect(pnt_times, now_from_start) - 1
00134 if self._r_gripper.type() != 'custom':
00135 self._r_gripper.command_position(r_cmd[idx].positions[0])
00136 if self._l_gripper.type() != 'custom':
00137 self._l_gripper.command_position(l_cmd[idx].positions[0])
00138 rate.sleep()
00139 now_from_start = rospy.get_time() - start_time
00140
00141 def _clean_line(self, line, joint_names):
00142 """
00143 Cleans a single line of recorded joint positions
00144
00145 @param line: the line described in a list to process
00146 @param joint_names: joint name keys
00147
00148 @return command: returns dictionary {joint: value} of valid commands
00149 @return line: returns list of current line values stripped of commas
00150 """
00151 def try_float(x):
00152 try:
00153 return float(x)
00154 except ValueError:
00155 return None
00156
00157 line = [try_float(x) for x in line.rstrip().split(',')]
00158
00159 combined = zip(joint_names[1:], line[1:])
00160
00161 cleaned = [x for x in combined if x[1] is not None]
00162
00163 command = dict(cleaned)
00164 return (command, line,)
00165
00166 def _add_point(self, positions, side, time):
00167 """
00168 Appends trajectory with new point
00169
00170 @param positions: joint positions
00171 @param side: limb to command point
00172 @param time: time from start for point in seconds
00173 """
00174
00175 point = JointTrajectoryPoint()
00176 point.positions = copy(positions)
00177 point.time_from_start = rospy.Duration(time)
00178 if side == 'left':
00179 self._l_goal.trajectory.points.append(point)
00180 elif side == 'right':
00181 self._r_goal.trajectory.points.append(point)
00182 elif side == 'left_gripper':
00183 self._l_grip.trajectory.points.append(point)
00184 elif side == 'right_gripper':
00185 self._r_grip.trajectory.points.append(point)
00186
00187 def parse_file(self, filename):
00188 """
00189 Parses input file into FollowJointTrajectoryGoal format
00190
00191 @param filename: input filename
00192 """
00193
00194 with open(filename, 'r') as f:
00195 lines = f.readlines()
00196
00197 joint_names = lines[0].rstrip().split(',')
00198
00199 for name in joint_names:
00200 if 'left' == name[:-3]:
00201 self._l_goal.trajectory.joint_names.append(name)
00202 elif 'right' == name[:-3]:
00203 self._r_goal.trajectory.joint_names.append(name)
00204
00205 def find_start_offset(pos):
00206
00207 cur = []
00208 cmd = []
00209 dflt_vel = []
00210 vel_param = self._param_ns + "%s_default_velocity"
00211
00212
00213 for name in joint_names:
00214 if 'left' == name[:-3]:
00215 cmd.append(pos[name])
00216 cur.append(self._l_arm.joint_angle(name))
00217 prm = rospy.get_param(vel_param % name, 0.25)
00218 dflt_vel.append(prm)
00219 elif 'right' == name[:-3]:
00220 cmd.append(pos[name])
00221 cur.append(self._r_arm.joint_angle(name))
00222 prm = rospy.get_param(vel_param % name, 0.25)
00223 dflt_vel.append(prm)
00224 diffs = map(operator.sub, cmd, cur)
00225 diffs = map(operator.abs, diffs)
00226
00227 offset = max(map(operator.div, diffs, dflt_vel))
00228 return offset
00229
00230 for idx, values in enumerate(lines[1:]):
00231
00232 cmd, values = self._clean_line(values, joint_names)
00233
00234 if idx == 0:
00235
00236
00237
00238
00239 cur_cmd = [self._l_arm.joint_angle(jnt) for jnt in self._l_goal.trajectory.joint_names]
00240 self._add_point(cur_cmd, 'left', 0.0)
00241 cur_cmd = [self._r_arm.joint_angle(jnt) for jnt in self._r_goal.trajectory.joint_names]
00242 self._add_point(cur_cmd, 'right', 0.0)
00243 start_offset = find_start_offset(cmd)
00244
00245
00246 self._slow_move_offset = start_offset
00247 self._trajectory_start_offset = rospy.Duration(start_offset + values[0])
00248
00249 cur_cmd = [cmd[jnt] for jnt in self._l_goal.trajectory.joint_names]
00250 self._add_point(cur_cmd, 'left', values[0] + start_offset)
00251 cur_cmd = [cmd[jnt] for jnt in self._r_goal.trajectory.joint_names]
00252 self._add_point(cur_cmd, 'right', values[0] + start_offset)
00253 cur_cmd = [cmd['left_gripper']]
00254 self._add_point(cur_cmd, 'left_gripper', values[0] + start_offset)
00255 cur_cmd = [cmd['right_gripper']]
00256 self._add_point(cur_cmd, 'right_gripper', values[0] + start_offset)
00257
00258 def _feedback(self, data):
00259
00260
00261 if (not self._get_trajectory_flag() and
00262 data.actual.time_from_start >= self._trajectory_start_offset):
00263 self._set_trajectory_flag(value=True)
00264
00265 def _set_trajectory_flag(self, value=False):
00266 with self._lock:
00267
00268 self._arm_trajectory_started = value
00269
00270 def _get_trajectory_flag(self):
00271 temp_flag = False
00272 with self._lock:
00273
00274 temp_flag = self._arm_trajectory_started
00275 return temp_flag
00276
00277 def start(self):
00278 """
00279 Sends FollowJointTrajectoryAction request
00280 """
00281 self._left_client.send_goal(self._l_goal, feedback_cb=self._feedback)
00282 self._right_client.send_goal(self._r_goal, feedback_cb=self._feedback)
00283
00284 while not rospy.is_shutdown() and not self._get_trajectory_flag():
00285 rospy.sleep(0.05)
00286 self._execute_gripper_commands()
00287
00288 def stop(self):
00289 """
00290 Preempts trajectory execution by sending cancel goals
00291 """
00292 if (self._left_client.gh is not None and
00293 self._left_client.get_state() == actionlib.GoalStatus.ACTIVE):
00294 self._left_client.cancel_goal()
00295
00296 if (self._right_client.gh is not None and
00297 self._right_client.get_state() == actionlib.GoalStatus.ACTIVE):
00298 self._right_client.cancel_goal()
00299
00300
00301 rospy.sleep(0.1)
00302
00303 def wait(self):
00304 """
00305 Waits for and verifies trajectory execution result
00306 """
00307
00308
00309 last_time = self._r_goal.trajectory.points[-1].time_from_start.to_sec()
00310 time_buffer = rospy.get_param(self._param_ns + 'goal_time', 0.0) + 1.5
00311 timeout = rospy.Duration(self._slow_move_offset +
00312 last_time +
00313 time_buffer)
00314
00315 l_finish = self._left_client.wait_for_result(timeout)
00316 r_finish = self._right_client.wait_for_result(timeout)
00317 l_result = (self._left_client.get_result().error_code == 0)
00318 r_result = (self._right_client.get_result().error_code == 0)
00319
00320
00321 if all([l_finish, r_finish, l_result, r_result]):
00322 return True
00323 else:
00324 msg = ("Trajectory action failed or did not finish before "
00325 "timeout/interrupt.")
00326 rospy.logwarn(msg)
00327 return False
00328
00329
00330 def main():
00331 """RSDK Joint Trajectory Example: File Playback
00332
00333 Plays back joint positions honoring timestamps recorded
00334 via the joint_recorder example.
00335
00336 Run the joint_recorder.py example first to create a recording
00337 file for use with this example. Then make sure to start the
00338 joint_trajectory_action_server before running this example.
00339
00340 This example will use the joint trajectory action server
00341 with velocity control to follow the positions and times of
00342 the recorded motion, accurately replicating movement speed
00343 necessary to hit each trajectory point on time.
00344 """
00345 epilog = """
00346 Related examples:
00347 joint_recorder.py; joint_position_file_playback.py.
00348 """
00349 arg_fmt = argparse.RawDescriptionHelpFormatter
00350 parser = argparse.ArgumentParser(formatter_class=arg_fmt,
00351 description=main.__doc__,
00352 epilog=epilog)
00353 parser.add_argument(
00354 '-f', '--file', metavar='PATH', required=True,
00355 help='path to input file'
00356 )
00357 parser.add_argument(
00358 '-l', '--loops', type=int, default=1,
00359 help='number of playback loops. 0=infinite.'
00360 )
00361
00362 args = parser.parse_args(rospy.myargv()[1:])
00363
00364 print("Initializing node... ")
00365 rospy.init_node("rsdk_joint_trajectory_file_playback")
00366 print("Getting robot state... ")
00367 rs = baxter_interface.RobotEnable(CHECK_VERSION)
00368 print("Enabling robot... ")
00369 rs.enable()
00370 print("Running. Ctrl-c to quit")
00371
00372 traj = Trajectory()
00373 traj.parse_file(path.expanduser(args.file))
00374
00375 rospy.on_shutdown(traj.stop)
00376 result = True
00377 loop_cnt = 1
00378 loopstr = str(args.loops)
00379 if args.loops == 0:
00380 args.loops = float('inf')
00381 loopstr = "forever"
00382 while (result == True and loop_cnt <= args.loops
00383 and not rospy.is_shutdown()):
00384 print("Playback loop %d of %s" % (loop_cnt, loopstr,))
00385 traj.start()
00386 result = traj.wait()
00387 loop_cnt = loop_cnt + 1
00388 print("Exiting - File Playback Complete")
00389
00390 if __name__ == "__main__":
00391 main()