nao_controller.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 #
00004 # ROS node to provide joint angle control to Nao by wrapping NaoQI
00005 # This code is currently compatible to NaoQI version 1.6 or newer (latest 
00006 # tested: 1.12)
00007 #
00008 # Copyright 2011 Armin Hornung, University of Freiburg
00009 # http://www.ros.org/wiki/nao
00010 #
00011 # Redistribution and use in source and binary forms, with or without
00012 # modification, are permitted provided that the following conditions are met:
00013 #
00014 #    # Redistributions of source code must retain the above copyright
00015 #       notice, this list of conditions and the following disclaimer.
00016 #    # Redistributions in binary form must reproduce the above copyright
00017 #       notice, this list of conditions and the following disclaimer in the
00018 #       documentation and/or other materials provided with the distribution.
00019 #    # Neither the name of the University of Freiburg nor the names of its
00020 #       contributors may be used to endorse or promote products derived from
00021 #       this software without specific prior written permission.
00022 #
00023 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00024 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00025 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00026 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00027 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00028 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00029 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00030 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00031 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00032 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 # POSSIBILITY OF SUCH DAMAGE.
00034 #
00035 
00036 import roslib
00037 
00038 roslib.load_manifest('nao_driver')
00039 import rospy
00040 
00041 import actionlib
00042 import nao_msgs.msg
00043 from nao_msgs.msg import JointTrajectoryGoal, JointTrajectoryResult, JointTrajectoryAction, JointAnglesWithSpeed, \
00044                          JointAnglesWithSpeedGoal, JointAnglesWithSpeedResult, JointAnglesWithSpeedAction   
00045  
00046 from nao_driver import * 
00047 
00048 import math
00049 from math import fabs
00050 
00051 from std_msgs.msg import String
00052 from std_srvs.srv import Empty, EmptyResponse
00053 from sensor_msgs.msg import JointState
00054 
00055 class NaoController(NaoNode):
00056     def __init__(self): 
00057         NaoNode.__init__(self)
00058     
00059         # ROS initialization:
00060         rospy.init_node('nao_controller')
00061         
00062         self.connectNaoQi()
00063         
00064         # store the number of joints in each motion chain and collection, used for sanity checks
00065         self.collectionSize = {}
00066         for collectionName in ['Head', 'LArm', 'LLeg', 'RLeg', 'RArm', 'Body', 'BodyJoints', 'BodyActuators']:
00067             self.collectionSize[collectionName] = len(self.motionProxy.getJointNames(collectionName));
00068     
00069 
00070         # Get poll rate for actionlib (ie. how often to check whether currently running task has been preempted)
00071         # Defaults to 200ms
00072         self.poll_rate = int(rospy.get_param("~poll_rate", 0.2)*1000)
00073         
00074         # initial stiffness (defaults to 0 so it doesn't strain the robot when no teleoperation is running)
00075         # set to 1.0 if you want to control the robot immediately
00076         initStiffness = rospy.get_param('~init_stiffness', 0.0)
00077         
00078         # TODO: parameterize
00079         if initStiffness > 0.0 and initStiffness <= 1.0:
00080             self.motionProxy.stiffnessInterpolation('Body', initStiffness, 0.5)
00081 
00082 
00083         # start services / actions:
00084         self.enableStiffnessSrv = rospy.Service("body_stiffness/enable", Empty, self.handleStiffnessSrv)
00085         self.disableStiffnessSrv = rospy.Service("body_stiffness/disable", Empty, self.handleStiffnessOffSrv)
00086 
00087 
00088         #Start simple action servers
00089         self.jointTrajectoryServer = actionlib.SimpleActionServer("joint_trajectory", JointTrajectoryAction, 
00090                                                                   execute_cb=self.executeJointTrajectoryAction,
00091                                                                   auto_start=False)
00092         
00093         self.jointStiffnessServer = actionlib.SimpleActionServer("joint_stiffness_trajectory", JointTrajectoryAction, 
00094                                                                   execute_cb=self.executeJointStiffnessAction,
00095                                                                   auto_start=False)
00096         
00097         self.jointAnglesServer = actionlib.SimpleActionServer("joint_angles_action", JointAnglesWithSpeedAction, 
00098                                                                   execute_cb=self.executeJointAnglesWithSpeedAction,
00099                                                                   auto_start=False)
00100 
00101         #Start action servers
00102         self.jointTrajectoryServer.start()
00103         self.jointStiffnessServer.start()
00104         self.jointAnglesServer.start()
00105 
00106         # subsribers last:
00107         rospy.Subscriber("joint_angles", JointAnglesWithSpeed, self.handleJointAngles, queue_size=10)
00108         rospy.Subscriber("joint_stiffness", JointState, self.handleJointStiffness, queue_size=10)
00109 
00110         rospy.loginfo("nao_controller initialized")
00111 
00112     def connectNaoQi(self):
00113         '''(re-) connect to NaoQI'''
00114         rospy.loginfo("Connecting to NaoQi at %s:%d", self.pip, self.pport)
00115 
00116         self.motionProxy = self.getProxy("ALMotion")
00117         if self.motionProxy is None:
00118             exit(1)
00119             
00120     def handleJointAngles(self, msg):
00121         rospy.logdebug("Received a joint angle target")
00122         try:
00123             # Note: changeAngles() and setAngles() are non-blocking functions.
00124             if (msg.relative==0):
00125                 self.motionProxy.setAngles(list(msg.joint_names), list(msg.joint_angles), msg.speed)
00126             else:
00127                 self.motionProxy.changeAngles(list(msg.joint_names), list(msg.joint_angles), msg.speed)
00128         except RuntimeError,e:
00129             rospy.logerr("Exception caught:\n%s", e)
00130             
00131     def handleJointStiffness(self, msg):
00132         rospy.logdebug("Received a joint angle stiffness")
00133         try:
00134             self.motionProxy.setStiffnesses(list(msg.name), list(msg.effort))
00135         except RuntimeError,e:
00136             rospy.logerr("Exception caught:\n%s", e)
00137 
00138     def handleStiffnessSrv(self, req):
00139         try:
00140             self.motionProxy.stiffnessInterpolation("Body", 1.0, 0.5)
00141             rospy.loginfo("Body stiffness enabled")
00142             return EmptyResponse()
00143         except RuntimeError,e:
00144             rospy.logerr("Exception caught:\n%s", e)
00145             return None
00146         
00147     def handleStiffnessOffSrv(self, req):
00148         try:
00149             self.motionProxy.stiffnessInterpolation("Body", 0.0, 0.5)
00150             rospy.loginfo("Body stiffness removed")
00151             return EmptyResponse()
00152         except RuntimeError,e:
00153             rospy.logerr("Exception caught:\n%s", e)
00154             return None
00155             
00156 
00157     def jointTrajectoryGoalMsgToAL(self, goal):
00158         """Helper, convert action goal msg to Aldebraran-style arrays for NaoQI"""
00159         names = list(goal.trajectory.joint_names)
00160 #        if goal.trajectory.joint_names == ["Body"]:
00161 #            names = self.motionProxy.getJointNames('Body')
00162        
00163         if len(goal.trajectory.points) == 1 and len(goal.trajectory.points[0].positions) == 1:
00164             angles = goal.trajectory.points[0].positions[0]
00165         else:
00166             angles = list(list(p.positions[i] for p in goal.trajectory.points) for i in range(0,len(goal.trajectory.points[0].positions)))
00167         
00168         #strip 6,7 and last 2 from angles if the pose was for H25 but we're running an H21
00169         if not isinstance(angles, float) and len(angles) > self.collectionSize["Body"]:
00170             rospy.loginfo("Stripping angles from %d down to %d", len(angles), self.collectionSize["Body"])
00171             angles.pop(6)
00172             angles.pop(7)
00173             angles.pop()
00174             angles.pop()
00175             
00176         if len(names) > self.collectionSize["Body"]:
00177             rospy.loginfo("Stripping names from %d down to %d", len(names), self.collectionSize["Body"])
00178             names.pop(6)
00179             names.pop(7)
00180             names.pop()
00181             names.pop()
00182         
00183         times = list(p.time_from_start.to_sec() for p in goal.trajectory.points)
00184         if len(times) == 1 and len(names) == 1:
00185             times = times[0]
00186         if (len(names) > 1):
00187             times = [times]*len(names)
00188             
00189         return (names, angles, times)
00190     
00191 
00192     def executeJointTrajectoryAction(self, goal):
00193         rospy.loginfo("JointTrajectory action executing");
00194                     
00195         names, angles, times = self.jointTrajectoryGoalMsgToAL(goal)
00196                 
00197         rospy.logdebug("Received trajectory for joints: %s times: %s", str(names), str(times))     
00198         rospy.logdebug("Trajectory angles: %s", str(angles))
00199 
00200         task_id = None
00201         running = True
00202         #Wait for task to complete
00203         while running and not self.jointTrajectoryServer.is_preempt_requested() and not rospy.is_shutdown():
00204             #If we haven't started the task already...
00205             if task_id is None:
00206                 # ...Start it in another thread (thanks to motionProxy.post)
00207                 task_id = self.motionProxy.post.angleInterpolation(names, angles, times, (goal.relative==0))
00208             
00209             #Wait for a bit to complete, otherwise check we can keep running
00210             running = self.motionProxy.wait(task_id, self.poll_rate)
00211         
00212         # If still running at this point, stop the task
00213         if running and task_id:
00214             self.motionProxy.stop( task_id )
00215         
00216         jointTrajectoryResult = JointTrajectoryResult()
00217         jointTrajectoryResult.goal_position.header.stamp = rospy.Time.now()
00218         jointTrajectoryResult.goal_position.position = self.motionProxy.getAngles(names, True)
00219         jointTrajectoryResult.goal_position.name = names
00220 
00221         if not self.checkJointsLen(jointTrajectoryResult.goal_position):
00222             self.jointTrajectoryServer.set_aborted(jointTrajectoryResult)
00223             rospy.logerr("JointTrajectory action error in result: sizes mismatch")
00224         
00225         elif running:
00226             self.jointTrajectoryServer.set_preempted(jointTrajectoryResult)
00227             rospy.logdebug("JointTrajectory preempted")
00228         
00229         else:
00230             self.jointTrajectoryServer.set_succeeded(jointTrajectoryResult)
00231             rospy.loginfo("JointTrajectory action done")
00232 
00233 
00234     def executeJointStiffnessAction(self, goal):
00235         rospy.loginfo("JointStiffness action executing");
00236                     
00237         names, angles, times = self.jointTrajectoryGoalMsgToAL(goal)
00238         
00239         rospy.logdebug("Received stiffness trajectory for joints: %s times: %s", str(names), str(times))     
00240         rospy.logdebug("stiffness values: %s", str(angles))
00241 
00242         task_id = None
00243         running = True
00244         #Wait for task to complete
00245         while running and not self.jointStiffnessServer.is_preempt_requested() and not rospy.is_shutdown():
00246             #If we haven't started the task already...
00247             if task_id is None:
00248                 # ...Start it in another thread (thanks to motionProxy.post)
00249                 task_id = self.motionProxy.post.stiffnessInterpolation(names, angles, times)
00250             
00251             #Wait for a bit to complete, otherwise check we can keep running
00252             running = self.motionProxy.wait(task_id, self.poll_rate)
00253 
00254         # If still running at this point, stop the task
00255         if running and task_id:
00256             self.motionProxy.stop( task_id )
00257             
00258         jointStiffnessResult = JointTrajectoryResult()
00259         jointStiffnessResult.goal_position.header.stamp = rospy.Time.now()
00260         jointStiffnessResult.goal_position.position = self.motionProxy.getStiffnesses(names)
00261         jointStiffnessResult.goal_position.name = names
00262 
00263         if not self.checkJointsLen(jointStiffnessResult.goal_position):
00264             self.jointStiffnessServer.set_aborted(jointStiffnessResult)
00265             rospy.logerr("JointStiffness action error in result: sizes mismatch")
00266         
00267         elif running:
00268             self.jointStiffnessServer.set_preempted(jointStiffnessResult)
00269             rospy.logdebug("JointStiffness preempted")
00270         
00271         else:
00272             self.jointStiffnessServer.set_succeeded(jointStiffnessResult)
00273             rospy.loginfo("JointStiffness action done")
00274             
00275 
00276     def executeJointAnglesWithSpeedAction(self, goal):           
00277         
00278         names = list(goal.joint_angles.joint_names)
00279         angles = list(goal.joint_angles.joint_angles)
00280         rospy.logdebug("Received JointAnglesWithSpeed for joints: %s angles: %s", str(names), str(angles))
00281             
00282         if goal.joint_angles.relative == 1:
00283             # TODO: this uses the current angles instead of the angles at the given timestamp
00284             currentAngles = self.motionProxy.getAngles(names, True)
00285             angles = list(map(lambda x,y: x+y, angles, currentAngles))            
00286 
00287         task_id = None
00288         running = True
00289         #Wait for task to complete
00290         while running and not self.jointAnglesServer.is_preempt_requested() and not rospy.is_shutdown():
00291             #If we haven't started the task already...
00292             if task_id is None:
00293                 # ...Start it in another thread (thanks to motionProxy.post)
00294                 task_id = self.motionProxy.post.angleInterpolationWithSpeed(names, angles, goal.joint_angles.speed)
00295             
00296             #Wait for a bit to complete, otherwise check we can keep running
00297             running = self.motionProxy.wait(task_id, self.poll_rate)
00298         
00299         # If still running at this point, stop the task
00300         if running and task_id:
00301             self.motionProxy.stop( task_id )
00302             
00303         jointAnglesWithSpeedResult = JointAnglesWithSpeedResult()
00304         jointAnglesWithSpeedResult.goal_position.header.stamp = rospy.Time.now()
00305         jointAnglesWithSpeedResult.goal_position.position = self.motionProxy.getAngles(names, True)
00306         jointAnglesWithSpeedResult.goal_position.name = names
00307 
00308         if not self.checkJointsLen(jointAnglesWithSpeedResult.goal_position):
00309             self.jointAnglesServer.set_aborted(jointAnglesWithSpeedResult)
00310             rospy.logerr("JointAnglesWithSpeed action error in result: sizes mismatch")
00311 
00312         elif running:
00313             self.jointAnglesServer.set_preempted(jointAnglesWithSpeedResult)
00314             rospy.logdebug("JointAnglesWithSpeed preempted")
00315 
00316         else:
00317             self.jointAnglesServer.set_succeeded(jointAnglesWithSpeedResult)
00318             rospy.loginfo("JointAnglesWithSpeed action done")
00319 
00320     def checkJointsLen(self, goal_position):      
00321         if len(goal_position.name) == 1 and self.collectionSize.has_key(goal_position.name[0]):
00322             return len(goal_position.position) == self.collectionSize[goal_position.name[0]] 
00323         else:
00324             return len(goal_position.position) ==  len(goal_position.name)
00325 
00326 if __name__ == '__main__':
00327 
00328     controller = NaoController()
00329     rospy.loginfo("nao_controller running...")
00330     rospy.spin()
00331     
00332     rospy.loginfo("nao_controller stopped.")
00333     exit(0)
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


nao_driver
Author(s): Armin Hornung, Stefan Osswald, Daniel Maier
autogenerated on Tue Oct 15 2013 10:06:23