Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 import roslib; roslib.load_manifest('articulate_cart')
00037 import rospy
00038 import actionlib
00039 from pr2_controllers_msgs.msg import Pr2GripperCommandAction, Pr2GripperCommandGoal
00040 import move_base_msgs.msg
00041 import geometry_msgs.msg
00042 
00043 class CloseGrippers:
00044 
00045     def __init__(self):
00046         self.goal_received = False
00047         self.goal_sub = rospy.Subscriber('move_base/goal', move_base_msgs.msg.MoveBaseActionGoal, self.goal_cb)
00048         self.pose_sub = rospy.Subscriber('/initialpose', geometry_msgs.msg.PoseWithCovarianceStamped, self.pose_cb)
00049 
00050     def goal_cb(self, msg):
00051         if not self.goal_received:
00052             rospy.loginfo('Closing grippers now that a goal has been received')
00053             self.goal_received = True
00054         
00055     def pose_cb(self, msg):
00056         if not self.goal_received:
00057             rospy.loginfo('Closing grippers')
00058             self.goal_received = True
00059 
00060     def spin(self):
00061         l_client = actionlib.SimpleActionClient('l_gripper_controller/gripper_action', Pr2GripperCommandAction)
00062         r_client = actionlib.SimpleActionClient('r_gripper_controller/gripper_action', Pr2GripperCommandAction)
00063         l_client.wait_for_server()
00064         r_client.wait_for_server()
00065 
00066         goal = Pr2GripperCommandGoal()
00067         goal.command.position = 0.0
00068         goal.command.max_effort = 100.0
00069 
00070 
00071         while not rospy.is_shutdown():
00072             if self.goal_received:
00073                 l_client.send_goal(goal)
00074                 r_client.send_goal(goal)
00075                 l_client.wait_for_result()
00076                 r_client.wait_for_result()
00077             rospy.sleep(1)
00078 
00079 
00080 def main():
00081     rospy.init_node('close_grippers')
00082     node = CloseGrippers()
00083     rospy.loginfo('close_grippers initialized')
00084     node.spin()
00085 
00086     
00087 
00088 
00089 if __name__ == "__main__":
00090     main()