pose_manager.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # ROS node to provide a few joint angle trajectories as default poses
4 #
5 # Copyright 2011 Armin Hornung & Daniel Maier University of Freiburg
6 # http://www.ros.org/wiki/nao
7 #
8 # Redistribution and use in source and binary forms, with or without
9 # modification, are permitted provided that the following conditions are met:
10 #
11 # # Redistributions of source code must retain the above copyright
12 # notice, this list of conditions and the following disclaimer.
13 # # Redistributions in binary form must reproduce the above copyright
14 # notice, this list of conditions and the following disclaimer in the
15 # documentation and/or other materials provided with the distribution.
16 # # Neither the name of the University of Freiburg nor the names of its
17 # contributors may be used to endorse or promote products derived from
18 # this software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
21 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
22 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
23 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
24 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
25 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
26 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
27 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
28 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
29 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30 # POSSIBILITY OF SUCH DAMAGE.
31 #
32 
33 import rospy
34 import sys
35 
36 import rospy.rostime
37 from rospy.rostime import Duration
38 
39 import actionlib
40 from actionlib_msgs.msg import GoalStatus
41 import naoqi_bridge_msgs.msg
42 from naoqi_bridge_msgs.msg import JointTrajectoryGoal, JointTrajectoryAction, BodyPoseAction, BodyPoseGoal
43 from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
44 
45 from sensor_msgs.msg import JointState
46 from std_msgs.msg import String
47 from std_msgs.msg import Bool
48 from std_srvs.srv import Empty
49 
50 import xapparser
51 
52 class PoseManager():
53  def __init__(self):
54  # ROS initialization:
55  rospy.init_node('pose_manager')
56 
57  self.poseLibrary = dict()
58  self.readInPoses()
59  self.poseServer = actionlib.SimpleActionServer("body_pose", BodyPoseAction,
60  execute_cb=self.executeBodyPose,
61  auto_start=False)
62  self.trajectoryClient = actionlib.SimpleActionClient("joint_trajectory", JointTrajectoryAction)
63  if self.trajectoryClient.wait_for_server(rospy.Duration(3.0)):
64  try:
65  rospy.wait_for_service("stop_walk_srv", timeout=2.0)
66  self.stopWalkSrv = rospy.ServiceProxy("stop_walk_srv", Empty)
67  except:
68  rospy.logwarn("stop_walk_srv not available, pose_manager will not stop the walker before executing a trajectory. "
69  +"This is normal if there is no nao_walker running.")
70  self.stopWalkSrv = None
71  self.poseServer.start()
72 
73  rospy.loginfo("pose_manager running, offering poses: %s", self.poseLibrary.keys());
74 
75  else:
76  rospy.logfatal("Could not connect to required \"joint_trajectory\" action server, is the nao_controller node running?");
77  rospy.signal_shutdown("Required component missing");
78 
79 
80  def parseXapPoses(self, xaplibrary):
81  try:
82  poses = xapparser.getpostures(xaplibrary)
83  except RuntimeError as re:
84  rospy.logwarn("Error while parsing the XAP file: %s" % str(re))
85  return
86 
87  for name, pose in poses.items():
88 
89  trajectory = JointTrajectory()
90 
91  trajectory.joint_names = pose.keys()
92  joint_values = pose.values()
93 
94  point = JointTrajectoryPoint()
95  point.time_from_start = Duration(2.0) # hardcoded duration!
96  point.positions = pose.values()
97  trajectory.points = [point]
98 
99  self.poseLibrary[name] = trajectory
100 
101 
102  def readInPoses(self):
103 
104  xaplibrary = rospy.get_param('~xap', None)
105  if xaplibrary:
106  self.parseXapPoses(xaplibrary)
107 
108  poses = rospy.get_param('~poses', None)
109  if poses:
110  for key,value in poses.iteritems():
111  try:
112  # TODO: handle multiple points in trajectory
113  trajectory = JointTrajectory()
114  trajectory.joint_names = value["joint_names"]
115  point = JointTrajectoryPoint()
116  point.time_from_start = Duration(value["time_from_start"])
117  point.positions = value["positions"]
118  trajectory.points = [point]
119  self.poseLibrary[key] = trajectory
120  except:
121  rospy.logwarn("Could not parse pose \"%s\" from the param server:", key);
122  rospy.logwarn(sys.exc_info())
123 
124  # add a default crouching pose:
125  if not "crouch" in self.poseLibrary:
126  trajectory = JointTrajectory()
127  trajectory.joint_names = ["Body"]
128  point = JointTrajectoryPoint()
129  point.time_from_start = Duration(1.5)
130  point.positions = [0.0,0.0, # head
131  1.545, 0.33, -1.57, -0.486, 0.0, 0.0, # left arm
132  -0.3, 0.057, -0.744, 2.192, -1.122, -0.035, # left leg
133  -0.3, 0.057, -0.744, 2.192, -1.122, -0.035, # right leg
134  1.545, -0.33, 1.57, 0.486, 0.0, 0.0] # right arm
135  trajectory.points = [point]
136  self.poseLibrary["crouch"] = trajectory;
137 
138 
139  rospy.loginfo("Loaded %d poses: %s", len(self.poseLibrary), self.poseLibrary.keys())
140 
141 
142  def executeBodyPose(self, goal):
143  if not goal.pose_name in self.poseLibrary:
144  rospy.loginfo("Pose %s not in library, reload library from parameters..." % goal.pose_name)
145  self.readInPoses()
146 
147  if goal.pose_name in self.poseLibrary:
148  rospy.loginfo("Executing body pose %s...", goal.pose_name);
149  if not self.stopWalkSrv is None:
150  self.stopWalkSrv()
151 
152  trajGoal = JointTrajectoryGoal()
153  # time out one sec. after trajectory ended:
154  trajGoal.trajectory = self.poseLibrary[goal.pose_name]
155  timeout = trajGoal.trajectory.points[-1].time_from_start + Duration(1.0)
156  trajGoal.trajectory.header.stamp = rospy.Time.now()
157  # TODO: cancel goal after timeout is not working yet in nao_controller
158  self.trajectoryClient.send_goal_and_wait(trajGoal, timeout)
159  if self.trajectoryClient.get_state() != GoalStatus.SUCCEEDED:
160  self.poseServer.set_aborted(text="JointTrajectory action did not succeed (timeout?)");
161 
162  self.poseServer.set_succeeded()
163  rospy.loginfo("Done.");
164 
165  else:
166  msg = "pose \""+goal.pose_name+"\" not in pose_manager's library";
167  rospy.logwarn("%s", msg)
168  self.poseServer.set_aborted(text=str(msg));
169 
170 
171 
172 if __name__ == '__main__':
173 
174  manager = PoseManager()
175  rospy.spin()
176  exit(0)
177 
def parseXapPoses(self, xaplibrary)
Definition: pose_manager.py:80
def executeBodyPose(self, goal)


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