45 rospy.init_node(
"trajectory_lock")
48 print "Using default joint bound of .08 per joint" 49 joint_bounds = [.08]*10
51 joint_bounds = [float(x)
for x
in rospy.myargv()[1:]]
56 max_error = max([abs(x)
for x
in msg.error.positions])
58 exceeded = [abs(x) > y
for x,y
in zip(msg.error.positions, joint_bounds)]
60 print "All: %s" %
" ".join([
"% .4f" % x
for x
in msg.error.positions] )
63 print "Exceeded: %.4f" % max_error
66 cmd = trajectory_msgs.msg.JointTrajectory()
67 cmd.header.stamp = msg.header.stamp
68 cmd.joint_names = msg.joint_names
69 cmd.points.append( trajectory_msgs.msg.JointTrajectoryPoint())
70 cmd.points[0].time_from_start = rospy.Duration(.125)
71 cmd.points[0].positions = msg.actual.positions
74 print "Small: %.4f" % max_error
77 pub = rospy.Publisher(
"command", trajectory_msgs.msg.JointTrajectory, queue_size=10)
79 rospy.Subscriber(
"state", pr2_controllers_msgs.msg.JointTrajectoryControllerState, callback)