9 from control_msgs.msg
import (
10 FollowJointTrajectoryAction,
11 FollowJointTrajectoryFeedback,
12 FollowJointTrajectoryResult,
15 from trajectory_msgs.msg
import (
26 GOAL_TOLERANCE = [0.05, 0.05, 0.05, 0.05, 0.05]
28 RATIOS = [3640, 8400, 6000, 4000, 4500]
32 OUTPUT_STRIP_CHARS = string.whitespace +
'>' 36 '''Reorganise waist-to-wrist ordered joint counts into alphabetical angle values for ros publishing''' 38 out[0] = float(-(li[2]*pi/(RATIOS[2]*2)))
39 out[1] = float(-(li[3]*pi/(RATIOS[3]*2)))
40 out[2] = float(-(li[1]*pi/(RATIOS[1]*2)))
41 out[3] = float(-(li[0]*pi/(RATIOS[0]*2)))
42 out[4] = float((li[4]*pi/(RATIOS[4]*2)))
46 '''Reorganise alphabetical angle values into waist-to-wrist ordered joint counts for sending to arm''' 48 out[0] = int(round(-(li[3]*2*RATIOS[0]/pi)))
49 out[1] = int(round(-(li[2]*2*RATIOS[1]/pi)))
50 out[2] = int(round(-(li[0]*2*RATIOS[2]/pi)))
51 out[3] = int(round(-(li[1]*2*RATIOS[3]/pi)))
52 out[4] = int(round(li[4]*2*RATIOS[4]/pi))
56 '''Joint trajectory action server allowing joint position based control of r12 arm''' 58 self.
_action_ns = controller_name +
'/follow_joint_trajectory' 61 FollowJointTrajectoryAction,
67 self.
_result = FollowJointTrajectoryResult()
69 rospy.loginfo(
'Successful init')
72 '''Checks if all joints are within tolerance of final position, and returns true if so''' 73 errors = map(operator.sub,
77 errors_tolerances = zip(errors, tolerances)
78 for ele
in errors_tolerances:
79 if (abs(ele[0]) > ele[1]) :
84 '''Updates feedback with current joint positions and returns current position as angles''' 86 self.
_feedback.header.stamp = rospy.Duration.from_sec(rospy.get_time())
88 self.
_feedback.desired.positions = new_pos
89 self.
_feedback.desired.time_from_start = rospy.Duration.from_sec(time_elapsed)
91 self.
_feedback.actual.time_from_start = rospy.Duration.from_sec(time_elapsed)
92 self.
_feedback.error.positions = map(operator.sub,
96 self.
_feedback.error.time_from_start = rospy.Duration.from_sec(time_elapsed)
101 '''Initialises and runs route, and updates feedback until complete or time duration violated''' 102 rospy.loginfo(
'Started cb')
103 start_time = rospy.get_time()
104 joint_names = goal.trajectory.joint_names
105 trajectory_points = goal.trajectory.points
107 trajectory_points = trajectory_points[1:]
108 arm.write(
'FIND TRAJECTORY .\r\n')
109 route_exists_check = arm.read()
110 route_exists_check = route_exists_check.strip(OUTPUT_STRIP_CHARS)
111 if (route_exists_check[-1]) <> 0:
112 arm.write(
'FORGET TRAJECTORY\r\n')
113 arm.write(
'ROUTE TRAJECTORY\r\n')
114 arm.write(
'500 RESERVE\r\n')
115 joint_values = [0, 0, 0, 0, 0]
116 for point
in trajectory_points:
119 for i
in range (4,-1,-1):
120 position_input += str(joint_values[i])
121 position_input +=
' ' 122 position_input +=
'$JL\r\n' 123 arm.write(position_input)
125 arm.write(
'$RUN\r\n')
126 end_time = trajectory_points[-1].time_from_start.to_sec()
127 time_elapsed = rospy.get_time() - start_time
128 pos = trajectory_points[0].positions
129 rospy.loginfo(
'Started route')
130 while (time_elapsed < end_time
and not rospy.is_shutdown()):
132 if self.
_as.is_preempt_requested():
133 rospy.loginfo(
"%s: Joint trajectory action preempted, stopping arm" % (self.
_action_name))
136 self.
_as.set_preempted()
138 result = self.
_check_goal(pos, trajectory_points[-1].positions, GOAL_TOLERANCE)
141 rospy.loginfo(
"%s: Joint trajectory action succeeded" % (self.
_action_name))
147 if __name__ ==
'__main__':
148 rospy.init_node(
'r12_interface')
150 rospy.loginfo(
'Success: Connected to ${0}.'.format(port))
def _execute_cb(self, goal)
def _check_goal(self, pos, final_pos, tolerances)
def _update_feedback(self, joint_names, last_pos, time_elapsed)
def __init__(self, controller_name)