]> defiant.homedns.org Git - arm_ros_conn.git/blobdiff - scripts/arm_ros_conn.py
added FollowJointTrajectory Action Server
[arm_ros_conn.git] / scripts / arm_ros_conn.py
index 67561b3b8dfb13111e329c91ea22400dc583e231..42a3e5647558f664b6c376ca1077998d43434c00 100755 (executable)
@@ -2,83 +2,65 @@
 # -*- coding: iso-8859-15 -*-
 
 import rospy
-import tf
-import prctl
-#import cProfile
-import threading
-from pyshared.json_client import JsonClient
-from geometry_msgs.msg import Twist
-from nav_msgs.msg import Odometry
+import arm
+import actionlib
+from sensor_msgs.msg import JointState
+from control_msgs.msg import FollowJointTrajectoryAction, FollowJointTrajectoryActionResult, FollowJointTrajectoryActionFeedback, FollowJointTrajectoryResult
+from actionlib_msgs.msg import GoalStatus
+from math import *
+
+lJointNames = ["base_to_link1", "link_1_2_joint", "link_2_3_joint", "gripper_joint_1", "gripper_joint_2", "left_gripper_joint", "right_gripper_joint"]
+
 
 class ARMRosConn():
+       _feedback = FollowJointTrajectoryActionFeedback()
+       _result = FollowJointTrajectoryActionResult()
+
        def __init__(self):
                rospy.init_node('arm')
-               prctl.set_name("arm_ros_bridge")
-               self.__lock_cmd = threading.Lock()
-               self.pComm = JsonClient(("arm", 10002))
-
-               rospy.Subscriber("cmd_vel", Twist, self.cmdVelReceived)
-               self.sub_scan = None
-               self.motion_enabled_last = None
-               self.pub_odom = rospy.Publisher("odom", Odometry, queue_size=16)
-               self.tf_broadcaster = tf.broadcaster.TransformBroadcaster()
 
+               self.speed = 220
+               arm.switch(0)
+               arm.switch(2)
+               arm.set_hall_mode(3, 0)
+               arm.set_hall_mode(5, 0)
+               arm.set_tolerance(3, 0)
+               arm.set_tolerance(5, 0)
+
+               self._as = actionlib.SimpleActionServer("arm_controller/follow_joint_trajectory", FollowJointTrajectoryAction, execute_cb=self.execute_joint_trajectory, auto_start = False)
+               self._as.start()
+               self.pub_joint_states = rospy.Publisher("joint_states", JointState, queue_size=16)
                self.run()
 
-       def command(self, cmd):
-               with self.__lock_cmd:
-                       return self.pComm.write(cmd)
-
        def run(self):
-               rate = rospy.Rate(10.0)
-               #pr = cProfile.Profile()
-               #pr.enable()
+               rate = rospy.Rate(20)
                while not rospy.is_shutdown():
-                       self.send_odometry()
-
+                       self.publish_joint_states()
                        rate.sleep()
-               #pr.disable()
-               #pr.dump_stats("/tmp/test.stats")
-
-       def send_odometry(self):
-               current_time = rospy.Time.now()
-                lPos, fAngle, lSpeed = self.command("get engine pose")
-
-               # since all odometry is 6DOF we'll need a quaternion created from yaw
-               odom_quat = tf.transformations.quaternion_from_euler(0, 0, fAngle)
-
-               # first, we'll publish the transform over tf
-               self.tf_broadcaster.sendTransform((lPos[0], lPos[1], 0.0), odom_quat, current_time, "base_link", "odom")
-
-               # next, we'll publish the odometry message over ROS
-               odom = Odometry()
-               odom.header.stamp = current_time
-               odom.header.frame_id = "/odom"
-
-               # set the position
-               odom.pose.pose.position.x = lPos[0]
-               odom.pose.pose.position.y = lPos[1]
-               odom.pose.pose.position.z = 0.0
-               odom.pose.pose.orientation.x = odom_quat[0]
-               odom.pose.pose.orientation.y = odom_quat[1]
-               odom.pose.pose.orientation.z = odom_quat[2]
-               odom.pose.pose.orientation.w = odom_quat[3]
-
-               # set the velocity
-               odom.child_frame_id = "base_link"
-               odom.twist.twist.linear.x = lSpeed[0]
-               odom.twist.twist.linear.y = 0.0
-               odom.twist.twist.angular.z = lSpeed[1]
-
-               # publish the message
-               self.pub_odom.publish(odom)
-
-       # test with rostopic pub -1 cmd_vel geometry_msgs/Twist '[0, 0, 0]' '[0, 0, 0]'
-       def cmdVelReceived(self, msg):
-               trans = msg.linear.x
-               rot = msg.angular.z
+       
+       def publish_joint_states(self):
+               joint_state = JointState()
+               joint_state.header.stamp = rospy.Time.now()
+               joint_state.name = lJointNames
+               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]
+               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
+                       arm.to_angle(0, self.speed, -point.positions[goal.trajectory.joint_names.index(lJointNames[0])])
+                       arm.to_angle(1, self.speed, point.positions[goal.trajectory.joint_names.index(lJointNames[1])])
+                       arm.to_angle(2, self.speed, -point.positions[goal.trajectory.joint_names.index(lJointNames[2])])
+                       arm.to_angle(3, self.speed, -point.positions[goal.trajectory.joint_names.index(lJointNames[3])])
+                       arm.to_angle(4, self.speed, point.positions[goal.trajectory.joint_names.index(lJointNames[4])])
+                       self._feedback.status = GoalStatus.SUCCEEDED
+                       self._feedback.feedback.joint_names = goal.trajectory.joint_names 
+                       self._feedback.feedback.desired = point
+                       self._as.publish_feedback(self._feedback.feedback)
+               self._result.status = FollowJointTrajectoryResult.SUCCESSFUL
+               self._as.set_succeeded(self._result.result)
 
-               self.command("set engine speed %f %f" % (trans, rot))
 
 if __name__ == '__main__':
        ARMRosConn()