44 from humanoid_nav_msgs.srv
import StepTargetService, StepTargetServiceResponse
45 from humanoid_nav_msgs.srv
import ClipFootstep, ClipFootstepResponse
47 from nao_apps
import ( startWalkPose, clip_footstep_tuple )
52 FLOAT_CMP_THR = 0.000001
57 return abs(a - b) <= FLOAT_CMP_THR
62 def __init__(self, x=0.0, y=0.0, theta=0.0, leg=0.0):
64 self.pose.x = round(x, 4)
65 self.pose.y = round(y, 4)
66 self.pose.theta = round(theta, 4)
70 return (
float_equ(self.pose.x, a.pose.x)
and 72 float_equ(self.pose.theta, a.pose.theta)
and 76 return not (self == a)
79 return "(%f, %f, %f, %i)" % (self.pose.x, self.pose.y, self.pose.theta,
88 NaoqiNode.__init__(self,
'nao_footsteps')
95 initStiffness = rospy.get_param(
'~init_stiffness', 0.0)
98 if initStiffness > 0.0
and initStiffness <= 1.0:
99 self.motionProxy.stiffnessInterpolation(
'Body', initStiffness, 0.5)
102 rospy.Subscriber(
"footstep", StepTarget, self.
handleStep, queue_size=50)
105 self.
stepToSrv = rospy.Service(
"footstep_srv", StepTargetService,
107 self.
clipSrv = rospy.Service(
"clip_footstep_srv", ClipFootstep,
112 "footsteps_execution",
116 self.actionServer.start()
118 rospy.loginfo(
"nao_footsteps initialized")
121 """(re-) connect to NaoQI""" 122 rospy.loginfo(
"Connecting to NaoQi at %s:%d", self.
pip, self.
pport)
131 Stops the current walking bahavior and blocks until the clearing is 135 self.motionProxy.setWalkTargetVelocity(0.0, 0.0, 0.0, self.stepFrequency)
136 self.motionProxy.waitUntilWalkIsFinished()
138 except RuntimeError,e:
139 print "An error has been caught" 147 rospy.loginfo(
"Step leg: %d; target: %f %f %f", data.leg, data.pose.x,
148 data.pose.y, data.pose.theta)
150 if data.leg == StepTarget.right:
152 elif data.leg == StepTarget.left:
155 rospy.logerr(
"Received a wrong leg constant: %d, ignoring step",
156 " command", data.leg)
159 footStep = [[data.pose.x, data.pose.y, data.pose.theta]]
160 timeList = [STEP_TIME]
161 self.motionProxy.setFootSteps(leg, footStep, timeList,
False)
163 print self.motionProxy.getFootSteps()
164 self.motionProxy.waitUntilWalkIsFinished()
167 except RuntimeError, e:
168 rospy.logerr(
"Exception caught in handleStep:\n%s", e)
173 return StepTargetServiceResponse()
178 is_left_support = step.leg != StepTarget.left
179 unclipped_step = (step.pose.x, step.pose.y, step.pose.theta)
181 unclipped_step, is_left_support)
185 resp = ClipFootstepResponse()
190 def update_feedback(feedback, executed_footsteps):
192 if not len(executed_footsteps):
196 leg, time, (x, y, theta) = executed_footsteps[-1]
200 leg = (StepTarget.right
if leg == LEG_RIGHT
else 205 if feedback.executed_footsteps[-1] == step:
209 feedback.executed_footsteps.append(step)
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)
220 rospy.logerr(
"Received a wrong leg constant: %d, ignoring step " 223 steps.append([round(step.pose.x, 4),
224 round(step.pose.y, 4),
225 round(step.pose.theta, 4)])
227 time_list.append(time_list[-1] + STEP_TIME)
229 time_list.append(STEP_TIME)
231 rospy.loginfo(
"Start executing footsteps %s",
232 [[x, y, theta, leg]
for (x, y, theta), leg
in 235 feedback = ExecFootstepsFeedback()
236 result = ExecFootstepsResult()
238 self.motionProxy.setFootSteps(legs, steps, time_list,
True)
239 while self.motionProxy.walkIsActive():
241 if self.actionServer.is_preempt_requested():
242 self.motionProxy.stopWalk()
243 self.actionServer.set_preempted()
244 rospy.loginfo(
"Preempting footstep execution");
249 (_, executed_footsteps, _) = self.motionProxy.getFootSteps()
250 update_feedback(feedback, executed_footsteps)
251 self.actionServer.publish_feedback(feedback)
253 rospy.Rate(goal.feedback_frequency).sleep()
256 result.executed_footsteps = feedback.executed_footsteps
257 self.actionServer.set_succeeded(result)
260 if __name__ ==
'__main__':
263 rospy.loginfo(
"nao_footsteps running...")
265 rospy.loginfo(
"nao_footsteps stopping...")
268 rospy.loginfo(
"nao_footsteps stopped.")
def get_proxy(self, name, warn=True)