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