]> defiant.homedns.org Git - arm_ros_conn.git/commitdiff
added FollowJointTrajectory Action Server
authorErik Andresen <erik@vontaene.de>
Tue, 20 Oct 2015 20:40:55 +0000 (22:40 +0200)
committerErik Andresen <erik@vontaene.de>
Tue, 20 Oct 2015 20:40:55 +0000 (22:40 +0200)
launch/arm.launch
scripts/arm_ros_conn.py

index 80bf10178b22ae97ca6b4dd45c65afee8756c41c..46cc15e08fa8c3ae2704df37d057300140e5a98d 100644 (file)
@@ -4,5 +4,5 @@
 
        <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" output="screen"/>
 
-       <node pkg="arm_ros_conn" type="arm_ros_conn.py" name="arm_ros_conn" output="screen" respawn="true"/>
+       <node pkg="arm_ros_conn" type="arm_ros_conn.py" name="arm_ros_conn" output="screen" respawn="false"/>
 </launch>
index d11344fa429925a11b68eccccf841d8c98a2a07a..42a3e5647558f664b6c376ca1077998d43434c00 100755 (executable)
@@ -5,12 +5,21 @@ import rospy
 import arm
 import actionlib
 from sensor_msgs.msg import JointState
-from control_msgs.msg import FollowJointTrajectoryAction
+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')
 
+               self.speed = 220
                arm.switch(0)
                arm.switch(2)
                arm.set_hall_mode(3, 0)
@@ -32,12 +41,25 @@ class ARMRosConn():
        def publish_joint_states(self):
                joint_state = JointState()
                joint_state.header.stamp = rospy.Time.now()
-               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"]
+               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):
-               print 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)
 
 
 if __name__ == '__main__':