torso_up.py
Go to the documentation of this file.
1 #! /usr/bin/python
2 import roslib
3 roslib.load_manifest('pr2_position_scripts')
4 
5 import rospy
6 import actionlib
7 from pr2_controllers_msgs.msg import SingleJointPositionAction, SingleJointPosi\
8 tionGoal
9 
10 rospy.init_node('torso_up')
11 torso_action_client = actionlib.SimpleActionClient('torso_controller/position_j\
12 oint_action', SingleJointPositionAction);
13 rospy.loginfo("torso_up: waiting for torso action server")
14 torso_action_client.wait_for_server()
15 rospy.loginfo("torso_up: torso action server found")
16 goal = SingleJointPositionGoal()
17 goal.position = 0.295
18 rospy.loginfo("torso_up: sending command to lift torso")
19 torso_action_client.send_goal(goal)
20 torso_action_client.wait_for_result(rospy.Duration(30))
21 


pr2_position_scripts
Author(s): Tony Pratkanis
autogenerated on Thu Jun 6 2019 19:18:45