+
+ def publish_joint_states(self):
+ joint_state = JointState()
+ joint_state.header.stamp = rospy.Time.now()
+ joint_state.name = lJointNames
+ self.lAngles = [-arm.get_angle(0), arm.get_angle(1), -arm.get_angle(2), -arm.get_angle(3), arm.get_angle(4), arm.get_angle(5)]
+ joint_state.position = self.lAngles[:-1] + [0.175-self.lAngles[-1]/2, 0.175-self.lAngles[-1]/2]
+ self.pub_joint_states.publish(joint_state)
+
+ def execute_joint_trajectory(self, goal):
+ for point in goal.trajectory.points:
+ print goal.trajectory.joint_names
+ print point.positions
+ lGoalPosOrdered = [
+ point.positions[goal.trajectory.joint_names.index(lJointNames[0])],
+ point.positions[goal.trajectory.joint_names.index(lJointNames[1])],
+ point.positions[goal.trajectory.joint_names.index(lJointNames[2])],
+ point.positions[goal.trajectory.joint_names.index(lJointNames[3])],
+ point.positions[goal.trajectory.joint_names.index(lJointNames[4])],
+ ]
+ arm.to_angle(0, self.speed, -lGoalPosOrdered[0])
+ arm.to_angle(1, self.speed, lGoalPosOrdered[1])
+ arm.to_angle(2, self.speed, -lGoalPosOrdered[2])
+ arm.to_angle(3, self.speed, -lGoalPosOrdered[3])
+ arm.to_angle(4, self.speed, lGoalPosOrdered[4])
+
+ error = 0
+ while True:
+ error = np.array(lGoalPosOrdered) - np.array(self.lAngles[:-1])
+ if np.linalg.norm(error) < 0.01:
+ break
+
+ if self._as.is_preempt_requested():
+ self._as.set_preempted()
+ break
+ sleep(0.001)
+
+ self._feedback.status = GoalStatus.SUCCEEDED
+ self._feedback.feedback.joint_names = lJointNames[:-1]
+ self._feedback.feedback.desired.positions = lGoalPosOrdered
+ self._feedback.feedback.actual.positions = self.lAngles[:-1]
+ self._feedback.feedback.error.positions = error
+ self._as.publish_feedback(self._feedback.feedback)
+ self._result.status = FollowJointTrajectoryResult.SUCCESSFUL
+ self._as.set_succeeded(self._result.result)