2 # -*- coding: iso-8859-15 -*-
9 from sensor_msgs.msg import JointState
10 from control_msgs.msg import FollowJointTrajectoryAction, FollowJointTrajectoryActionResult, FollowJointTrajectoryActionFeedback, FollowJointTrajectoryResult
11 from control_msgs.msg import GripperCommandAction, GripperCommandActionResult, GripperCommandFeedback
12 from actionlib_msgs.msg import GoalStatus
13 from time import sleep
16 lJointNames = ["arm_base_to_link1", "link_1_2_joint", "link_2_3_joint", "link_3_4_joint", "link_4_5_joint", "left_gripper_joint", "right_gripper_joint"]
20 _feedback = FollowJointTrajectoryActionFeedback()
21 _result = FollowJointTrajectoryActionResult()
22 _gripper_feedback = GripperCommandFeedback()
23 _gripper_result = GripperCommandActionResult()
26 rospy.init_node('arm')
29 self.lAngles = [0] * 6
32 arm.set_hall_mode(3, 0)
33 arm.set_hall_mode(5, 0)
34 arm.set_tolerance(3, 0)
35 arm.set_tolerance(5, 0)
37 self._as_arm = actionlib.SimpleActionServer("arm_controller/follow_joint_trajectory", FollowJointTrajectoryAction, execute_cb=self.execute_joint_trajectory, auto_start = False)
39 self._as_gripper = actionlib.SimpleActionServer("gripper_controller/gripper_action", GripperCommandAction, execute_cb=self.execute_gripper_action, auto_start = False)
40 self._as_gripper.start()
41 self.pub_joint_states = rospy.Publisher("joint_states", JointState, queue_size=16)
46 while not rospy.is_shutdown():
47 self.publish_joint_states()
50 def publish_joint_states(self):
51 joint_state = JointState()
52 joint_state.header.stamp = rospy.Time.now()
53 joint_state.name = lJointNames
54 self.lAngles = [-arm.get_angle(0), arm.get_angle(1), -arm.get_angle(2), -arm.get_angle(3), arm.get_angle(4), 0.35-arm.get_angle(5)]
55 joint_state.position = self.lAngles[:-1] + [self.lAngles[-1], self.lAngles[-1]]
56 self.pub_joint_states.publish(joint_state)
58 def execute_joint_trajectory(self, goal):
59 self._result.status = FollowJointTrajectoryResult.SUCCESSFUL
60 for point in goal.trajectory.points:
61 print goal.trajectory.joint_names
64 point.positions[goal.trajectory.joint_names.index(lJointNames[0])],
65 point.positions[goal.trajectory.joint_names.index(lJointNames[1])],
66 point.positions[goal.trajectory.joint_names.index(lJointNames[2])],
67 point.positions[goal.trajectory.joint_names.index(lJointNames[3])],
68 point.positions[goal.trajectory.joint_names.index(lJointNames[4])],
71 arm.to_angle(0, self.speed, -lGoalPosOrdered[0])
72 arm.to_angle(1, self.speed, lGoalPosOrdered[1])
73 arm.to_angle(2, self.speed, -lGoalPosOrdered[2])
74 arm.to_angle(3, self.speed, -lGoalPosOrdered[3])
75 arm.to_angle(4, self.speed, lGoalPosOrdered[4])
76 except arm.RangeError as e:
77 print >> sys.stderr, e.message
78 self._feedback.status = GoalStatus.REJECTED
79 self._as_arm.publish_feedback(self._feedback.feedback)
80 self._result.status = FollowJointTrajectoryResult.INVALID_GOAL
85 error = np.array(lGoalPosOrdered) - np.array(self.lAngles[:-1])
87 if all(abs(f) < 0.02 for f in error):
88 print "Position reached"
91 if self._as_arm.is_preempt_requested():
92 self._as_arm.set_preempted()
96 self._feedback.status = GoalStatus.SUCCEEDED
97 self._feedback.feedback.joint_names = lJointNames[:-1]
98 self._feedback.feedback.desired.positions = lGoalPosOrdered
99 self._feedback.feedback.actual.positions = self.lAngles[:-1]
100 self._feedback.feedback.error.positions = error
101 self._as_arm.publish_feedback(self._feedback.feedback)
102 self._as_arm.set_succeeded(self._result.result)
105 def execute_gripper_action(self, goal):
106 arm.to_angle(5, self.speed, 0.35-goal.command.position)
108 error = goal.command.position - self.lAngles[-1]
109 if abs(error) < 0.02:
112 self._gripper_feedback.position = self.lAngles[-1]
113 self._gripper_feedback.stalled = False
114 self._gripper_feedback.reached_goal = False
116 if self._as_gripper.is_preempt_requested():
117 self._as_gripper.set_preempted()
120 self._gripper_result.status = GoalStatus.SUCCEEDED
121 self._gripper_result.result.position = goal.command.position
122 self._gripper_result.result.stalled = False
123 self._gripper_result.result.reached_goal = True
124 self._as_gripper.set_succeeded(self._gripper_result.result)
126 if __name__ == '__main__':