]> defiant.homedns.org Git - arm_ros_conn.git/blob - scripts/arm_ros_conn.py
fixes for new urdf
[arm_ros_conn.git] / scripts / arm_ros_conn.py
1 #!/usr/bin/env python
2 # -*- coding: iso-8859-15 -*-
3
4 import sys
5 import rospy
6 import arm
7 import actionlib
8 import numpy as np
9 from sensor_msgs.msg import JointState
10 from control_msgs.msg import FollowJointTrajectoryAction, FollowJointTrajectoryActionResult, FollowJointTrajectoryActionFeedback, FollowJointTrajectoryResult
11 from control_msgs.msg import GripperCommandAction
12 from actionlib_msgs.msg import GoalStatus
13 from time import sleep
14 from math import *
15
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"]
17
18
19 class ARMRosConn():
20         _feedback = FollowJointTrajectoryActionFeedback()
21         _result = FollowJointTrajectoryActionResult()
22
23         def __init__(self):
24                 rospy.init_node('arm')
25
26                 self.speed = 220
27                 self.lAngles = [0] * 6
28                 arm.switch(0)
29                 arm.switch(2)
30                 arm.set_hall_mode(3, 0)
31                 arm.set_hall_mode(5, 0)
32                 arm.set_tolerance(3, 0)
33                 arm.set_tolerance(5, 0)
34
35                 self._as_arm = actionlib.SimpleActionServer("arm_controller/follow_joint_trajectory", FollowJointTrajectoryAction, execute_cb=self.execute_joint_trajectory, auto_start = False)
36                 self._as_arm.start()
37                 self._as_gripper = actionlib.SimpleActionServer("gripper_controller/gripper_action", GripperCommandAction, execute_cb=self.execute_gripper_action, auto_start = False)
38                 self._as_gripper.start()
39                 self.pub_joint_states = rospy.Publisher("joint_states", JointState, queue_size=16)
40                 self.run()
41
42         def run(self):
43                 rate = rospy.Rate(20)
44                 while not rospy.is_shutdown():
45                         self.publish_joint_states()
46                         rate.sleep()
47         
48         def publish_joint_states(self):
49                 joint_state = JointState()
50                 joint_state.header.stamp = rospy.Time.now()
51                 joint_state.name = lJointNames
52                 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)]
53                 joint_state.position = self.lAngles[:-1] + [0.175-self.lAngles[-1]/2, 0.175-self.lAngles[-1]/2]
54                 self.pub_joint_states.publish(joint_state)
55
56         def execute_joint_trajectory(self, goal):
57                 self._result.status = FollowJointTrajectoryResult.SUCCESSFUL
58                 for point in goal.trajectory.points:
59                         print goal.trajectory.joint_names
60                         print point.positions
61                         lGoalPosOrdered = [
62                                 point.positions[goal.trajectory.joint_names.index(lJointNames[0])],
63                                 point.positions[goal.trajectory.joint_names.index(lJointNames[1])],
64                                 point.positions[goal.trajectory.joint_names.index(lJointNames[2])],
65                                 point.positions[goal.trajectory.joint_names.index(lJointNames[3])],
66                                 point.positions[goal.trajectory.joint_names.index(lJointNames[4])],
67                         ]
68                         try:
69                                 arm.to_angle(0, self.speed, -lGoalPosOrdered[0])
70                                 arm.to_angle(1, self.speed,  lGoalPosOrdered[1])
71                                 arm.to_angle(2, self.speed, -lGoalPosOrdered[2])
72                                 arm.to_angle(3, self.speed, -lGoalPosOrdered[3])
73                                 arm.to_angle(4, self.speed,  lGoalPosOrdered[4])
74                         except arm.RangeError as e:
75                                 print >> sys.stderr, e.message
76                                 self._feedback.status = GoalStatus.REJECTED
77                                 self._as_arm.publish_feedback(self._feedback.feedback)
78                                 self._result.status = FollowJointTrajectoryResult.INVALID_GOAL
79                                 break
80
81                         error = 0
82                         while True:
83                                 error = np.array(lGoalPosOrdered) - np.array(self.lAngles[:-1])
84                                 print "Error", error
85                                 if all(f < 0.02 for f in error):
86                                         break
87
88                                 if self._as_arm.is_preempt_requested():
89                                         self._as_arm.set_preempted()
90                                         break
91                                 sleep(0.001)
92
93                         self._feedback.status = GoalStatus.SUCCEEDED
94                         self._feedback.feedback.joint_names = lJointNames[:-1]
95                         self._feedback.feedback.desired.positions = lGoalPosOrdered
96                         self._feedback.feedback.actual.positions = self.lAngles[:-1]
97                         self._feedback.feedback.error.positions = error
98                         self._as_arm.publish_feedback(self._feedback.feedback)
99                 self._as_arm.set_succeeded(self._result.result)
100
101
102         def execute_gripper_action(self, goal):
103                 print goal
104
105 if __name__ == '__main__':
106         ARMRosConn()