rg_int.py
Go to the documentation of this file.
00001 #!/usr/bin/python
00002 
00003 import roslib; roslib.load_manifest('assistive_teleop')
00004 import rospy
00005 from geometry_msgs.msg  import PoseStamped
00006 from std_msgs.msg import Float32, String
00007 from object_manipulation_msgs.msg import ReactiveGraspGoal, ReactiveGraspAction
00008 import pose_utils
00009 import actionlib
00010 
00011 class ReactiveGraspIntermediary:
00012     def __init__(self):
00013         rospy.Subscriber('wt_rg_left_goal', PoseStamped, self.left_goal_cb)
00014         rospy.Subscriber('wt_rg_right_goal', PoseStamped, self.right_goal_cb)
00015 
00016         self.pose_test = rospy.Publisher('test_pose', PoseStamped, latch=True)
00017 
00018         self.rg_action_client = [actionlib.SimpleActionClient('reactive_grasp/left', ReactiveGraspAction),
00019                                  actionlib.SimpleActionClient('reactive_grasp/right', ReactiveGraspAction)]
00020         
00021         rospy.loginfo("Waiting for reactive_grasp/left server")
00022         if self.rg_action_client[0].wait_for_server(rospy.Duration(3)):
00023             rospy.loginfo("Found reactive_grasp/left server")
00024         else:
00025             rospy.logwarn("CANNOT FIND reactive_grasp/left server")
00026         
00027         rospy.loginfo("Waiting for reactive_grasp/right server")
00028         if self.rg_action_client[0].wait_for_server(rospy.Duration(3)):
00029             rospy.loginfo("Found reactive_grasp/right server")
00030         else:
00031             rospy.logwarn("CANNOT FIND reactive_grasp/right server")
00032         
00033 
00034     def right_goal_cb(self, ps):
00035         goal_pose = self.find_approach(ps)
00036         self.pose_test.publish(goal_pose)
00037         goal = ReactiveGraspGoal()
00038         goal.arm_name = 'right_arm'
00039         goal.final_grasp_pose = goal_pose
00040         self.rg_action_client[1].send_goal(goal)
00041         print "Sent Reactive Grasp Goal to Right Arm"
00042 
00043     def left_goal_cb(self, ps):
00044         goal_pose = self.find_approach(ps)
00045         goal = ReactiveGraspGoal()
00046         goal.arm_name = 'right_arm'
00047         goal.final_grasp_pose = goal_pose
00048         self.rg_action_client[0].send_goal(goal)
00049         print "Sent Reactive Grasp Goal to Left Arm"
00050         
00051     def find_approach(self, ps, stdoff=0.16):
00052         rotd_pose = pose_utils.rot_pose(ps, 0, -90, 0)
00053         transd_pose = pose_utils.pose_relative_move(rotd_pose, -stdoff, 0, 0)
00054         return transd_pose
00055 
00056 
00057 
00058 if __name__=='__main__':
00059     rospy.init_node('wt_reactive_grasp_int')
00060     RGI = ReactiveGraspIntermediary()
00061     while not rospy.is_shutdown():
00062         rospy.spin()


assistive_teleop
Author(s): Phillip M. Grice, Advisor: Prof. Charlie Kemp, Lab: The Healthcare Robotoics Lab at Georgia Tech.
autogenerated on Wed Nov 27 2013 11:35:34