execute_pose.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # A simple action client calling the pose_manager
4 #
5 # Author: Armin Hornung, University of Freiburg
6 
7 import rospy
8 import sys
9 import actionlib
10 
11 from naoqi_bridge_msgs.msg import BodyPoseAction, BodyPoseGoal
12 
13 if __name__ == '__main__':
14  if len(sys.argv) != 2:
15  sys.exit('\nUSAGE: %s pose_name\n\n' % sys.argv[0])
16 
17  rospy.init_node('execute_pose')
18 
19  poseClient = actionlib.SimpleActionClient("body_pose", BodyPoseAction)
20  if not poseClient.wait_for_server(rospy.Duration(3.0)):
21  rospy.logfatal("Could not connect to required \"body_pose\" action server, is the pose_manager node running?");
22  rospy.signal_shutdown();
23 
24  goal = BodyPoseGoal
25  goal.pose_name = str(sys.argv[1])
26  rospy.loginfo("Calling pose_manager for pose %s...", goal.pose_name)
27 
28 
29  poseClient.send_goal_and_wait(goal, rospy.Duration(5.0))
30  #TODO: check for errors
31  exit(0)


naoqi_pose
Author(s): Armin Hornung, Séverin Lemaignan
autogenerated on Thu Jul 16 2020 03:18:32