]> defiant.homedns.org Git - arm_ros_conn.git/blob - scripts/arm_ros_conn.py
angle/urdf fixes
[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 from sensor_msgs.msg import JointState
8 from control_msgs.msg import FollowJointTrajectoryAction
9
10 class ARMRosConn():
11         def __init__(self):
12                 rospy.init_node('arm')
13
14                 arm.switch(0)
15                 arm.switch(2)
16                 arm.set_hall_mode(3, 0)
17                 arm.set_hall_mode(5, 0)
18                 arm.set_tolerance(3, 0)
19                 arm.set_tolerance(5, 0)
20
21                 self._as = actionlib.SimpleActionServer("arm_controller/follow_joint_trajectory", FollowJointTrajectoryAction, execute_cb=self.execute_joint_trajectory, auto_start = False)
22                 self._as.start()
23                 self.pub_joint_states = rospy.Publisher("joint_states", JointState, queue_size=16)
24                 self.run()
25
26         def run(self):
27                 rate = rospy.Rate(20)
28                 while not rospy.is_shutdown():
29                         self.publish_joint_states()
30                         rate.sleep()
31         
32         def publish_joint_states(self):
33                 joint_state = JointState()
34                 joint_state.header.stamp = rospy.Time.now()
35                 joint_state.name = ["base_to_link1", "link_1_2_joint", "link_2_3_joint", "gripper_joint_1", "gripper_joint_2", "left_gripper_joint", "right_gripper_joint"]
36                 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]
37                 self.pub_joint_states.publish(joint_state)
38
39         def execute_joint_trajectory(self, goal):
40                 print goal
41
42
43 if __name__ == '__main__':
44         ARMRosConn()