pose_controller.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 #
4 # ROS node to provide joint angle control to Nao by wrapping NaoQI
5 # This code is currently compatible to NaoQI version 1.6 or newer (latest
6 # tested: 1.12)
7 #
8 # Copyright 2011 Armin Hornung, University of Freiburg
9 # http://www.ros.org/wiki/nao
10 #
11 # Redistribution and use in source and binary forms, with or without
12 # modification, are permitted provided that the following conditions are met:
13 #
14 # # Redistributions of source code must retain the above copyright
15 # notice, this list of conditions and the following disclaimer.
16 # # Redistributions in binary form must reproduce the above copyright
17 # notice, this list of conditions and the following disclaimer in the
18 # documentation and/or other materials provided with the distribution.
19 # # Neither the name of the University of Freiburg nor the names of its
20 # contributors may be used to endorse or promote products derived from
21 # this software without specific prior written permission.
22 #
23 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
24 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
25 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
26 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
27 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
28 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
29 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
30 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
31 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
32 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 # POSSIBILITY OF SUCH DAMAGE.
34 #
35 
36 
37 import rospy
38 import actionlib
39 from naoqi_bridge_msgs.msg import(
40  JointTrajectoryResult,
41  JointTrajectoryAction,
42  JointAnglesWithSpeed,
43  JointAnglesWithSpeedResult,
44  JointAnglesWithSpeedAction,
45  BodyPoseWithSpeedAction,
46  BodyPoseWithSpeedGoal,
47  BodyPoseWithSpeedResult)
48 
49 from naoqi_driver.naoqi_node import NaoqiNode
50 
51 from std_msgs.msg import String
52 from std_srvs.srv import Empty, EmptyResponse, Trigger, TriggerResponse
53 from sensor_msgs.msg import JointState
54 
55 class PoseController(NaoqiNode):
56  def __init__(self):
57  NaoqiNode.__init__(self, 'pose_controller')
58 
59  self.connectNaoQi()
60 
61  self.rate = rospy.Rate(10)
62 
63  # store the number of joints in each motion chain and collection, used for sanity checks
64  self.collectionSize = {}
65  for collectionName in ['Head', 'LArm', 'LLeg', 'RLeg', 'RArm', 'Body', 'BodyJoints', 'BodyActuators']:
66  try:
67  self.collectionSize[collectionName] = len(self.motionProxy.getJointNames(collectionName));
68  except RuntimeError:
69  # the following is useful for old NAOs with no legs/arms
70  rospy.logwarn('Collection %s not found on your robot.' % collectionName)
71 
72  # Get poll rate for actionlib (ie. how often to check whether currently running task has been preempted)
73  # Defaults to 200ms
74  self.poll_rate = int(rospy.get_param("~poll_rate", 0.2)*1000)
75 
76  # initial stiffness (defaults to 0 so it doesn't strain the robot when no teleoperation is running)
77  # set to 1.0 if you want to control the robot immediately
78  initStiffness = rospy.get_param('~init_stiffness', 0.0)
79 
80  # TODO: parameterize
81  if initStiffness > 0.0 and initStiffness <= 1.0:
82  self.motionProxy.stiffnessInterpolation('Body', initStiffness, 0.5)
83 
84  # advertise topics:
85  self.getLifeStatePub = rospy.Publisher("get_life_state", String, queue_size=10)
86 
87  # start services / actions:
88  self.enableStiffnessSrv = rospy.Service("body_stiffness/enable", Empty, self.handleStiffnessSrv)
89  self.disableStiffnessSrv = rospy.Service("body_stiffness/disable", Empty, self.handleStiffnessOffSrv)
90  self.wakeUpSrv = rospy.Service("wakeup", Empty, self.handleWakeUpSrv)
91  self.restSrv = rospy.Service("rest", Empty, self.handleRestSrv)
92  self.enableLifeSrv = rospy.Service("life/enable", Empty, self.handleLifeSrv)
93  self.disableLifeSrv = rospy.Service("life/disable", Empty, self.handleLifeOffSrv)
94  self.getLifeSrv = rospy.Service("life/get_state", Trigger, self.handleGetLifeSrv)
95 
96 
97  #Start simple action servers
98  self.jointTrajectoryServer = actionlib.SimpleActionServer("joint_trajectory", JointTrajectoryAction,
99  execute_cb=self.executeJointTrajectoryAction,
100  auto_start=False)
101 
102  self.jointStiffnessServer = actionlib.SimpleActionServer("joint_stiffness_trajectory", JointTrajectoryAction,
103  execute_cb=self.executeJointStiffnessAction,
104  auto_start=False)
105 
106  self.jointAnglesServer = actionlib.SimpleActionServer("joint_angles_action", JointAnglesWithSpeedAction,
107  execute_cb=self.executeJointAnglesWithSpeedAction,
108  auto_start=False)
109 
110  #Start action servers
111  self.jointTrajectoryServer.start()
112  self.jointStiffnessServer.start()
113  self.jointAnglesServer.start()
114 
115  # only start when ALRobotPosture proxy is available
116  if not (self.robotPostureProxy is None):
117  self.bodyPoseWithSpeedServer = actionlib.SimpleActionServer("body_pose_naoqi", BodyPoseWithSpeedAction,
118  execute_cb=self.executeBodyPoseWithSpeed,
119  auto_start=False)
120  self.bodyPoseWithSpeedServer.start()
121  else:
122  rospy.logwarn("Proxy to ALRobotPosture not available, requests to body_pose_naoqi will be ignored.")
123 
124  # subscribers last:
125  rospy.Subscriber("joint_angles", JointAnglesWithSpeed, self.handleJointAngles, queue_size=10)
126  rospy.Subscriber("joint_stiffness", JointState, self.handleJointStiffness, queue_size=10)
127 
128  rospy.loginfo("nao_controller initialized")
129 
130  def connectNaoQi(self):
131  '''(re-) connect to NaoQI'''
132  rospy.loginfo("Connecting to NaoQi at %s:%d", self.pip, self.pport)
133 
134  self.motionProxy = self.get_proxy("ALMotion")
135  if self.motionProxy is None:
136  exit(1)
137 
138  # optional, newly introduced in 1.14
139  self.robotPostureProxy = self.get_proxy("ALRobotPosture")
140 
141  # get a proxy to autonomous life
142  self.lifeProxy = self.get_proxy("ALAutonomousLife")
143 
144 
145  def handleJointAngles(self, msg):
146  rospy.logdebug("Received a joint angle target")
147  try:
148  # Note: changeAngles() and setAngles() are non-blocking functions.
149  if (msg.relative==0):
150  self.motionProxy.setAngles(list(msg.joint_names), list(msg.joint_angles), msg.speed)
151  else:
152  self.motionProxy.changeAngles(list(msg.joint_names), list(msg.joint_angles), msg.speed)
153  except RuntimeError,e:
154  rospy.logerr("Exception caught:\n%s", e)
155 
156  def handleJointStiffness(self, msg):
157  rospy.logdebug("Received a joint angle stiffness")
158  try:
159  self.motionProxy.setStiffnesses(list(msg.name), list(msg.effort))
160  except RuntimeError,e:
161  rospy.logerr("Exception caught:\n%s", e)
162 
163  def handleStiffnessSrv(self, req):
164  try:
165  self.motionProxy.stiffnessInterpolation("Body", 1.0, 0.5)
166  rospy.loginfo("Body stiffness enabled")
167  return EmptyResponse()
168  except RuntimeError,e:
169  rospy.logerr("Exception caught:\n%s", e)
170  return None
171 
172  def handleStiffnessOffSrv(self, req):
173  try:
174  self.motionProxy.stiffnessInterpolation("Body", 0.0, 0.5)
175  rospy.loginfo("Body stiffness removed")
176  return EmptyResponse()
177  except RuntimeError,e:
178  rospy.logerr("Exception caught:\n%s", e)
179  return None
180 
181  def handleWakeUpSrv(self, req):
182  try:
183  self.motionProxy.wakeUp()
184  rospy.loginfo("Wake Up")
185  return EmptyResponse()
186  except RuntimeError,e:
187  rospy.logerr("Exception caught:\n%s", e)
188  return None
189 
190  def handleRestSrv(self, req):
191  try:
192  self.motionProxy.rest()
193  rospy.loginfo("Rest")
194  return EmptyResponse()
195  except RuntimeError,e:
196  rospy.logerr("Exception caught:\n%s", e)
197  return None
198 
199  def handleLifeSrv(self, req):
200  try:
201  self.lifeProxy.setState("solitary")
202  rospy.loginfo("set life state to solitary")
203  return EmptyResponse()
204  except RuntimeError, e:
205  rospy.logerr("Exception while setting life state:\n%s", e)
206  return None
207 
208  def handleLifeOffSrv(self, req):
209  try:
210  self.lifeProxy.setState("disabled")
211  rospy.loginfo("set life state to disabled")
212  return EmptyResponse()
213  except RuntimeError, e:
214  rospy.logerr("Exception while disabling life state:\n%s", e)
215  return None
216 
217  def handleGetLifeSrv(self, req):
218  try:
219  res = TriggerResponse()
220  res.success = True
221  res.message = self.lifeProxy.getState()
222  rospy.loginfo("current life state is " + str(res.message))
223  return res
224  except RuntimeError, e:
225  rospy.logerr("Exception while getting life state:\n%s", e)
226  return None
227 
228  def jointTrajectoryGoalMsgToAL(self, goal):
229  """Helper, convert action goal msg to Aldebraran-style arrays for NaoQI"""
230  names = list(goal.trajectory.joint_names)
231 # if goal.trajectory.joint_names == ["Body"]:
232 # names = self.motionProxy.getJointNames('Body')
233 
234  if len(goal.trajectory.points) == 1 and len(goal.trajectory.points[0].positions) == 1:
235  angles = goal.trajectory.points[0].positions[0]
236  else:
237  angles = list(list(p.positions[i] for p in goal.trajectory.points) for i in range(0,len(goal.trajectory.points[0].positions)))
238 
239  #strip 6,7 and last 2 from angles if the pose was for H25 but we're running an H21
240  if not isinstance(angles, float) and len(angles) > self.collectionSize["Body"]:
241  rospy.loginfo("Stripping angles from %d down to %d", len(angles), self.collectionSize["Body"])
242  angles.pop(6)
243  angles.pop(7)
244  angles.pop()
245  angles.pop()
246 
247  if len(names) > self.collectionSize["Body"]:
248  rospy.loginfo("Stripping names from %d down to %d", len(names), self.collectionSize["Body"])
249  names.pop(6)
250  names.pop(7)
251  names.pop()
252  names.pop()
253 
254  times = list(p.time_from_start.to_sec() for p in goal.trajectory.points)
255  if len(times) == 1 and len(names) == 1:
256  times = times[0]
257  if (len(names) > 1):
258  times = [times]*len(names)
259 
260  return (names, angles, times)
261 
262 
264  rospy.loginfo("JointTrajectory action executing");
265 
266  names, angles, times = self.jointTrajectoryGoalMsgToAL(goal)
267 
268  rospy.logdebug("Received trajectory for joints: %s times: %s", str(names), str(times))
269  rospy.logdebug("Trajectory angles: %s", str(angles))
270 
271  task_id = None
272  running = True
273  #Wait for task to complete
274  while running and not self.jointTrajectoryServer.is_preempt_requested() and not rospy.is_shutdown():
275  #If we haven't started the task already...
276  if task_id is None:
277  # ...Start it in another thread (thanks to motionProxy.post)
278  task_id = self.motionProxy.post.angleInterpolation(names, angles, times, (goal.relative==0))
279 
280  #Wait for a bit to complete, otherwise check we can keep running
281  running = self.motionProxy.wait(task_id, self.poll_rate)
282 
283  # If still running at this point, stop the task
284  if running and task_id:
285  self.motionProxy.stop( task_id )
286 
287  jointTrajectoryResult = JointTrajectoryResult()
288  jointTrajectoryResult.goal_position.header.stamp = rospy.Time.now()
289  jointTrajectoryResult.goal_position.position = self.motionProxy.getAngles(names, True)
290  jointTrajectoryResult.goal_position.name = names
291 
292  if not self.checkJointsLen(jointTrajectoryResult.goal_position):
293  self.jointTrajectoryServer.set_aborted(jointTrajectoryResult)
294  rospy.logerr("JointTrajectory action error in result: sizes mismatch")
295 
296  elif running:
297  self.jointTrajectoryServer.set_preempted(jointTrajectoryResult)
298  rospy.logdebug("JointTrajectory preempted")
299 
300  else:
301  self.jointTrajectoryServer.set_succeeded(jointTrajectoryResult)
302  rospy.loginfo("JointTrajectory action done")
303 
304 
306  rospy.loginfo("JointStiffness action executing");
307 
308  names, angles, times = self.jointTrajectoryGoalMsgToAL(goal)
309 
310  rospy.logdebug("Received stiffness trajectory for joints: %s times: %s", str(names), str(times))
311  rospy.logdebug("stiffness values: %s", str(angles))
312 
313  task_id = None
314  running = True
315  #Wait for task to complete
316  while running and not self.jointStiffnessServer.is_preempt_requested() and not rospy.is_shutdown():
317  #If we haven't started the task already...
318  if task_id is None:
319  # ...Start it in another thread (thanks to motionProxy.post)
320  task_id = self.motionProxy.post.stiffnessInterpolation(names, angles, times)
321 
322  #Wait for a bit to complete, otherwise check we can keep running
323  running = self.motionProxy.wait(task_id, self.poll_rate)
324 
325  # If still running at this point, stop the task
326  if running and task_id:
327  self.motionProxy.stop( task_id )
328 
329  jointStiffnessResult = JointTrajectoryResult()
330  jointStiffnessResult.goal_position.header.stamp = rospy.Time.now()
331  jointStiffnessResult.goal_position.position = self.motionProxy.getStiffnesses(names)
332  jointStiffnessResult.goal_position.name = names
333 
334  if not self.checkJointsLen(jointStiffnessResult.goal_position):
335  self.jointStiffnessServer.set_aborted(jointStiffnessResult)
336  rospy.logerr("JointStiffness action error in result: sizes mismatch")
337 
338  elif running:
339  self.jointStiffnessServer.set_preempted(jointStiffnessResult)
340  rospy.logdebug("JointStiffness preempted")
341 
342  else:
343  self.jointStiffnessServer.set_succeeded(jointStiffnessResult)
344  rospy.loginfo("JointStiffness action done")
345 
346 
348 
349  names = list(goal.joint_angles.joint_names)
350  angles = list(goal.joint_angles.joint_angles)
351  rospy.logdebug("Received JointAnglesWithSpeed for joints: %s angles: %s", str(names), str(angles))
352 
353  if goal.joint_angles.relative == 1:
354  # TODO: this uses the current angles instead of the angles at the given timestamp
355  currentAngles = self.motionProxy.getAngles(names, True)
356  angles = list(map(lambda x,y: x+y, angles, currentAngles))
357 
358  task_id = None
359  running = True
360  #Wait for task to complete
361  while running and not self.jointAnglesServer.is_preempt_requested() and not rospy.is_shutdown():
362  #If we haven't started the task already...
363  if task_id is None:
364  # ...Start it in another thread (thanks to motionProxy.post)
365  task_id = self.motionProxy.post.angleInterpolationWithSpeed(names, angles, goal.joint_angles.speed)
366 
367  #Wait for a bit to complete, otherwise check we can keep running
368  running = self.motionProxy.wait(task_id, self.poll_rate)
369 
370  # If still running at this point, stop the task
371  if running and task_id:
372  self.motionProxy.stop( task_id )
373 
374  jointAnglesWithSpeedResult = JointAnglesWithSpeedResult()
375  jointAnglesWithSpeedResult.goal_position.header.stamp = rospy.Time.now()
376  jointAnglesWithSpeedResult.goal_position.position = self.motionProxy.getAngles(names, True)
377  jointAnglesWithSpeedResult.goal_position.name = names
378 
379  if not self.checkJointsLen(jointAnglesWithSpeedResult.goal_position):
380  self.jointAnglesServer.set_aborted(jointAnglesWithSpeedResult)
381  rospy.logerr("JointAnglesWithSpeed action error in result: sizes mismatch")
382 
383  elif running:
384  self.jointAnglesServer.set_preempted(jointAnglesWithSpeedResult)
385  rospy.logdebug("JointAnglesWithSpeed preempted")
386 
387  else:
388  self.jointAnglesServer.set_succeeded(jointAnglesWithSpeedResult)
389  rospy.loginfo("JointAnglesWithSpeed action done")
390 
391  def checkJointsLen(self, goal_position):
392  if len(goal_position.name) == 1 and self.collectionSize.has_key(goal_position.name[0]):
393  return len(goal_position.position) == self.collectionSize[goal_position.name[0]]
394  else:
395  return len(goal_position.position) == len(goal_position.name)
396 
397  def executeBodyPoseWithSpeed(self, goal):
398 
399  #~ Sanity checks
400  if (goal.speed < 0.0) or (goal.speed > 1.0):
401  bodyPoseWithSpeedResult = BodyPoseWithSpeedResult()
402  self.bodyPoseWithSpeedServer.set_aborted(bodyPoseWithSpeedResult)
403  rospy.logerr("Body pose setter: Not a valid speed value.")
404  return
405 
406  valid_postures = self.robotPostureProxy.getPostureList()
407 
408  if goal.posture_name not in valid_postures:
409  bodyPoseWithSpeedResult = BodyPoseWithSpeedResult()
410  self.bodyPoseWithSpeedServer.set_aborted(bodyPoseWithSpeedResult)
411  rospy.logerr("Body pose setter: Not a valid posture.")
412  return
413 
414  #~ Must set stiffness on
415  try:
416  self.motionProxy.stiffnessInterpolation("Body", 1.0, 0.5)
417  rospy.loginfo("Body stiffness enabled")
418  except RuntimeError,e:
419  rospy.logerr("Exception caught:\n%s", e)
420  return
421 
422  #~ Go to posture. This is blocking
423  self.robotPostureProxy.goToPosture(goal.posture_name, goal.speed)
424  #~ Return success
425  self.bodyPoseWithSpeedServer.set_succeeded()
426 
427  def run(self):
428  while self.is_looping():
429  try:
430  if self.getLifeStatePub.get_num_connections() > 0:
431  get_life_state_msg = String()
432  get_life_state_msg.data = self.lifeProxy.getState()
433  self.getLifeStatePub.publish(get_life_state_msg)
434 
435  except RuntimeError, e:
436  print "Error accessing ALMotion, ALRobotPosture, ALAutonomousLife, exiting...\n"
437  print e
438  rospy.signal_shutdown("No NaoQI available anymore")
439 
440  self.rate.sleep()
441 
442 if __name__ == '__main__':
443 
444  controller = PoseController()
445  controller.start()
446  rospy.loginfo("nao pose_controller running...")
447  rospy.spin()
448 
449  rospy.loginfo("nao pose_controller stopped.")
450  exit(0)
def executeJointTrajectoryAction(self, goal)
def executeJointAnglesWithSpeedAction(self, goal)
def jointTrajectoryGoalMsgToAL(self, goal)
def executeJointStiffnessAction(self, goal)
def checkJointsLen(self, goal_position)
def executeBodyPoseWithSpeed(self, goal)


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