2 # -*- coding: iso-8859-15 -*-
7 from sensor_msgs.msg import JointState
8 from control_msgs.msg import FollowJointTrajectoryAction, FollowJointTrajectoryActionResult, FollowJointTrajectoryActionFeedback, FollowJointTrajectoryResult
9 from actionlib_msgs.msg import GoalStatus
12 lJointNames = ["base_to_link1", "link_1_2_joint", "link_2_3_joint", "gripper_joint_1", "gripper_joint_2", "left_gripper_joint", "right_gripper_joint"]
16 _feedback = FollowJointTrajectoryActionFeedback()
17 _result = FollowJointTrajectoryActionResult()
20 rospy.init_node('arm')
25 arm.set_hall_mode(3, 0)
26 arm.set_hall_mode(5, 0)
27 arm.set_tolerance(3, 0)
28 arm.set_tolerance(5, 0)
30 self._as = actionlib.SimpleActionServer("arm_controller/follow_joint_trajectory", FollowJointTrajectoryAction, execute_cb=self.execute_joint_trajectory, auto_start = False)
32 self.pub_joint_states = rospy.Publisher("joint_states", JointState, queue_size=16)
37 while not rospy.is_shutdown():
38 self.publish_joint_states()
41 def publish_joint_states(self):
42 joint_state = JointState()
43 joint_state.header.stamp = rospy.Time.now()
44 joint_state.name = lJointNames
45 joint_state.position = [-arm.get_angle(0), arm.get_angle(1), -arm.get_angle(2), -arm.get_angle(3), arm.get_angle(4), 0.175-arm.get_angle(5)/2, 0.175-arm.get_angle(5)/2]
46 self.pub_joint_states.publish(joint_state)
48 def execute_joint_trajectory(self, goal):
49 for point in goal.trajectory.points:
50 print goal.trajectory.joint_names
52 arm.to_angle(0, self.speed, -point.positions[goal.trajectory.joint_names.index(lJointNames[0])])
53 arm.to_angle(1, self.speed, point.positions[goal.trajectory.joint_names.index(lJointNames[1])])
54 arm.to_angle(2, self.speed, -point.positions[goal.trajectory.joint_names.index(lJointNames[2])])
55 arm.to_angle(3, self.speed, -point.positions[goal.trajectory.joint_names.index(lJointNames[3])])
56 arm.to_angle(4, self.speed, point.positions[goal.trajectory.joint_names.index(lJointNames[4])])
57 self._feedback.status = GoalStatus.SUCCEEDED
58 self._feedback.feedback.joint_names = goal.trajectory.joint_names
59 self._feedback.feedback.desired = point
60 self._as.publish_feedback(self._feedback.feedback)
61 self._result.status = FollowJointTrajectoryResult.SUCCESSFUL
62 self._as.set_succeeded(self._result.result)
65 if __name__ == '__main__':