$search
00001 #!/usr/bin/env python 00002 # 00003 # Copyright (c) 2010, Bosch LLC 00004 # All rights reserved. 00005 # 00006 # Redistribution and use in source and binary forms, with or without 00007 # modification, are permitted provided that the following conditions are met: 00008 # 00009 # * Redistributions of source code must retain the above copyright 00010 # notice, this list of conditions and the following disclaimer. 00011 # * Redistributions in binary form must reproduce the above copyright 00012 # notice, this list of conditions and the following disclaimer in the 00013 # documentation and/or other materials provided with the distribution. 00014 # * Neither the name of Bosch LLC nor the names of its 00015 # contributors may be used to endorse or promote products derived from 00016 # this software without specific prior written permission. 00017 # 00018 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00019 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00020 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00021 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00022 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00023 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00024 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00025 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00026 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00027 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00028 # POSSIBILITY OF SUCH DAMAGE. 00029 # 00030 # Authors: Christian Bersch Bosch LLC 00031 00032 import roslib 00033 roslib.load_manifest("simple_robot_control") 00034 import rospy 00035 00036 from pr2_controllers_msgs.msg import * 00037 import actionlib 00038 00039 class Torso: 00040 def __init__(self): 00041 00042 self.torsoClient = actionlib.SimpleActionClient("torso_controller/position_joint_action", pr2_controllers_msgs.msg.SingleJointPositionAction) 00043 00044 if not self.torsoClient.wait_for_server(rospy.Duration(10.0)): 00045 rospy.logerr("Could not connect to head_traj_controller/point_head_action") 00046 exit(1) 00047 00048 def move(self, position = 0.3, wait = True): 00049 if position > 0.3 or position < 0.0: 00050 print "torso position must be in [0.0 , 0.3]" 00051 return False 00052 goal = pr2_controllers_msgs.msg.SingleJointPositionGoal() 00053 goal.position = position 00054 goal.min_duration = rospy.Duration(2.0) 00055 goal.max_velocity = 1.0 00056 if wait: 00057 self.torsoClient.send_goal_and_wait(goal) 00058 else: 00059 self.torsoClient.send_goal(goal) 00060 00061 00062