nao_footsteps.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # ROS node to control Nao's footsteps (testing for NaoQI 1.12)
4 #
5 # Copyright 2012 Armin Hornung and Johannes Garimort, University of Freiburg
6 # http://www.ros.org/wiki/nao_driver
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 time
35 
36 from naoqi_driver.naoqi_node import NaoqiNode
37 
38 import math
39 from math import fabs
40 
41 import actionlib
42 
43 from humanoid_nav_msgs.msg import *
44 from humanoid_nav_msgs.srv import StepTargetService, StepTargetServiceResponse
45 from humanoid_nav_msgs.srv import ClipFootstep, ClipFootstepResponse
46 
47 from nao_apps import ( startWalkPose, clip_footstep_tuple )
48 
49 
50 LEG_LEFT = "LLeg"
51 LEG_RIGHT = "RLeg"
52 FLOAT_CMP_THR = 0.000001
53 STEP_TIME = 0.5
54 
55 
56 def float_equ(a, b):
57  return abs(a - b) <= FLOAT_CMP_THR
58 
59 
60 # redefine StepTarget by inheritance
62  def __init__(self, x=0.0, y=0.0, theta=0.0, leg=0.0):
63  super(StepTarget, self).__init__()
64  self.pose.x = round(x, 4)
65  self.pose.y = round(y, 4)
66  self.pose.theta = round(theta, 4)
67  self.leg = leg
68 
69  def __eq__(self, a):
70  return (float_equ(self.pose.x, a.pose.x) and
71  float_equ(self.pose.y, a.pose.y) and
72  float_equ(self.pose.theta, a.pose.theta) and
73  self.leg == a.leg)
74 
75  def __ne__(self, a):
76  return not (self == a)
77 
78  def __str__(self):
79  return "(%f, %f, %f, %i)" % (self.pose.x, self.pose.y, self.pose.theta,
80  self.leg)
81 
82  def __repr__(self):
83  return self.__str__()
84 
85 
87  def __init__(self):
88  NaoqiNode.__init__(self, 'nao_footsteps')
89 
90  self.connectNaoQi()
91 
92  # initial stiffness (defaults to 0 so it doesn't strain the robot when
93  # no teleoperation is running)
94  # set to 1.0 if you want to control the robot immediately
95  initStiffness = rospy.get_param('~init_stiffness', 0.0)
96 
97  # TODO: parameterize
98  if initStiffness > 0.0 and initStiffness <= 1.0:
99  self.motionProxy.stiffnessInterpolation('Body', initStiffness, 0.5)
100 
101  # last: ROS subscriptions (after all vars are initialized)
102  rospy.Subscriber("footstep", StepTarget, self.handleStep, queue_size=50)
103 
104  # ROS services (blocking functions)
105  self.stepToSrv = rospy.Service("footstep_srv", StepTargetService,
106  self.handleStepSrv)
107  self.clipSrv = rospy.Service("clip_footstep_srv", ClipFootstep,
108  self.handleClipSrv)
109 
110  # Initialize action server
112  "footsteps_execution",
113  ExecFootstepsAction,
114  execute_cb=self.footstepsExecutionCallback,
115  auto_start=False)
116  self.actionServer.start()
117 
118  rospy.loginfo("nao_footsteps initialized")
119 
120  def connectNaoQi(self):
121  """(re-) connect to NaoQI"""
122  rospy.loginfo("Connecting to NaoQi at %s:%d", self.pip, self.pport)
123 
124  self.motionProxy = self.get_proxy("ALMotion")
125  if self.motionProxy is None:
126  exit(1)
127 
128 
129  def stopWalk(self):
130  """
131  Stops the current walking bahavior and blocks until the clearing is
132  complete.
133  """
134  try:
135  self.motionProxy.setWalkTargetVelocity(0.0, 0.0, 0.0, self.stepFrequency)
136  self.motionProxy.waitUntilWalkIsFinished()
137 
138  except RuntimeError,e:
139  print "An error has been caught"
140  print e
141  return False
142 
143  return True
144 
145 
146  def handleStep(self, data):
147  rospy.loginfo("Step leg: %d; target: %f %f %f", data.leg, data.pose.x,
148  data.pose.y, data.pose.theta)
149  try:
150  if data.leg == StepTarget.right:
151  leg = [LEG_RIGHT]
152  elif data.leg == StepTarget.left:
153  leg = [LEG_LEFT]
154  else:
155  rospy.logerr("Received a wrong leg constant: %d, ignoring step",
156  " command", data.leg)
157  return
158 
159  footStep = [[data.pose.x, data.pose.y, data.pose.theta]]
160  timeList = [STEP_TIME]
161  self.motionProxy.setFootSteps(leg, footStep, timeList, False)
162  time.sleep(0.1)
163  print self.motionProxy.getFootSteps()
164  self.motionProxy.waitUntilWalkIsFinished()
165 
166  return True
167  except RuntimeError, e:
168  rospy.logerr("Exception caught in handleStep:\n%s", e)
169  return False
170 
171  def handleStepSrv(self, req):
172  if self.handleStep(req.step):
173  return StepTargetServiceResponse()
174  else:
175  return None
176 
177  def handleClipping(self, step):
178  is_left_support = step.leg != StepTarget.left
179  unclipped_step = (step.pose.x, step.pose.y, step.pose.theta)
180  step.pose.x, step.pose.y, step.pose.theta = clip_footstep_tuple(
181  unclipped_step, is_left_support)
182  return step
183 
184  def handleClipSrv(self, req):
185  resp = ClipFootstepResponse()
186  resp.step = self.handleClipping(req.step)
187  return resp
188 
189  def footstepsExecutionCallback(self, goal):
190  def update_feedback(feedback, executed_footsteps):
191  # check if an footstep has been performed
192  if not len(executed_footsteps):
193  return
194  # use the last footstep in the list since this might be the new one
195  # (NOTE: if one step is missed here, increase the feedback rate)
196  leg, time, (x, y, theta) = executed_footsteps[-1]
197  # check if footstep information is up-to-date
198  if not float_equ(time, STEP_TIME):
199  return
200  leg = (StepTarget.right if leg == LEG_RIGHT else
201  StepTarget.left)
202  step = StepTarget(x, y, theta, leg)
203  # add the footstep only if it is a new one
204  try:
205  if feedback.executed_footsteps[-1] == step:
206  return
207  except IndexError:
208  pass
209  feedback.executed_footsteps.append(step)
210 
211  legs = []
212  steps = []
213  time_list = []
214  for step in goal.footsteps:
215  if step.leg == StepTarget.right:
216  legs.append(LEG_RIGHT)
217  elif step.leg == StepTarget.left:
218  legs.append(LEG_LEFT)
219  else:
220  rospy.logerr("Received a wrong leg constant: %d, ignoring step "
221  "command", step.leg)
222  return
223  steps.append([round(step.pose.x, 4),
224  round(step.pose.y, 4),
225  round(step.pose.theta, 4)])
226  try:
227  time_list.append(time_list[-1] + STEP_TIME)
228  except IndexError:
229  time_list.append(STEP_TIME)
230 
231  rospy.loginfo("Start executing footsteps %s",
232  [[x, y, theta, leg] for (x, y, theta), leg in
233  zip(steps, legs)])
234 
235  feedback = ExecFootstepsFeedback()
236  result = ExecFootstepsResult()
237  success = True
238  self.motionProxy.setFootSteps(legs, steps, time_list, True)
239  while self.motionProxy.walkIsActive():
240  # handle preempt requests
241  if self.actionServer.is_preempt_requested():
242  self.motionProxy.stopWalk()
243  self.actionServer.set_preempted()
244  rospy.loginfo("Preempting footstep execution");
245  success = False
246  break
247 
248  # get execution information from the robot and update the feedback
249  (_, executed_footsteps, _) = self.motionProxy.getFootSteps()
250  update_feedback(feedback, executed_footsteps)
251  self.actionServer.publish_feedback(feedback)
252 
253  rospy.Rate(goal.feedback_frequency).sleep()
254 
255  if success:
256  result.executed_footsteps = feedback.executed_footsteps
257  self.actionServer.set_succeeded(result)
258 
259 
260 if __name__ == '__main__':
261 
262  walker = NaoFootsteps()
263  rospy.loginfo("nao_footsteps running...")
264  rospy.spin()
265  rospy.loginfo("nao_footsteps stopping...")
266  walker.stopWalk()
267 
268  rospy.loginfo("nao_footsteps stopped.")
269  exit(0)
def handleClipping(self, step)
def handleStepSrv(self, req)
def float_equ(a, b)
def handleClipSrv(self, req)
def clip_footstep_tuple(foot, is_left_support)
def footstepsExecutionCallback(self, goal)
def handleStep(self, data)
def __init__(self, x=0.0, y=0.0, theta=0.0, leg=0.0)
def get_proxy(self, name, warn=True)


nao_apps
Author(s):
autogenerated on Mon Jun 10 2019 14:04:55