├── .gitignore ├── LICENSE.txt ├── README.md ├── nao_apps ├── CHANGELOG.rst ├── CMakeLists.txt ├── launch │ ├── alife.launch │ ├── behaviors.launch │ ├── footsteps.launch │ ├── leds.launch │ ├── speech.launch │ ├── tactile.launch │ └── walker.launch ├── nodes │ ├── nao_alife.py │ ├── nao_behaviors.py │ ├── nao_diagnostic_updater.py │ ├── nao_footsteps.py │ ├── nao_leds.py │ ├── nao_speech.py │ ├── nao_tactile.py │ └── nao_walker.py ├── package.xml ├── scripts │ ├── test_footsteps.py │ └── test_joint_angles.py ├── setup.py └── src │ └── nao_apps │ ├── __init__.py │ ├── nao_footstep_clipping.py │ └── start_walk_pose.py ├── nao_bringup ├── CHANGELOG.rst ├── CMakeLists.txt ├── config │ ├── nao_analysers.yaml │ └── nao_full.rviz ├── launch │ ├── nao_full.launch │ └── nao_full_py.launch └── package.xml ├── nao_description ├── CHANGELOG.rst ├── CMakeLists.txt ├── config │ └── urdf.rviz ├── launch │ ├── display.launch │ ├── robot_state_publisher.launch │ └── upload_nao.launch ├── package.xml ├── scripts │ └── test_cam_transform.py ├── src │ └── base_footprint.cpp └── urdf │ ├── naoV32_generated_urdf │ ├── nao.urdf │ ├── naoGazebo.xacro │ ├── naoTransmission.xacro │ ├── nao_arms.xacro │ ├── nao_fingers.xacro │ ├── nao_head.xacro │ ├── nao_legs.xacro │ ├── nao_material.xacro │ ├── nao_robot.xacro │ ├── nao_sensors.xacro │ ├── nao_torso.xacro │ └── nao_visual_collisions.xacro │ ├── naoV33_generated_urdf │ ├── nao.urdf │ ├── naoGazebo.xacro │ ├── naoTransmission.xacro │ ├── nao_arms.xacro │ ├── nao_fingers.xacro │ ├── nao_head.xacro │ ├── nao_legs.xacro │ ├── nao_material.xacro │ ├── nao_robot.xacro │ ├── nao_sensors.xacro │ ├── nao_torso.xacro │ └── nao_visual_collisions.xacro │ ├── naoV40_generated_urdf │ ├── nao.urdf │ ├── naoGazebo.xacro │ ├── naoTransmission.xacro │ ├── nao_arms.xacro │ ├── nao_fingers.xacro │ ├── nao_head.xacro │ ├── nao_legs.xacro │ ├── nao_material.xacro │ ├── nao_robot.xacro │ ├── nao_sensors.xacro │ ├── nao_torso.xacro │ └── nao_visual_collisions.xacro │ ├── naoV50_generated_urdf │ ├── nao.urdf │ ├── naoGazebo.xacro │ ├── naoTransmission.xacro │ ├── nao_arms.xacro │ ├── nao_fingers.xacro │ ├── nao_head.xacro │ ├── nao_legs.xacro │ ├── nao_material.xacro │ ├── nao_robot.xacro │ ├── nao_sensors.xacro │ ├── nao_torso.xacro │ └── nao_visual_collisions.xacro │ ├── nao_robot_v3.urdf.xacro │ ├── nao_robot_v3_structure.urdf.xacro │ ├── nao_robot_v4.urdf.xacro │ ├── nao_robot_v4_structure.urdf.xacro │ └── visuals.xacro └── nao_robot ├── CHANGELOG.rst ├── CMakeLists.txt └── package.xml /.gitignore: -------------------------------------------------------------------------------- 1 | *.py[cod] 2 | 3 | # C extensions 4 | *.so 5 | 6 | # Packages 7 | *.egg 8 | *.egg-info 9 | dist 10 | build 11 | eggs 12 | parts 13 | bin 14 | var 15 | sdist 16 | develop-eggs 17 | .installed.cfg 18 | lib 19 | lib64 20 | build/ 21 | 22 | # Installer logs 23 | pip-log.txt 24 | 25 | # Unit test / coverage reports 26 | .coverage 27 | .tox 28 | nosetests.xml 29 | 30 | # Translations 31 | *.mo 32 | 33 | # Mr Developer 34 | .mr.developer.cfg 35 | .project 36 | .pydevproject 37 | 38 | #Specific ignores for nao_robot 39 | naoqi_bridge_msgs/src 40 | msg_gen 41 | srv_gen 42 | # Actionlib: 43 | naoqi_bridge_msgs/msg/*Action.msg 44 | naoqi_bridge_msgs/msg/*Feedback.msg 45 | naoqi_bridge_msgs/msg/*Goal.msg 46 | naoqi_bridge_msgs/msg/*Result.msg 47 | 48 | -------------------------------------------------------------------------------- /LICENSE.txt: -------------------------------------------------------------------------------- 1 | Copyright (c) 2009-2013, A. Hornung, University of Freiburg 2 | All rights reserved. 3 | 4 | Redistribution and use in source and binary forms, with or without 5 | modification, are permitted provided that the following conditions are met: 6 | 7 | * Redistributions of source code must retain the above copyright 8 | notice, this list of conditions and the following disclaimer. 9 | * Redistributions in binary form must reproduce the above copyright 10 | notice, this list of conditions and the following disclaimer in the 11 | documentation and/or other materials provided with the distribution. 12 | * Neither the name of the University of Freiburg nor the names of its 13 | contributors may be used to endorse or promote products derived from 14 | this software without specific prior written permission. 15 | 16 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 17 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 18 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 19 | ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 20 | LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 21 | CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 22 | SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 23 | INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 24 | CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 25 | ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 26 | POSSIBILITY OF SUCH DAMAGE. 27 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | nao_robot 2 | ========= 3 | 4 | ROS stack for the NAO robot, see http://www.ros.org/wiki/nao_robot 5 | -------------------------------------------------------------------------------- /nao_apps/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package nao_apps 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.5.15 (2016-11-23) 6 | ------------------- 7 | * add missing dependencies 8 | * renamed tacticle to tactile 9 | * [nao_apps] Fixing bug generated when renaming in naoqi_bridge_msgs TactileTouch to HeadTouch 10 | * Fix hard-coded node name in dynamic_reconfigure.client, closes `#26 `_ 11 | * Contributors: Felip Marti, Mikael Arguedas, Stefan Osswald 12 | 13 | 0.5.14 (2016-01-23) 14 | ------------------- 15 | 16 | 0.5.13 (2016-01-16) 17 | ------------------- 18 | 19 | 0.5.12 (2016-01-01) 20 | ------------------- 21 | * change from naoqi_driver.cfg to naoqi_driver_py.cfg 22 | * Contributors: Kanae Kochigami 23 | 24 | 0.5.11 (2015-08-11) 25 | ------------------- 26 | 27 | 0.5.10 (2015-07-31) 28 | ------------------- 29 | 30 | 0.5.9 (2015-07-30) 31 | ------------------ 32 | 33 | 0.5.8 (2015-07-30) 34 | ------------------ 35 | * transfer to naoqi_py 36 | * use naoqi_pose instead of nao_pose 37 | * Contributors: Karsten Knese, Kei Okada 38 | 39 | 0.5.7 (2015-03-27) 40 | ------------------ 41 | * properly install Python scripts 42 | This fixes `#19 `_ 43 | * no need for custom file 44 | * enable goto initial pose to start walking 45 | * Contributors: Karsten Knese, Vincent Rabaud 46 | 47 | 0.5.6 (2015-02-27) 48 | ------------------ 49 | * Cleanup and rename launch files 50 | * Contributors: Karsten Knese 51 | 52 | 0.5.5 (2015-02-17) 53 | ------------------ 54 | 55 | 0.5.4 (2015-02-17) 56 | ------------------ 57 | 58 | 0.5.3 (2014-12-14) 59 | ------------------ 60 | * check naoqi version and exit if not supported 61 | * add nodes/nao_alife.py launch/nao_alife.launch 62 | * add .launch files 63 | * Contributors: Kei Okada 64 | 65 | 0.5.2 (2014-12-04) 66 | ------------------ 67 | * remove trailing spaces 68 | * add nao_speech.launch 69 | * Contributors: Kanae Kochigami, Mikael ARGUEDAS 70 | 71 | 0.5.1 (2014-11-13) 72 | ------------------ 73 | * Merge pull request `#2 `_ from k-okada/encode_utf8 74 | vocabulary must encode to utf8 75 | * bugfix: missing reconfigure in naoqi_driver 76 | * vocabulary must encode to utf8 77 | * bugfix: python imports 78 | * Contributors: Karsten Knese, Kei Okada, Vincent Rabaud 79 | 80 | 0.5.0 (2014-11-06) 81 | ------------------ 82 | * cleanups 83 | * transfer nao_robot apps 84 | * merge from nao_driver into nao_apps 85 | * Contributors: Karsten Knese, Vincent Rabaud 86 | -------------------------------------------------------------------------------- /nao_apps/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(nao_apps) 3 | 4 | ## Find catkin macros and libraries 5 | find_package(catkin REQUIRED COMPONENTS 6 | ) 7 | 8 | catkin_python_setup() 9 | 10 | catkin_package( 11 | ) 12 | 13 | catkin_install_python(PROGRAMS ./nodes/nao_alife.py ./nodes/nao_behaviors.py ./nodes/nao_diagnostic_updater.py 14 | ./nodes/nao_footsteps.py ./nodes/nao_leds.py ./nodes/nao_speech.py ./nodes/nao_tactile.py ./nodes/nao_walker.py 15 | DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 16 | ) 17 | 18 | install(DIRECTORY launch 19 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 20 | ) 21 | -------------------------------------------------------------------------------- /nao_apps/launch/alife.launch: -------------------------------------------------------------------------------- 1 | 2 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | -------------------------------------------------------------------------------- /nao_apps/launch/behaviors.launch: -------------------------------------------------------------------------------- 1 | 2 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | -------------------------------------------------------------------------------- /nao_apps/launch/footsteps.launch: -------------------------------------------------------------------------------- 1 | 2 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /nao_apps/launch/leds.launch: -------------------------------------------------------------------------------- 1 | 2 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | -------------------------------------------------------------------------------- /nao_apps/launch/speech.launch: -------------------------------------------------------------------------------- 1 | 2 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | -------------------------------------------------------------------------------- /nao_apps/launch/tactile.launch: -------------------------------------------------------------------------------- 1 | 2 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | -------------------------------------------------------------------------------- /nao_apps/launch/walker.launch: -------------------------------------------------------------------------------- 1 | 2 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | -------------------------------------------------------------------------------- /nao_apps/nodes/nao_alife.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | # 4 | # ROS node to interface with Naoqi Autonomous Life modules 5 | # Tested with NaoQI: 2.1 6 | # 7 | # Copyright (c) 2014, Kei Okada 8 | # 9 | # Redistribution and use in source and binary forms, with or without 10 | # modification, are permitted provided that the following conditions are met: 11 | # 12 | # # Redistributions of source code must retain the above copyright 13 | # notice, this list of conditions and the following disclaimer. 14 | # # Redistributions in binary form must reproduce the above copyright 15 | # notice, this list of conditions and the following disclaimer in the 16 | # documentation and/or other materials provided with the distribution. 17 | # # Neither the name of the Imperial College London nor the names of its 18 | # contributors may be used to endorse or promote products derived from 19 | # this software without specific prior written permission. 20 | # 21 | # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 22 | # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 23 | # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 24 | # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 25 | # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 26 | # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 27 | # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 28 | # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 29 | # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 30 | # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 31 | # POSSIBILITY OF SUCH DAMAGE. 32 | # 33 | 34 | import rospy 35 | import distutils 36 | 37 | from naoqi_driver.naoqi_node import NaoqiNode 38 | from naoqi import (ALBroker, ALProxy, ALModule) 39 | 40 | from std_srvs.srv import( Empty, EmptyResponse ) 41 | 42 | class NaoALife(NaoqiNode): 43 | #This should be treated as a constant 44 | NODE_NAME = "nao_alife" 45 | 46 | def __init__( self ): 47 | 48 | #Initialisation 49 | NaoqiNode.__init__( self, self.NODE_NAME ) 50 | if self.get_version() < distutils.version.LooseVersion('2.0'): 51 | rospy.logwarn("{} is only available on NaoQi version 2.0 or higher, your version is {}".format(self.NODE_NAME, self.get_version())) 52 | exit(1) 53 | 54 | #Proxy to interface with LEDs 55 | self.proxy = self.get_proxy( "ALAutonomousLife" ) 56 | 57 | # Register ROS services 58 | self.disabled_srv = rospy.Service("~disabled", Empty, self.disabled ) 59 | self.solitary_srv = rospy.Service("~solitary", Empty, self.solitary ) 60 | self.interactive_srv = rospy.Service("~interactive", Empty, self.interactive ) 61 | self.safeguard_srv = rospy.Service("~safeguard", Empty, self.safeguard ) 62 | 63 | def setstate( self, state): 64 | try: 65 | self.proxy.setState( state ) 66 | except Exception as e: 67 | rospy.logwarn("Could not transit from " + self.proxy.getState() + " to " + state) 68 | rospy.logerr(e) 69 | return EmptyResponse() 70 | 71 | def disabled( self, request = None ): 72 | return self.setstate('disabled') 73 | def solitary( self, request = None ): 74 | return self.setstate('solitary') 75 | def interactive( self, request = None ): 76 | return self.setstate('interactive') 77 | def safeguard( self, request = None ): 78 | return self.setstate('safeguard') 79 | 80 | if __name__ == '__main__': 81 | node = NaoALife() 82 | rospy.loginfo( node.NODE_NAME + " running..." ) 83 | rospy.spin() 84 | rospy.loginfo( node.NODE_NAME + " stopped." ) 85 | exit(0) 86 | -------------------------------------------------------------------------------- /nao_apps/nodes/nao_behaviors.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | # 4 | # ROS node to control NAO's built-in and user-installed behaviors using NaoQI 5 | # Tested with NaoQI: 1.12 6 | # 7 | # Copyright (c) 2012, 2013 Miguel Sarabia 8 | # Imperial College London 9 | # 10 | # Redistribution and use in source and binary forms, with or without 11 | # modification, are permitted provided that the following conditions are met: 12 | # 13 | # # Redistributions of source code must retain the above copyright 14 | # notice, this list of conditions and the following disclaimer. 15 | # # Redistributions in binary form must reproduce the above copyright 16 | # notice, this list of conditions and the following disclaimer in the 17 | # documentation and/or other materials provided with the distribution. 18 | # # Neither the name of the Imperial College London nor the names of its 19 | # contributors may be used to endorse or promote products derived from 20 | # this software without specific prior written permission. 21 | # 22 | # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 23 | # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 24 | # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 25 | # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 26 | # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 27 | # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 28 | # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 29 | # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 30 | # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 31 | # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 32 | # POSSIBILITY OF SUCH DAMAGE. 33 | # 34 | 35 | import threading 36 | import rospy 37 | import actionlib 38 | 39 | from naoqi_driver.naoqi_node import NaoqiNode 40 | 41 | from naoqi_bridge_msgs.msg import RunBehaviorAction 42 | 43 | from naoqi_bridge_msgs.srv import ( 44 | GetInstalledBehaviors, 45 | GetInstalledBehaviorsResponse, 46 | ) 47 | 48 | class NaoBehaviors(NaoqiNode): 49 | #This should be treated as a constant 50 | NODE_NAME = "nao_behaviors" 51 | 52 | def __init__( self ): 53 | 54 | #Initialisation 55 | NaoqiNode.__init__( self, self.NODE_NAME ) 56 | 57 | #We need this variable to be able to call stop behavior when preempted 58 | self.behavior = None 59 | self.lock = threading.RLock() 60 | 61 | #Proxy for listingBehaviors and stopping them 62 | self.behaviorProxy = self.get_proxy( "ALBehaviorManager" ) 63 | 64 | # Register ROS services 65 | self.getInstalledBehaviorsService = rospy.Service( 66 | "get_installed_behaviors", 67 | GetInstalledBehaviors, 68 | self.getInstalledBehaviors 69 | ) 70 | 71 | #Prepare and start actionlib server 72 | self.actionlibServer = actionlib.SimpleActionServer( 73 | "run_behavior", 74 | RunBehaviorAction, 75 | self.runBehavior, 76 | False 77 | ) 78 | 79 | self.actionlibServer.register_preempt_callback( self.stopBehavior ) 80 | 81 | self.actionlibServer.start() 82 | 83 | def getInstalledBehaviors( self, request ): 84 | result = self.behaviorProxy.getInstalledBehaviors() 85 | return GetInstalledBehaviorsResponse( result ) 86 | 87 | 88 | def runBehavior( self, request ): 89 | #Note this function is executed from a different thread 90 | rospy.logdebug( 91 | "Execution of behavior: '{}' requested".format(request.behavior)) 92 | 93 | #Check requested behavior is installed 94 | if not request.behavior in self.behaviorProxy.getInstalledBehaviors(): 95 | error_msg = "Behavior '{}' not installed".format(request.behavior) 96 | self.actionlibServer.set_aborted(text = error_msg) 97 | rospy.logdebug(error_msg) 98 | return 99 | 100 | with self.lock: 101 | # Check first if we're already preempted, and return if so 102 | if self.actionlibServer.is_preempt_requested(): 103 | self.actionlibServer.set_preempted() 104 | rospy.logdebug("Behavior execution preempted before it started") 105 | return 106 | 107 | #Save name of behavior to be run 108 | self.behavior = request.behavior 109 | #Execute behavior (on another thread so we can release lock) 110 | taskID = self.behaviorProxy.post.runBehavior( self.behavior ) 111 | 112 | # Wait for task to complete (or be preempted) 113 | rospy.logdebug("Waiting for behavior execution to complete") 114 | self.behaviorProxy.wait( taskID, 0 ) 115 | 116 | #Evaluate results 117 | with self.lock: 118 | self.behavior = None 119 | # If preempted, report so 120 | if self.actionlibServer.is_preempt_requested() : 121 | self.actionlibServer.set_preempted() 122 | rospy.logdebug("Behavior execution preempted") 123 | # Otherwise, set as succeeded 124 | else: 125 | self.actionlibServer.set_succeeded() 126 | rospy.logdebug("Behavior execution succeeded") 127 | 128 | def stopBehavior( self ): 129 | with self.lock: 130 | if self.behavior and self.actionlibServer.is_active() : 131 | self.behaviorProxy.stopBehavior( self.behavior ) 132 | 133 | 134 | if __name__ == '__main__': 135 | node = NaoBehaviors() 136 | rospy.loginfo( node.NODE_NAME + " running..." ) 137 | rospy.spin() 138 | rospy.loginfo( node.NODE_NAME + " stopped." ) 139 | exit(0) 140 | -------------------------------------------------------------------------------- /nao_apps/nodes/nao_leds.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | # 4 | # ROS node to control NAO's LEDs using NaoQI 5 | # Tested with NaoQI: 1.12 6 | # 7 | # Copyright (c) 2012, 2013 Miguel Sarabia 8 | # Imperial College London 9 | # 10 | # Redistribution and use in source and binary forms, with or without 11 | # modification, are permitted provided that the following conditions are met: 12 | # 13 | # # Redistributions of source code must retain the above copyright 14 | # notice, this list of conditions and the following disclaimer. 15 | # # Redistributions in binary form must reproduce the above copyright 16 | # notice, this list of conditions and the following disclaimer in the 17 | # documentation and/or other materials provided with the distribution. 18 | # # Neither the name of the Imperial College London nor the names of its 19 | # contributors may be used to endorse or promote products derived from 20 | # this software without specific prior written permission. 21 | # 22 | # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 23 | # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 24 | # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 25 | # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 26 | # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 27 | # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 28 | # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 29 | # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 30 | # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 31 | # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 32 | # POSSIBILITY OF SUCH DAMAGE. 33 | # 34 | 35 | 36 | import rospy 37 | import actionlib 38 | import random 39 | import copy 40 | 41 | from naoqi_driver.naoqi_node import NaoqiNode 42 | 43 | from naoqi_bridge_msgs.msg import( 44 | BlinkAction, 45 | BlinkResult, 46 | BlinkFeedback, 47 | FadeRGB 48 | ) 49 | 50 | class NaoLeds(NaoqiNode): 51 | #This should be treated as a constant 52 | NODE_NAME = "nao_leds" 53 | 54 | def __init__( self ): 55 | 56 | #Initialisation 57 | NaoqiNode.__init__( self, self.NODE_NAME ) 58 | 59 | #Proxy to interface with LEDs 60 | self.proxy = self.get_proxy( "ALLeds" ) 61 | 62 | #Seed python's random number generator 63 | random.seed( rospy.Time.now().to_nsec() ) 64 | 65 | #Create a subscriber for the fade_rgb topic 66 | self.subscriber = rospy.Subscriber( 67 | "fade_rgb", 68 | FadeRGB, 69 | self.fade_rgb) 70 | 71 | #Prepare and start actionlib server 72 | self.actionlib = actionlib.SimpleActionServer( 73 | "blink", 74 | BlinkAction, 75 | self.run_blink, 76 | False 77 | ) 78 | self.actionlib.start() 79 | 80 | def fade_rgb(self, request) : 81 | hexColor = int( 82 | int(request.color.r*255) << 16 | 83 | int(request.color.g*255) << 8 | 84 | int(request.color.b*255) 85 | ) 86 | 87 | self.proxy.fadeRGB( 88 | request.led_name, 89 | hexColor, 90 | request.fade_duration.to_sec() 91 | ) 92 | 93 | def run_blink( self, request ): 94 | #Note that this function is executed on a different thread 95 | 96 | third_of_duration = request.blink_duration / 3.0 97 | 98 | #Prepare background message 99 | bg_msg = FadeRGB(); 100 | bg_msg.led_name = "FaceLeds" 101 | bg_msg.color = request.bg_color 102 | bg_msg.fade_duration = third_of_duration 103 | 104 | #Prepare a copy for blink_msg 105 | blink_msg = copy.deepcopy( bg_msg ) 106 | 107 | #Construct result and feedback 108 | feedback = BlinkFeedback() 109 | result = BlinkResult() 110 | result.still_blinking = False 111 | 112 | #Check valid parameters 113 | bad_request = False 114 | reason = "" 115 | if not request.colors: 116 | bad_request = True 117 | reason = "No colors to blink were specified" 118 | elif request.blink_duration.to_sec() <= 0.0: 119 | bad_request = True 120 | reason = "Blink duration cannot be 0" 121 | elif request.blink_rate_mean <= 0.0 or request.blink_rate_sd <= 0.0: 122 | bad_request = True 123 | reason = "Invalid parameter for blink rate" 124 | 125 | if bad_request: 126 | rospy.logwarn("Bad Blink request: {}".format(reason)) 127 | self.actionlib.set_aborted(result, reason) 128 | return 129 | 130 | #Sleep time is drawn from a gaussian dist with these parameters 131 | sleep_mean = request.blink_rate_mean 132 | sleep_sd = request.blink_rate_sd 133 | max_sleep_time = sleep_mean + 3* sleep_sd #This is highly unlikely 134 | 135 | #Main blinking loop 136 | while ( not self.actionlib.is_preempt_requested() and 137 | not rospy.is_shutdown() ) : 138 | 139 | #Chose a blinking color at random 140 | blink_msg.color = random.choice( request.colors ) 141 | 142 | #Send command (takes 1/3 duration to fade) 143 | self.fade_rgb( blink_msg ) 144 | #Sleep (takes 1/3 duration) 145 | rospy.sleep( third_of_duration ) 146 | #Fade to background (takes another 1/3 duration) 147 | self.fade_rgb( bg_msg ) 148 | 149 | #Publish feedback 150 | feedback.last_color = blink_msg.color 151 | self.actionlib.publish_feedback( feedback ) 152 | 153 | #Sleep for a random amount of time 154 | sleep_time = random.gauss( sleep_mean, sleep_sd ) 155 | 156 | if sleep_time < 0: 157 | sleep_time = 0 158 | elif sleep_time > max_sleep_time : 159 | sleep_time = max_sleep_time 160 | 161 | rospy.sleep( sleep_time ) 162 | 163 | #If we were pre-empted by other request, make sure result shows this 164 | if self.actionlib.is_new_goal_available() : 165 | result.still_blinking = True 166 | 167 | # Task never completes so if we reach here, blink has been pre-empted 168 | self.actionlib.set_preempted( result ) 169 | 170 | if __name__ == '__main__': 171 | node = NaoLeds() 172 | rospy.loginfo( node.NODE_NAME + " running..." ) 173 | rospy.spin() 174 | rospy.loginfo( node.NODE_NAME + " stopped." ) 175 | exit(0) 176 | -------------------------------------------------------------------------------- /nao_apps/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | nao_apps 4 | 0.5.15 5 | Applications for NAO using the NAOqi API 6 | 7 | Vincent Rabaud 8 | 9 | BSD 10 | 11 | catkin 12 | 13 | actionlib 14 | diagnostic_msgs 15 | dynamic_reconfigure 16 | geometry_msgs 17 | humanoid_nav_msgs 18 | naoqi_apps 19 | naoqi_navigation 20 | naoqi_sensors_py 21 | naoqi_tools 22 | naoqi_bridge_msgs 23 | naoqi_driver 24 | naoqi_driver_py 25 | naoqi_pose 26 | rospy 27 | std_msgs 28 | std_srvs 29 | 30 | trajectory_msgs 31 | 32 | 33 | -------------------------------------------------------------------------------- /nao_apps/scripts/test_footsteps.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | import roslib 4 | roslib.load_manifest('naoqi_driver') 5 | import rospy 6 | from rospy.exceptions import ROSException 7 | 8 | 9 | import roslib.rostime 10 | from roslib.rostime import Duration 11 | 12 | 13 | import std_srvs 14 | from std_srvs.srv import Empty 15 | import humanoid_nav_msgs 16 | from humanoid_nav_msgs.msg import StepTarget 17 | from humanoid_nav_msgs.srv import StepTargetService, StepTargetServiceRequest 18 | 19 | def footstep_client(): 20 | inhibitWalkSrv = rospy.ServiceProxy("inhibit_walk", std_srvs.srv.Empty) 21 | uninhibitWalkSrv = rospy.ServiceProxy("uninhibit_walk", std_srvs.srv.Empty) 22 | 23 | 24 | 25 | rospy.loginfo("Waiting for footstep server...") 26 | rospy.wait_for_service('footstep_srv') 27 | client = rospy.ServiceProxy("footstep_srv", humanoid_nav_msgs.srv.StepTargetService) 28 | rospy.loginfo("Done.") 29 | 30 | # try: 31 | goal = StepTarget() 32 | goal.leg = 0 33 | goal.pose.x = 0.08 34 | goal.pose.theta = 0.3 35 | client(goal) 36 | 37 | goal.leg = 1 38 | goal.pose.theta = 0.3 39 | client(goal) 40 | 41 | goal.leg = 0 42 | goal.pose.x = 0.0 43 | goal.pose.y = -0.16 44 | client(goal) 45 | 46 | goal.leg = 1 47 | goal.pose.x = 0.00 48 | goal.pose.y = 0.088 49 | goal.pose.theta = 0.0 50 | client(goal) 51 | 52 | goal.leg = 0 53 | goal.pose.x = 0.0 54 | goal.pose.y = -0.16 55 | client(goal) 56 | 57 | goal.leg = 1 58 | goal.pose.x = 0.00 59 | goal.pose.y = 0.0 60 | goal.pose.theta = 0.0 61 | client(goal) 62 | 63 | 64 | 65 | if __name__ == '__main__': 66 | try: 67 | rospy.init_node('footstep_test_client') 68 | footstep_client() 69 | 70 | except rospy.ROSInterruptException: 71 | print "program interrupted before completion" 72 | 73 | -------------------------------------------------------------------------------- /nao_apps/scripts/test_joint_angles.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | import roslib 4 | #from rospy.exceptions import ROSException 5 | roslib.load_manifest('naoqi_driver') 6 | import rospy 7 | from rospy import Duration 8 | 9 | 10 | import actionlib 11 | from actionlib_msgs.msg import GoalStatus 12 | import naoqi_bridge_msgs.msg 13 | import trajectory_msgs.msg 14 | from trajectory_msgs.msg import JointTrajectoryPoint 15 | import std_srvs.srv 16 | 17 | # go to crouching position 18 | def joint_angle_client(): 19 | #inhibitWalkSrv = rospy.ServiceProxy("inhibit_walk", std_srvs.srv.Empty) 20 | #uninhibitWalkSrv = rospy.ServiceProxy("uninhibit_walk", std_srvs.srv.Empty) 21 | 22 | client = actionlib.SimpleActionClient("joint_trajectory", naoqi_bridge_msgs.msg.JointTrajectoryAction) 23 | stiffness_client = actionlib.SimpleActionClient("joint_stiffness_trajectory", naoqi_bridge_msgs.msg.JointTrajectoryAction) 24 | angle_client = actionlib.SimpleActionClient("joint_angles_action", naoqi_bridge_msgs.msg.JointAnglesWithSpeedAction) 25 | 26 | rospy.loginfo("Waiting for joint_trajectory and joint_stiffness servers...") 27 | client.wait_for_server() 28 | stiffness_client.wait_for_server() 29 | angle_client.wait_for_server() 30 | rospy.loginfo("Done.") 31 | 32 | #inhibitWalkSrv() 33 | try: 34 | goal = naoqi_bridge_msgs.msg.JointTrajectoryGoal() 35 | 36 | # move head: single joint, multiple keypoints 37 | goal.trajectory.joint_names = ["HeadYaw"] 38 | goal.trajectory.points.append(JointTrajectoryPoint(time_from_start = Duration(1.0), positions = [1.0])) 39 | goal.trajectory.points.append(JointTrajectoryPoint(time_from_start = Duration(2.0), positions = [-1.0])) 40 | goal.trajectory.points.append(JointTrajectoryPoint(time_from_start = Duration(2.5), positions = [0.0])) 41 | 42 | 43 | rospy.loginfo("Sending goal...") 44 | client.send_goal(goal) 45 | client.wait_for_result() 46 | result = client.get_result() 47 | rospy.loginfo("Results: %s", str(result.goal_position.position)) 48 | 49 | # Test for preemption 50 | rospy.loginfo("Sending goal again...") 51 | client.send_goal(goal) 52 | rospy.sleep(0.5) 53 | rospy.loginfo("Preempting goal...") 54 | client.cancel_goal() 55 | client.wait_for_result() 56 | if client.get_state() != GoalStatus.PREEMPTED or client.get_result() == result: 57 | rospy.logwarn("Preemption does not seem to be working") 58 | else: 59 | rospy.loginfo("Preemption seems okay") 60 | 61 | # crouching pose: single keypoint, multiple joints: 62 | goal.trajectory.joint_names = ["Body"] 63 | point = JointTrajectoryPoint() 64 | point.time_from_start = Duration(1.5) 65 | point.positions = [0.0,0.0, # head 66 | 1.545, 0.33, -1.57, -0.486, 0.0, 0.0, # left arm 67 | -0.3, 0.057, -0.744, 2.192, -1.122, -0.035, # left leg 68 | -0.3, 0.057, -0.744, 2.192, -1.122, -0.035, # right leg 69 | 1.545, -0.33, 1.57, 0.486, 0.0, 0.0] # right arm 70 | goal.trajectory.points = [point] 71 | 72 | rospy.loginfo("Sending goal...") 73 | client.send_goal(goal) 74 | client.wait_for_result() 75 | rospy.loginfo("Getting results...") 76 | result = client.get_result() 77 | print "Result:", ', '.join([str(n) for n in result.goal_position.position]) 78 | 79 | 80 | # multiple joints, multiple keypoints: 81 | goal.trajectory.joint_names = ["HeadYaw", "HeadPitch"] 82 | goal.trajectory.points = [] 83 | goal.trajectory.points.append(JointTrajectoryPoint(time_from_start = Duration(0.5), 84 | positions = [1.0, 1.0])) 85 | goal.trajectory.points.append(JointTrajectoryPoint(time_from_start = Duration(1.0), 86 | positions = [1.0, 0.0])) 87 | goal.trajectory.points.append(JointTrajectoryPoint(time_from_start = Duration(1.5), 88 | positions = [0.0, 0.0])) 89 | 90 | rospy.loginfo("Sending goal...") 91 | client.send_goal(goal) 92 | client.wait_for_result() 93 | rospy.loginfo("Getting results...") 94 | result = client.get_result() 95 | print "Result:", ', '.join([str(n) for n in result.goal_position.position]) 96 | 97 | 98 | # multiple joints, single keypoint: 99 | goal.trajectory.joint_names = ["HeadYaw", "HeadPitch"] 100 | goal.trajectory.points = [] 101 | goal.trajectory.points.append(JointTrajectoryPoint(time_from_start = Duration(0.5), 102 | positions = [0.5, 0.5])) 103 | 104 | rospy.loginfo("Sending goal...") 105 | client.send_goal(goal) 106 | client.wait_for_result() 107 | rospy.loginfo("Getting results...") 108 | result = client.get_result() 109 | print "Result:", ', '.join([str(n) for n in result.goal_position.position]) 110 | 111 | 112 | # Control of joints with relative speed 113 | angle_goal = naoqi_bridge_msgs.msg.JointAnglesWithSpeedGoal() 114 | angle_goal.joint_angles.relative = False 115 | angle_goal.joint_angles.joint_names = ["HeadYaw", "HeadPitch"] 116 | angle_goal.joint_angles.joint_angles = [1.0, 0.0] 117 | angle_goal.joint_angles.speed = 0.2 118 | rospy.loginfo("Sending joint angles goal...") 119 | angle_client.send_goal_and_wait(angle_goal) 120 | result = angle_client.get_result() 121 | rospy.loginfo("Angle results: %s", str(result.goal_position.position)) 122 | 123 | # Test for preemption 124 | angle_goal.joint_angles.joint_angles = [-1.0, 0.0] 125 | angle_goal.joint_angles.speed = 0.05 126 | rospy.loginfo("Sending goal again...") 127 | angle_client.send_goal(angle_goal) 128 | rospy.sleep(0.5) 129 | rospy.loginfo("Preempting goal...") 130 | angle_client.cancel_goal() 131 | angle_client.wait_for_result() 132 | if angle_client.get_state() != GoalStatus.PREEMPTED or angle_client.get_result() == result: 133 | rospy.logwarn("Preemption does not seem to be working") 134 | else: 135 | rospy.loginfo("Preemption seems okay") 136 | 137 | # Test stiffness actionlib 138 | stiffness_goal = naoqi_bridge_msgs.msg.JointTrajectoryGoal() 139 | stiffness_goal.trajectory.joint_names = ["Body"] 140 | stiffness_goal.trajectory.points.append(JointTrajectoryPoint(time_from_start = Duration(0.5), positions = [1.0])) 141 | rospy.loginfo("Sending stiffness goal...") 142 | stiffness_client.send_goal(stiffness_goal) 143 | stiffness_client.wait_for_result() 144 | result = stiffness_client.get_result() 145 | rospy.loginfo("Stiffness results: %s", str(result.goal_position.position)) 146 | 147 | # Test for preemption 148 | stiffness_goal.trajectory.points = [JointTrajectoryPoint(time_from_start = Duration(0.5), positions = [0.0])] 149 | rospy.loginfo("Sending goal again...") 150 | stiffness_client.send_goal(stiffness_goal) 151 | rospy.sleep(0.25) 152 | rospy.loginfo("Preempting goal...") 153 | stiffness_client.cancel_goal() 154 | stiffness_client.wait_for_result() 155 | if stiffness_client.get_state() != GoalStatus.PREEMPTED or stiffness_client.get_result() == result: 156 | rospy.logwarn("Preemption does not seem to be working") 157 | else: 158 | rospy.loginfo("Preemption seems okay") 159 | 160 | finally: 161 | pass #uninhibitWalkSrv() 162 | 163 | 164 | 165 | if __name__ == '__main__': 166 | try: 167 | rospy.init_node('joint_angle_client') 168 | joint_angle_client() 169 | 170 | except rospy.ROSInterruptException: 171 | print "program interrupted before completion" 172 | 173 | -------------------------------------------------------------------------------- /nao_apps/setup.py: -------------------------------------------------------------------------------- 1 | ## ! DO NOT MANUALLY INVOKE THIS setup.py, USE CATKIN INSTEAD 2 | 3 | from distutils.core import setup 4 | from catkin_pkg.python_setup import generate_distutils_setup 5 | 6 | # fetch values from package.xml 7 | setup_args = generate_distutils_setup( 8 | packages=['nao_apps'], 9 | package_dir={'': 'src'}) 10 | 11 | setup(**setup_args) 12 | 13 | -------------------------------------------------------------------------------- /nao_apps/src/nao_apps/__init__.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2013, Miguel Sarabia 2 | # Imperial College London 3 | # 4 | # Redistribution and use in source and binary forms, with or without 5 | # modification, are permitted provided that the following conditions are met: 6 | # 7 | # # Redistributions of source code must retain the above copyright 8 | # notice, this list of conditions and the following disclaimer. 9 | # # Redistributions in binary form must reproduce the above copyright 10 | # notice, this list of conditions and the following disclaimer in the 11 | # documentation and/or other materials provided with the distribution. 12 | # # Neither the name of the Imperial College London nor the names of its 13 | # contributors may be used to endorse or promote products derived from 14 | # this software without specific prior written permission. 15 | # 16 | # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 17 | # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 18 | # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 19 | # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 20 | # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 21 | # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 22 | # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 23 | # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 24 | # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 25 | # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 26 | # POSSIBILITY OF SUCH DAMAGE. 27 | # 28 | 29 | from nao_footstep_clipping import * 30 | from start_walk_pose import * 31 | 32 | #Do not allow nao_footstep_clipping.Params to be exposed 33 | del Params 34 | 35 | -------------------------------------------------------------------------------- /nao_apps/src/nao_apps/nao_footstep_clipping.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | import almath 4 | 5 | 6 | # Struct with clipping params initialized with clipping values for the NAO robot 7 | class Params(object): 8 | # Various parameters describing step characteristics. 9 | min_step_x = -0.04 10 | min_step_y = 0.088 11 | max_step_x = 0.08 12 | max_step_y = 0.16 13 | max_step_theta = 0.5 # 0.5xxx 14 | min_step_theta = -max_step_theta 15 | 16 | # Bounding boxes of NAO's feet. 17 | foot_box_r_fl = almath.Pose2D(0.11, 0.038, 0.0) 18 | foot_box_r_fr = almath.Pose2D(0.11, -0.050, 0.0) 19 | foot_box_r_rr = almath.Pose2D(-0.047, -0.050, 0.0) 20 | foot_box_r_rl = almath.Pose2D(-0.047, 0.038, 0.0) 21 | foot_box_r = almath.vectorPose2D([foot_box_r_fl, foot_box_r_fr, 22 | foot_box_r_rr, foot_box_r_rl]) 23 | 24 | foot_box_l_fl = almath.Pose2D(0.11, 0.050, 0.0) 25 | foot_box_l_fr = almath.Pose2D(0.11, -0.038, 0.0) 26 | foot_box_l_rr = almath.Pose2D(-0.047, -0.038, 0.0) 27 | foot_box_l_rl = almath.Pose2D(-0.047, 0.050, 0.0) 28 | foot_box_l = almath.vectorPose2D([foot_box_l_fl, foot_box_l_fr, 29 | foot_box_l_rr, foot_box_l_rl]) 30 | 31 | 32 | def clip_data(min, max, value): 33 | ''' Clip value between two extremes. ''' 34 | clipped = value 35 | 36 | if (clipped < min): 37 | clipped = min 38 | if (clipped > max): 39 | clipped = max 40 | 41 | return clipped 42 | 43 | 44 | def clip_footstep_on_gait_config(foot, is_left_support): 45 | ''' Clip the foot move so that it does not exceed the maximum 46 | size of steps. 47 | foot is an almath.Pose2D (x, y, theta position). 48 | is_left_support must be set to True if the move is on the right leg 49 | (the robot is supporting itself on the left leg). 50 | ''' 51 | 52 | # Clip X. 53 | clipped_x = clip_data(Params.min_step_x, Params.max_step_x, foot.x) 54 | foot.x = clipped_x 55 | 56 | # Clip Y. 57 | if not is_left_support: 58 | clipped_y = clip_data(Params.min_step_y, Params.max_step_y, foot.y) 59 | else: 60 | clipped_y = clip_data(-Params.max_step_y, -Params.min_step_y, foot.y) 61 | foot.y = clipped_y 62 | 63 | # Clip Theta. 64 | clipped_theta = clip_data(Params.min_step_theta, Params.max_step_theta, foot.theta) 65 | foot.theta = clipped_theta 66 | 67 | 68 | def clip_footstep_with_ellipse(foot): 69 | ''' Clip the foot move inside an ellipse defined by the foot's dimansions. 70 | foot is an almath.Pose2D (x, y, theta position). 71 | ''' 72 | 73 | # Apply an offset to have Y component of foot move centered on 0. 74 | if (foot.y < -Params.min_step_y): 75 | foot.y = foot.y + Params.min_step_y 76 | elif (foot.y > Params.min_step_y): 77 | foot.y = foot.y - Params.min_step_y 78 | else: 79 | return 80 | 81 | # Clip the foot move to an ellipse using ALMath method. 82 | if foot.x >= 0: 83 | almath.clipFootWithEllipse(Params.max_step_x, Params.max_step_y - Params.min_step_y, foot) 84 | else: 85 | almath.clipFootWithEllipse(Params.min_step_x, Params.max_step_y - Params.min_step_y, foot) 86 | 87 | # Correct the previous offset on Y component. 88 | if foot.y >=0: 89 | foot.y = foot.y + Params.min_step_y 90 | else: 91 | foot.y = foot.y - Params.min_step_y 92 | 93 | 94 | def clip_footstep_to_avoid_collision(foot, is_left_support): 95 | ''' Clip the foot move to avoid collision with the other foot. 96 | foot is an almath.Pose2D (x, y, theta position). 97 | is_left_support must be set to True if the move is on the right leg 98 | (the robot is supporting itself on the left leg). 99 | ''' 100 | 101 | # Use ALMath method. 102 | almath.avoidFootCollision(Params.foot_box_l, Params.foot_box_r, is_left_support, foot) 103 | 104 | 105 | def clip_footstep(foot, is_left_support): 106 | ''' Clipping functions to avoid any warnings and undesired effects 107 | when sending the footsteps to ALMotion. 108 | foot is an almath.Pose2D (x, y, theta position) 109 | is_left_support must be set to True if the move is on the right leg 110 | (the robot is supporting itself on the left leg). 111 | ''' 112 | 113 | # First clip the foot move with gait config. 114 | clip_footstep_on_gait_config(foot, is_left_support) 115 | # Then clip it on an ellipse. 116 | clip_footstep_with_ellipse(foot) 117 | # Then make sure you do not have any collision. 118 | clip_footstep_to_avoid_collision(foot, is_left_support) 119 | 120 | 121 | def clip_footstep_tuple(foot, is_left_support): 122 | """ 123 | Wrapper of clip_footstep to handle 'foot' as geometry_msgs.Pose2D. 124 | 'foot' is a tuple (x, y, theta). A tuple (x_clip, y_clip, theta_clip) is 125 | returned. 126 | """ 127 | 128 | foot = almath.Pose2D(*foot) 129 | clip_footstep(foot, is_left_support) 130 | return foot.x, foot.y, foot.theta 131 | -------------------------------------------------------------------------------- /nao_apps/src/nao_apps/start_walk_pose.py: -------------------------------------------------------------------------------- 1 | import rospy 2 | 3 | def startWalkPose(motionProxy): 4 | numJoints = len(motionProxy.getJointNames('Body')) 5 | 6 | allAngles = [ 7 | 0.0076280385255813599, # HeadPitch 8 | 0.019900038838386536, # HeadYaw 9 | 1.8085440397262573, # LAnklePitch 10 | 0.21165004372596741, # LAnkleRoll 11 | -1.4680800437927246, # LElbowRoll 12 | -0.52918803691864014, # LElbowYaw 13 | 0.0091620385646820068, # LHand 14 | 0.0011173889506608248, # LHipPitch 15 | 0.001575961709022522, # LHipRoll 16 | 0.024585962295532227, # LHipYawPitch 17 | -0.37885606288909912, # LKneePitch 18 | 0.93723207712173462, # LShoulderPitch 19 | -0.56301999092102051, # LShoulderRoll 20 | -0.019900038838386536, # LWristYaw 21 | 0.001575961709022522, # RAnklePitch 22 | 0.024585962295532227, # RAnkleRoll 23 | -0.37893998622894287, # RElbowRoll 24 | 0.9419180154800415, # RElbowYaw 25 | -0.55986803770065308, # RHand 26 | -0.024502038955688477, # RHipPitch 27 | 1.8224339485168457, # RHipRoll 28 | -0.22247196733951569, # RHipYawPitch 29 | 1.4756660461425781, # RKneePitch 30 | 0.52160197496414185, # RShoulderPitch 31 | 0.001492038369178772, # RShoulderRoll 32 | 0.025117311626672745] # RWristYaw 33 | 34 | if (numJoints == 26): 35 | angles = allAngles 36 | elif (numJoints == 22): # no hands (e.g. simulator) 37 | angles = allAngles[0:6] + allAngles[8:24] 38 | else: 39 | rospy.logerr("Unkown number of joints: %d", numJoints) 40 | return 41 | 42 | try: 43 | motionProxy.angleInterpolation('Body', angles, 1.5, True); 44 | 45 | except RuntimeError,e: 46 | print "An error has been caught" 47 | print e 48 | -------------------------------------------------------------------------------- /nao_bringup/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package nao_bringup 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.5.15 (2016-11-23) 6 | ------------------- 7 | 8 | 0.5.14 (2016-01-23) 9 | ------------------- 10 | 11 | 0.5.13 (2016-01-16) 12 | ------------------- 13 | 14 | 0.5.12 (2016-01-01) 15 | ------------------- 16 | * launch/nao_full.launch : support nao_port in launch/naoqi_driver.launch https://github.com/ros-naoqi/naoqi_driver/pull/52 17 | * Contributors: Kei Okada 18 | 19 | 0.5.11 (2015-08-11) 20 | ------------------- 21 | * introduce namespace for nao_bringup 22 | * Contributors: Karsten Knese 23 | 24 | 0.5.10 (2015-07-31) 25 | ------------------- 26 | 27 | 0.5.9 (2015-07-30) 28 | ------------------ 29 | * fix correct package dep 30 | * Contributors: Karsten Knese 31 | 32 | 0.5.8 (2015-07-30) 33 | ------------------ 34 | * rename naoqi_driver 35 | * transfer to naoqi_py 36 | * use naoqi_pose instead of nao_pose 37 | * Contributors: Karsten Knese, Kei Okada 38 | 39 | 0.5.7 (2015-03-27) 40 | ------------------ 41 | * remove legacy sonar node 42 | * set nao walker by default 43 | * Contributors: Karsten Knese 44 | 45 | 0.5.6 (2015-02-27) 46 | ------------------ 47 | * Cleanup and rename launch files 48 | * Contributors: Karsten Knese 49 | 50 | 0.5.5 (2015-02-17) 51 | ------------------ 52 | 53 | 0.5.4 (2015-02-17) 54 | ------------------ 55 | * configure sonars via namespace and params 56 | * Contributors: Karsten Knese 57 | 58 | 0.5.3 (2014-12-14) 59 | ------------------ 60 | * add bottom camera to nao_full.launch 61 | * Contributors: Kanae Kochigami 62 | 63 | 0.5.2 (2014-12-04) 64 | ------------------ 65 | * remove trailing spaces 66 | * Added naoqi_sensors dependency 67 | * deleted extra space 68 | * added nao_ip and nao_port as args to work 69 | * Add microphone launcher in nao_full 70 | * Contributors: Arguedas Mikael, Mikael ARGUEDAS, kochigami, sambrose 71 | 72 | 0.5.1 (2014-11-13) 73 | ------------------ 74 | * bugfix: fixing python imports for nao_robot 75 | * bugfix: python imports 76 | * Contributors: Karsten Knese 77 | 78 | 0.5.0 (2014-11-06) 79 | ------------------ 80 | * update on rviz config 81 | * moved pose manager into nao_robot 82 | * transfer nao_robot 83 | * 0.4.1 84 | * update changelogs 85 | * get the accent right in Séverin's name 86 | * 0.4.0 87 | * update changelogs 88 | * update nao_bringup launchfiles to use new urdf 89 | * 0.3.0 90 | * update changelogs 91 | * update maintainers 92 | Armin, thank you for all your work, in ROS, Octomap and NAO. 93 | Good luck out of the university ! 94 | * "0.2.3" 95 | * Changelogs 96 | * {ahornung->ros-nao} 97 | * {ahornung->ros-nao} 98 | * Add missing nao_sim.launch to nao_bringup install 99 | * "0.2.2" 100 | * changelog 101 | * Replace accented character in package.xml files, seems to cause 102 | problems with bloom 103 | * "0.2.1" 104 | * Changelogs 105 | * "0.2.0" 106 | * Adjust version number mismatch 107 | * Adding (edited) catkin-generated changelogs 108 | * Adding bugtracker and repo URLs to package manifests 109 | * nao_bringup: include nao_description launch files 110 | * Adding force_python parameter to nao_driver.launch to switch 111 | between C++ and python nodes for nao_sensors (Issue `#11 `_) 112 | Parameter will be passed on from higher-level launch files (nao_bringup). 113 | Default node is C++, unless a simulation launch file is started. 114 | * Add nao_sim launch file to bringup simulated nao 115 | * [nao_bringup] Include pose_manager in nao.launch 116 | * Include nao_driver/launch/nao_driver.launch instead of copying its content 117 | * XML comments do not work well in launch files... 118 | * Added nao_bringup: provide general launch file for ROS on Nao 119 | * Contributors: Armin Hornung, Karsten Knese, Séverin Lemaignan, Vincent Rabaud, margueda 120 | -------------------------------------------------------------------------------- /nao_bringup/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(nao_bringup) 3 | find_package(catkin REQUIRED) 4 | 5 | catkin_package() 6 | 7 | # install 8 | 9 | install(DIRECTORY config 10 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) 11 | 12 | install(DIRECTORY launch 13 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) 14 | -------------------------------------------------------------------------------- /nao_bringup/config/nao_analysers.yaml: -------------------------------------------------------------------------------- 1 | # nao_dashboard/NaoJointsAnalyzer extends diagnostic_aggregator/AnalyzerGroup 2 | # by providing overall stiffness value and a list of hot joints for nao_dashboard. 3 | # 4 | 5 | analyzers: 6 | nao: 7 | type: diagnostic_aggregator/AnalyzerGroup 8 | path: Nao 9 | analyzers: 10 | CPU: 11 | type: diagnostic_aggregator/GenericAnalyzer 12 | path: CPU 13 | find_and_remove_prefix: nao_cpu 14 | Power: 15 | type: diagnostic_aggregator/GenericAnalyzer 16 | path: Battery 17 | find_and_remove_prefix: nao_power 18 | # Joints: 19 | # type: nao_dashboard/NaoJointsAnalyzer 20 | # path: Joints 21 | # find_and_remove_prefix: nao_joint 22 | Laser: 23 | type: diagnostic_aggregator/GenericAnalyzer 24 | path: Laser 25 | find_and_remove_prefix: hokuyo 26 | Camera: 27 | type: diagnostic_aggregator/GenericAnalyzer 28 | path: Camera 29 | find_and_remove_prefix: nao_camera 30 | WLAN: 31 | type: diagnostic_aggregator/GenericAnalyzer 32 | path: WLAN 33 | find_and_remove_prefix: nao_wlan 34 | Ethernet: 35 | type: diagnostic_aggregator/GenericAnalyzer 36 | path: Ethernet 37 | find_and_remove_prefix: nao_ethernet 38 | Relays: 39 | type: diagnostic_aggregator/GenericAnalyzer 40 | path: Relays 41 | find_and_remove_prefix: relay_ 42 | 43 | -------------------------------------------------------------------------------- /nao_bringup/launch/nao_full.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | -------------------------------------------------------------------------------- /nao_bringup/launch/nao_full_py.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | -------------------------------------------------------------------------------- /nao_bringup/package.xml: -------------------------------------------------------------------------------- 1 | 2 | nao_bringup 3 | 0.5.15 4 | 5 | 6 | Launch files and scripts needed to bring ROS interfaces for Nao up into a 7 | running state. 8 | 9 | 10 | Séverin Lemaignan 11 | Séverin Lemaignan 12 | BSD 13 | 14 | http://www.ros.org/wiki/nao_robot 15 | https://github.com/ros-nao/nao_robot/issues 16 | https://github.com/ros-nao/nao_robot 17 | 18 | catkin 19 | 20 | nao_description 21 | naoqi_driver 22 | naoqi_driver_py 23 | naoqi_sensors_py 24 | naoqi_pose 25 | robot_state_publisher 26 | diagnostic_aggregator 27 | 28 | 29 | -------------------------------------------------------------------------------- /nao_description/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package nao_description 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.5.15 (2016-11-23) 6 | ------------------- 7 | 8 | 0.5.14 (2016-01-23) 9 | ------------------- 10 | * removed nao_dcm namespace to match changes made to nao_control 11 | * added gui:=true to match pepper_description display.launch 12 | * Contributors: Mikael Arguedas 13 | 14 | 0.5.13 (2016-01-16) 15 | ------------------- 16 | * Fix bad arm values. 17 | This fixes `#25 `_. 18 | * Contributors: Vincent Rabaud 19 | 20 | 0.5.12 (2016-01-01) 21 | ------------------- 22 | * remove type from naoTransmission 23 | * update the Gazebo .xacro and the corresponding .urdf 24 | * update the .xacro / .urdf to the latest version of naoqi_tools 25 | * Contributors: Mikael Arguedas, Vincent Rabaud 26 | 27 | 0.5.11 (2015-08-11) 28 | ------------------- 29 | 30 | 0.5.10 (2015-07-31) 31 | ------------------- 32 | 33 | 0.5.9 (2015-07-30) 34 | ------------------ 35 | 36 | 0.5.8 (2015-07-30) 37 | ------------------ 38 | 39 | 0.5.7 (2015-03-27) 40 | ------------------ 41 | * update full .urdf file using xacro 42 | * fixed ankle drift 43 | * Contributors: Mikael Arguedas, Vincent Rabaud 44 | 45 | 0.5.6 (2015-02-27) 46 | ------------------ 47 | * properly fix 535d34474d9f64ddb60f6f163656c10fcdf92774 48 | The automatic generator was used to generate inertia 49 | * dirty fix for naoqi_bridge/issues/31 50 | * Minor fix to load RViz config file in display.launch 51 | * fixing typo 52 | * Cleanup and rename launch files 53 | * Contributors: Karsten Knese, Konstantinos Chatzilygeroudis, Mikael Arguedas, Vincent Rabaud 54 | 55 | 0.5.5 (2015-02-17) 56 | ------------------ 57 | * update to the latest version of the generation script 58 | * Contributors: Vincent Rabaud 59 | 60 | 0.5.4 (2015-02-17) 61 | ------------------ 62 | * restore sensor in naoGazebo.xacro 63 | * Contributors: Mikael Arguedas 64 | 65 | 0.5.3 (2014-12-14) 66 | ------------------ 67 | 68 | 0.5.2 (2014-12-04) 69 | ------------------ 70 | * fixed gazebo tags used by nao_gazebo_plugin 71 | * remove trailing spaces 72 | * update generated urdf files, add gazebo plugins 73 | * Added xacro and urdf dependencies 74 | * Contributors: Arguedas Mikael, Mikael ARGUEDAS 75 | 76 | 0.5.1 (2014-11-13) 77 | ------------------ 78 | 79 | 0.5.0 (2014-11-06) 80 | ------------------ 81 | * transfer nao_robot 82 | * 0.4.1 83 | * update changelogs 84 | * added camera and sonar to naoGazebo.xacro 85 | * get the accent right in Séverin's name 86 | * 0.4.0 87 | * update changelogs 88 | * urdf generated files, launchfiles and config files 89 | generated files updated 90 | updated mesh file path 91 | add xacro macro for fingers in naohands 92 | update nao.urdf based on new macros for fingers 93 | export with meshes 94 | remove useless imu frame 95 | * 0.3.0 96 | * update changelogs 97 | * update maintainers 98 | Armin, thank you for all your work, in ROS, Octomap and NAO. 99 | Good luck out of the university ! 100 | * Revert "Merge pull request `#26 `_ from vrabaud/fix_xacro" 101 | Breaks groovy (xacro no catkin package), but will be required from hydro on 102 | This reverts commit 321424a634a309ea9c284cf027074cdeda2a3c67, reversing 103 | changes made to 383d285e01997e585bfa731525ce5f17a6cc3165. 104 | * fix the missing dependency on xacro 105 | * "0.2.3" 106 | * Changelogs 107 | * {ahornung->ros-nao} 108 | * {ahornung->ros-nao} 109 | * Fix `#17 `_: add dependency on sensor_msgs in nao_description 110 | * "0.2.2" 111 | * changelog 112 | * "0.2.1" 113 | * Changelogs 114 | * [nao_description] Added missing include dirs in CMakeLists 115 | * "0.2.0" 116 | * Adding (edited) catkin-generated changelogs 117 | * Adding bugtracker and repo URLs to package manifests 118 | * Adding base_footprint node to nao_description, publishes footprint according 119 | to REP-120 (based on previous node nao_remote/remap_odometry). Fixes Issue `#10 `_. 120 | * Moved nao_description from nao_common to nao_robot 121 | * Contributors: Armin Hornung, Karsten Knese, Séverin Lemaignan, Vincent Rabaud, margueda 122 | -------------------------------------------------------------------------------- /nao_description/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(nao_description) 3 | 4 | # We need to find catkin for the rest of the script to work 5 | find_package(catkin REQUIRED COMPONENTS 6 | roscpp 7 | tf 8 | message_filters 9 | sensor_msgs 10 | ) 11 | 12 | # Nothing that can be imported by other modules 13 | catkin_package() 14 | 15 | include_directories(${catkin_INCLUDE_DIRS}) 16 | add_executable(base_footprint src/base_footprint.cpp) 17 | target_link_libraries(base_footprint ${catkin_LIBRARIES}) 18 | 19 | install(TARGETS base_footprint 20 | RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} ) 21 | 22 | # Instructions to install launch files 23 | install(DIRECTORY launch/ 24 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch ) 25 | 26 | # Instructions to install urdf files 27 | install(DIRECTORY urdf/ 28 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/urdf) 29 | 30 | -------------------------------------------------------------------------------- /nao_description/launch/display.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | -------------------------------------------------------------------------------- /nao_description/launch/robot_state_publisher.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | -------------------------------------------------------------------------------- /nao_description/launch/upload_nao.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | -------------------------------------------------------------------------------- /nao_description/package.xml: -------------------------------------------------------------------------------- 1 | 2 | nao_description 3 | 0.5.15 4 | 5 | 6 | Description of the Nao robot model that can be used with robot_state_publisher to display the robot's state of joint angles. 7 | 8 | 9 | Armin Hornung 10 | Stefan Osswald 11 | Séverin Lemaignan 12 | Vincent Rabaud 13 | BSD 14 | 15 | http://www.ros.org/wiki/nao_description 16 | https://github.com/ros-nao/nao_robot/issues 17 | https://github.com/ros-nao/nao_robot 18 | 19 | catkin 20 | 21 | roscpp 22 | tf 23 | message_filters 24 | sensor_msgs 25 | urdf 26 | xacro 27 | 28 | roscpp 29 | robot_state_publisher 30 | tf 31 | message_filters 32 | sensor_msgs 33 | urdf 34 | xacro 35 | 36 | 37 | -------------------------------------------------------------------------------- /nao_description/scripts/test_cam_transform.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | import sys 3 | import roslib 4 | roslib.load_manifest('nao_description') 5 | import rospy 6 | import tf 7 | import numpy as np 8 | from tf import TransformListener 9 | from tf import transformations 10 | 11 | try: 12 | import motion 13 | from naoqi import ALProxy 14 | except ImportError: 15 | print("Error importing NaoQI. Please make sure that Aldebaran's NaoQI API is in your PYTHONPATH.") 16 | exit(1) 17 | 18 | 19 | # bla 20 | def space_to_str(space): 21 | if space == motion.SPACE_TORSO: 22 | return "Torso" 23 | elif space == motion.SPACE_WORLD: 24 | return "Odom" 25 | elif space == motion.SPACE_NAO: 26 | return "BaseFootprint" 27 | 28 | def transform_to_str(result): 29 | tstr = '' 30 | maxColumnWidth = 20 31 | for i in range(0,4): 32 | row = result[4*i:4*i+4] 33 | rstr = ''.join(["%s" %str(k).center(maxColumnWidth) for k in (row)] ) 34 | rstr = rstr + '\n' 35 | tstr = tstr+rstr 36 | #tstr.append('\n') 37 | return tstr 38 | 39 | def np_mat_to_str(m): 40 | mm = list() 41 | for i in range(0,4): 42 | for j in range(0,4): 43 | mm.append(m[i,j]) 44 | 45 | return transform_to_str(mm) 46 | 47 | def cam_rotation_matrix(): 48 | return np.matrix('0 0 1 0;-1 0 0 0; 0 -1 0 0; 0 0 0 1') 49 | 50 | if __name__ == '__main__': 51 | rospy.init_node('test_tf') 52 | listener = TransformListener() 53 | ip = "ra.local" 54 | port = 9559 55 | proxy = ALProxy("ALMotion", ip, port) 56 | print "motionproxy ready" 57 | space = motion.SPACE_TORSO 58 | chainName = "Head" 59 | currentSensor = proxy.getPosition(chainName, space, True) 60 | current = proxy.getPosition(chainName, space, False) 61 | print "Position of %s in space %s:"%(chainName, space_to_str(space)) 62 | print currentSensor 63 | print current 64 | rpy = currentSensor[3:] 65 | print rpy 66 | DCM = apply(transformations.euler_matrix,rpy) 67 | print DCM 68 | tTHSensor = proxy.getTransform(chainName, space, True) 69 | tTH = proxy.getTransform(chainName, space, False) 70 | print "Transform %s to %s:"%(space_to_str(space),chainName) 71 | print transform_to_str(tTHSensor) 72 | #print transform_to_str(tTH) 73 | chainName = "CameraTop" 74 | tTCSensor = proxy.getTransform(chainName, space, True) 75 | tTC = proxy.getTransform(chainName, space, False) 76 | print "Transform %s to %s:"%(space_to_str(space),chainName) 77 | print transform_to_str(tTCSensor) 78 | print 79 | T = np.matrix([tTCSensor[0:4],tTCSensor[4:8],tTCSensor[8:12],tTCSensor[12:]]) 80 | #print cam_rotation_matrix() 81 | DCM = T*cam_rotation_matrix() 82 | print "Transform %s to %s (with rotated coordinate frame):"%(space_to_str(space),chainName) 83 | print np_mat_to_str(DCM) 84 | 85 | stamp = rospy.Time() 86 | frame1 = 'Torso_link' 87 | frame2 = 'CameraTop_frame' 88 | try: 89 | listener.waitForTransform(frame1,frame2,stamp,rospy.Duration(1.0)) 90 | (trans,rot) = listener.lookupTransform(frame1,frame2,stamp) 91 | except tf.Exception as e: 92 | print "ERROR using TF" 93 | print "%s"%(e) 94 | sys.exit(-1) 95 | 96 | m = transformations.quaternion_matrix(rot) 97 | for i in range(0,3): 98 | m[i,3] = trans[i] 99 | print "[tf] Transform %s to %s:"%(frame1,frame2) 100 | print np_mat_to_str(m) 101 | 102 | e = np.linalg.norm(DCM - m) 103 | print "Error is: ",e 104 | if e > 1e-5: 105 | print "ERROR: Something is wrong with your TF transformations. Transforms do not match!" 106 | else: 107 | print "Test ok. Done" 108 | 109 | 110 | -------------------------------------------------------------------------------- /nao_description/src/base_footprint.cpp: -------------------------------------------------------------------------------- 1 | 2 | /* 3 | * Publish the Nao humanoid's base_footprint frame according to REP-120 4 | * Based on nao_common/remap_odometry.cpp 5 | * 6 | * Copyright 2013 Armin Hornung, Stefan Osswald, University of Freiburg 7 | * http://www.ros.org/wiki/nao 8 | * 9 | * Redistribution and use in source and binary forms, with or without 10 | * modification, are permitted provided that the following conditions are met: 11 | * 12 | * * Redistributions of source code must retain the above copyright 13 | * notice, this list of conditions and the following disclaimer. 14 | * * Redistributions in binary form must reproduce the above copyright 15 | * notice, this list of conditions and the following disclaimer in the 16 | * documentation and/or other materials provided with the distribution. 17 | * * Neither the name of the University of Freiburg nor the names of its 18 | * contributors may be used to endorse or promote products derived from 19 | * this software without specific prior written permission. 20 | * 21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 22 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 23 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 24 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 25 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 26 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 27 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 28 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 29 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 30 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 31 | * POSSIBILITY OF SUCH DAMAGE. 32 | */ 33 | 34 | #include 35 | #include 36 | #include 37 | #include 38 | #include 39 | #include 40 | #include 41 | 42 | class BaseFootprint 43 | { 44 | public: 45 | BaseFootprint(); 46 | ~BaseFootprint(); 47 | 48 | 49 | private: 50 | void jsCallback(const sensor_msgs::JointState::ConstPtr & msg); 51 | 52 | ros::NodeHandle m_nh; 53 | ros::NodeHandle m_privateNh; 54 | 55 | // for base_footprint_frame: broadcasts frame between right and left foot, coinciding with the ground 56 | message_filters::Subscriber * m_jsSub; 57 | tf::MessageFilter * m_jsFilter; 58 | tf::TransformBroadcaster m_brBaseFootPrint; 59 | tf::TransformListener m_listener; 60 | 61 | std::string m_odomFrameId; 62 | std::string m_baseFrameId; 63 | std::string m_lfootFrameId; 64 | std::string m_rfootFrameId; 65 | std::string m_baseFootPrintID; 66 | 67 | }; 68 | 69 | BaseFootprint::BaseFootprint() 70 | : m_privateNh("~"), m_odomFrameId("odom"), m_baseFrameId("base_link"), 71 | m_lfootFrameId("l_sole"), m_rfootFrameId("r_sole"), 72 | m_baseFootPrintID("base_footprint") 73 | { 74 | // Read parameters 75 | m_privateNh.param("odom_frame_id", m_odomFrameId, m_odomFrameId); 76 | m_privateNh.param("base_frame_id", m_baseFrameId, m_baseFrameId); 77 | m_privateNh.param("base_footprint_frame_id", m_baseFootPrintID, m_baseFootPrintID); 78 | 79 | 80 | // Resolve TF frames using ~tf_prefix parameter 81 | 82 | m_odomFrameId = m_listener.resolve(m_odomFrameId); 83 | m_baseFrameId = m_listener.resolve(m_baseFrameId); 84 | m_baseFootPrintID = m_listener.resolve(m_baseFootPrintID); 85 | m_lfootFrameId = m_listener.resolve(m_lfootFrameId); 86 | m_rfootFrameId = m_listener.resolve(m_rfootFrameId); 87 | 88 | // subscribe to joint_states to provide a clock signal for synchronization 89 | // since the frames are computed based on the joint state, all should be available 90 | // with the same time stamps 91 | m_jsSub = new message_filters::Subscriber(m_nh, "joint_states", 50); 92 | m_jsFilter = new tf::MessageFilter(*m_jsSub, m_listener, m_rfootFrameId, 50); 93 | std::vector frames; 94 | frames.push_back(m_rfootFrameId); 95 | frames.push_back(m_odomFrameId); 96 | m_jsFilter->setTargetFrames(frames); 97 | m_jsFilter->registerCallback(boost::bind(&BaseFootprint::jsCallback, this, _1)); 98 | } 99 | 100 | BaseFootprint::~BaseFootprint(){ 101 | delete m_jsFilter; 102 | delete m_jsSub; 103 | } 104 | 105 | void BaseFootprint::jsCallback(const sensor_msgs::JointState::ConstPtr & ptr) 106 | { 107 | ros::Time time = ptr->header.stamp; 108 | tf::StampedTransform tf_odom_to_base, tf_odom_to_left_foot, tf_odom_to_right_foot; 109 | 110 | ROS_DEBUG("JointState callback function, computing frame %s", m_baseFootPrintID.c_str()); 111 | try { 112 | m_listener.lookupTransform(m_odomFrameId, m_lfootFrameId, time, tf_odom_to_left_foot); 113 | m_listener.lookupTransform(m_odomFrameId, m_rfootFrameId, time, tf_odom_to_right_foot); 114 | m_listener.lookupTransform(m_odomFrameId, m_baseFrameId, time, tf_odom_to_base); 115 | } catch (const tf::TransformException& ex){ 116 | ROS_ERROR("%s",ex.what()); 117 | return ; 118 | } 119 | 120 | tf::Vector3 new_origin = (tf_odom_to_right_foot.getOrigin() + tf_odom_to_left_foot.getOrigin())/2.0; // middle of both feet 121 | double height = std::min(tf_odom_to_left_foot.getOrigin().getZ(), tf_odom_to_right_foot.getOrigin().getZ()); // fix to lowest foot 122 | new_origin.setZ(height); 123 | 124 | // adjust yaw according to torso orientation, all other angles 0 (= in z-plane) 125 | double roll, pitch, yaw; 126 | tf_odom_to_base.getBasis().getRPY(roll, pitch, yaw); 127 | 128 | tf::Transform tf_odom_to_footprint(tf::createQuaternionFromYaw(yaw), new_origin); 129 | tf::Transform tf_base_to_footprint = tf_odom_to_base.inverse() * tf_odom_to_footprint; 130 | 131 | // publish transform with parent m_baseFrameId and new child m_baseFootPrintID 132 | // i.e. transform from m_baseFrameId to m_baseFootPrintID 133 | m_brBaseFootPrint.sendTransform(tf::StampedTransform(tf_base_to_footprint, time, m_baseFrameId, m_baseFootPrintID)); 134 | ROS_DEBUG("Published Transform %s --> %s", m_baseFrameId.c_str(), m_baseFootPrintID.c_str()); 135 | 136 | return; 137 | 138 | } 139 | 140 | int main(int argc, char** argv){ 141 | ros::init(argc, argv, "base_footprint"); 142 | BaseFootprint baseFootprint; 143 | ros::spin(); 144 | 145 | return 0; 146 | } 147 | 148 | 149 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV32_generated_urdf/naoTransmission.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | transmission_interface/SimpleTransmission 15 | 16 | PositionJointInterface 17 | 18 | 19 | 20 | PositionJointInterface 21 | ${speed_red_type3A} 22 | 23 | 24 | 25 | transmission_interface/SimpleTransmission 26 | 27 | PositionJointInterface 28 | 29 | 30 | 31 | PositionJointInterface 32 | ${speed_red_type3B} 33 | 34 | 35 | 36 | 37 | 38 | 39 | transmission_interface/SimpleTransmission 40 | 41 | PositionJointInterface 42 | 43 | 44 | PositionJointInterface 45 | ${speed_red_type3A} 46 | 47 | 48 | 49 | transmission_interface/SimpleTransmission 50 | 51 | PositionJointInterface 52 | 53 | 54 | PositionJointInterface 55 | ${speed_red_type3B} 56 | 57 | 58 | 59 | transmission_interface/SimpleTransmission 60 | 61 | PositionJointInterface 62 | 63 | 64 | PositionJointInterface 65 | ${speed_red_type3A} 66 | 67 | 68 | 69 | transmission_interface/SimpleTransmission 70 | 71 | PositionJointInterface 72 | 73 | 74 | PositionJointInterface 75 | ${speed_red_type3B} 76 | 77 | 78 | 79 | 80 | transmission_interface/SimpleTransmission 81 | 82 | PositionJointInterface 83 | 84 | 85 | PositionJointInterface 86 | ${speed_red_type2A} 87 | 88 | 89 | 90 | transmission_interface/SimpleTransmission 91 | 92 | PositionJointInterface 93 | 94 | 95 | PositionJointInterface 96 | ${speed_red_type2B} 97 | 98 | 99 | 100 | 101 | 102 | 103 | 104 | 105 | 106 | 107 | transmission_interface/SimpleTransmission 108 | 109 | PositionJointInterface 110 | 111 | 112 | 113 | PositionJointInterface 114 | ${speed_red_type1A} 115 | 116 | 117 | 118 | transmission_interface/SimpleTransmission 119 | 120 | PositionJointInterface 121 | 122 | 123 | 124 | PositionJointInterface 125 | ${speed_red_type1A} 126 | 127 | 128 | 129 | transmission_interface/SimpleTransmission 130 | 131 | PositionJointInterface 132 | 133 | 134 | 135 | PositionJointInterface 136 | ${speed_red_type1B} 137 | 138 | 139 | 140 | transmission_interface/SimpleTransmission 141 | 142 | PositionJointInterface 143 | 144 | 145 | 146 | PositionJointInterface 147 | ${speed_red_type1B} 148 | 149 | 150 | 151 | transmission_interface/SimpleTransmission 152 | 153 | PositionJointInterface 154 | 155 | 156 | 157 | PositionJointInterface 158 | ${speed_red_type1B} 159 | 160 | 161 | 162 | transmission_interface/SimpleTransmission 163 | 164 | PositionJointInterface 165 | 166 | 167 | 168 | PositionJointInterface 169 | ${speed_red_type1A} 170 | 171 | 172 | 173 | 174 | 175 | 176 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV32_generated_urdf/nao_arms.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | 72 | 73 | 74 | 75 | 76 | 77 | 78 | 79 | 80 | 81 | 82 | 83 | 84 | 85 | 86 | 87 | 88 | 89 | 90 | 91 | 92 | 93 | 94 | 95 | 96 | 97 | 98 | 99 | 100 | 101 | 102 | 103 | 104 | 105 | 106 | 107 | 108 | 109 | 110 | 111 | 112 | 113 | 114 | 115 | 116 | 117 | 118 | 119 | 120 | 121 | 122 | 123 | 124 | 125 | 126 | 127 | 128 | 129 | 130 | 131 | 132 | 133 | 134 | 135 | 136 | 137 | 138 | 139 | 140 | 141 | 142 | 143 | 144 | 145 | 146 | 147 | 148 | 149 | 150 | 151 | 152 | 153 | 154 | 155 | 156 | 157 | 158 | 159 | 160 | 161 | 162 | 163 | 164 | 165 | 166 | 167 | 168 | 169 | 170 | 171 | 172 | 173 | 174 | 175 | 176 | 177 | 178 | 179 | 180 | 181 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV32_generated_urdf/nao_fingers.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | 72 | 73 | 74 | 75 | 76 | 77 | 78 | 79 | 80 | 81 | 82 | 83 | 84 | 85 | 86 | 87 | 88 | 89 | 90 | 91 | 92 | 93 | 94 | 95 | 96 | 97 | 98 | 99 | 100 | 101 | 102 | 103 | 104 | 105 | 106 | 107 | 108 | 109 | 110 | 111 | 112 | 113 | 114 | 115 | 116 | 117 | 118 | 119 | 120 | 121 | 122 | 123 | 124 | 125 | 126 | 127 | 128 | 129 | 130 | 131 | 132 | 133 | 134 | 135 | 136 | 137 | 138 | 139 | 140 | 141 | 142 | 143 | 144 | 145 | 146 | 147 | 148 | 149 | 150 | 151 | 152 | 153 | 154 | 155 | 156 | 157 | 158 | 159 | 160 | 161 | 162 | 163 | 164 | 165 | 166 | 167 | 168 | 169 | 170 | 171 | 172 | 173 | 174 | 175 | 176 | 177 | 178 | 179 | 180 | 181 | 182 | 183 | 184 | 185 | 186 | 187 | 188 | 189 | 190 | 191 | 192 | 193 | 194 | 195 | 196 | 197 | 198 | 199 | 200 | 201 | 202 | 203 | 204 | 205 | 206 | 207 | 208 | 209 | 210 | 211 | 212 | 213 | 214 | 215 | 216 | 217 | 218 | 219 | 220 | 221 | 222 | 223 | 224 | 225 | 226 | 227 | 228 | 229 | 230 | 231 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV32_generated_urdf/nao_head.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV32_generated_urdf/nao_legs.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | 72 | 73 | 74 | 75 | 76 | 77 | 78 | 79 | 80 | 81 | 82 | 83 | 84 | 85 | 86 | 87 | 88 | 89 | 90 | 91 | 92 | 93 | 94 | 95 | 96 | 97 | 98 | 99 | 100 | 101 | 102 | 103 | 104 | 105 | 106 | 107 | 108 | 109 | 110 | 111 | 112 | 113 | 114 | 115 | 116 | 117 | 118 | 119 | 120 | 121 | 122 | 123 | 124 | 125 | 126 | 127 | 128 | 129 | 130 | 131 | 132 | 133 | 134 | 135 | 136 | 137 | 138 | 139 | 140 | 141 | 142 | 143 | 144 | 145 | 146 | 147 | 148 | 149 | 150 | 151 | 152 | 153 | 154 | 155 | 156 | 157 | 158 | 159 | 160 | 161 | 162 | 163 | 164 | 165 | 166 | 167 | 168 | 169 | 170 | 171 | 172 | 173 | 174 | 175 | 176 | 177 | 178 | 179 | 180 | 181 | 182 | 183 | 184 | 185 | 186 | 187 | 188 | 189 | 190 | 191 | 192 | 193 | 194 | 195 | 196 | 197 | 198 | 199 | 200 | 201 | 202 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV32_generated_urdf/nao_material.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV32_generated_urdf/nao_robot.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV32_generated_urdf/nao_torso.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV33_generated_urdf/naoTransmission.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | transmission_interface/SimpleTransmission 15 | 16 | PositionJointInterface 17 | 18 | 19 | 20 | PositionJointInterface 21 | ${speed_red_type3A} 22 | 23 | 24 | 25 | transmission_interface/SimpleTransmission 26 | 27 | PositionJointInterface 28 | 29 | 30 | 31 | PositionJointInterface 32 | ${speed_red_type3B} 33 | 34 | 35 | 36 | 37 | 38 | 39 | transmission_interface/SimpleTransmission 40 | 41 | PositionJointInterface 42 | 43 | 44 | PositionJointInterface 45 | ${speed_red_type3A} 46 | 47 | 48 | 49 | transmission_interface/SimpleTransmission 50 | 51 | PositionJointInterface 52 | 53 | 54 | PositionJointInterface 55 | ${speed_red_type3B} 56 | 57 | 58 | 59 | transmission_interface/SimpleTransmission 60 | 61 | PositionJointInterface 62 | 63 | 64 | PositionJointInterface 65 | ${speed_red_type3A} 66 | 67 | 68 | 69 | transmission_interface/SimpleTransmission 70 | 71 | PositionJointInterface 72 | 73 | 74 | PositionJointInterface 75 | ${speed_red_type3B} 76 | 77 | 78 | 79 | 80 | transmission_interface/SimpleTransmission 81 | 82 | PositionJointInterface 83 | 84 | 85 | PositionJointInterface 86 | ${speed_red_type2A} 87 | 88 | 89 | 90 | transmission_interface/SimpleTransmission 91 | 92 | PositionJointInterface 93 | 94 | 95 | PositionJointInterface 96 | ${speed_red_type2B} 97 | 98 | 99 | 100 | 101 | 102 | 103 | 104 | 105 | 106 | 107 | transmission_interface/SimpleTransmission 108 | 109 | PositionJointInterface 110 | 111 | 112 | 113 | PositionJointInterface 114 | ${speed_red_type1A} 115 | 116 | 117 | 118 | transmission_interface/SimpleTransmission 119 | 120 | PositionJointInterface 121 | 122 | 123 | 124 | PositionJointInterface 125 | ${speed_red_type1A} 126 | 127 | 128 | 129 | transmission_interface/SimpleTransmission 130 | 131 | PositionJointInterface 132 | 133 | 134 | 135 | PositionJointInterface 136 | ${speed_red_type1B} 137 | 138 | 139 | 140 | transmission_interface/SimpleTransmission 141 | 142 | PositionJointInterface 143 | 144 | 145 | 146 | PositionJointInterface 147 | ${speed_red_type1B} 148 | 149 | 150 | 151 | transmission_interface/SimpleTransmission 152 | 153 | PositionJointInterface 154 | 155 | 156 | 157 | PositionJointInterface 158 | ${speed_red_type1B} 159 | 160 | 161 | 162 | transmission_interface/SimpleTransmission 163 | 164 | PositionJointInterface 165 | 166 | 167 | 168 | PositionJointInterface 169 | ${speed_red_type1A} 170 | 171 | 172 | 173 | 174 | 175 | 176 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV33_generated_urdf/nao_arms.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | 72 | 73 | 74 | 75 | 76 | 77 | 78 | 79 | 80 | 81 | 82 | 83 | 84 | 85 | 86 | 87 | 88 | 89 | 90 | 91 | 92 | 93 | 94 | 95 | 96 | 97 | 98 | 99 | 100 | 101 | 102 | 103 | 104 | 105 | 106 | 107 | 108 | 109 | 110 | 111 | 112 | 113 | 114 | 115 | 116 | 117 | 118 | 119 | 120 | 121 | 122 | 123 | 124 | 125 | 126 | 127 | 128 | 129 | 130 | 131 | 132 | 133 | 134 | 135 | 136 | 137 | 138 | 139 | 140 | 141 | 142 | 143 | 144 | 145 | 146 | 147 | 148 | 149 | 150 | 151 | 152 | 153 | 154 | 155 | 156 | 157 | 158 | 159 | 160 | 161 | 162 | 163 | 164 | 165 | 166 | 167 | 168 | 169 | 170 | 171 | 172 | 173 | 174 | 175 | 176 | 177 | 178 | 179 | 180 | 181 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV33_generated_urdf/nao_fingers.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | 72 | 73 | 74 | 75 | 76 | 77 | 78 | 79 | 80 | 81 | 82 | 83 | 84 | 85 | 86 | 87 | 88 | 89 | 90 | 91 | 92 | 93 | 94 | 95 | 96 | 97 | 98 | 99 | 100 | 101 | 102 | 103 | 104 | 105 | 106 | 107 | 108 | 109 | 110 | 111 | 112 | 113 | 114 | 115 | 116 | 117 | 118 | 119 | 120 | 121 | 122 | 123 | 124 | 125 | 126 | 127 | 128 | 129 | 130 | 131 | 132 | 133 | 134 | 135 | 136 | 137 | 138 | 139 | 140 | 141 | 142 | 143 | 144 | 145 | 146 | 147 | 148 | 149 | 150 | 151 | 152 | 153 | 154 | 155 | 156 | 157 | 158 | 159 | 160 | 161 | 162 | 163 | 164 | 165 | 166 | 167 | 168 | 169 | 170 | 171 | 172 | 173 | 174 | 175 | 176 | 177 | 178 | 179 | 180 | 181 | 182 | 183 | 184 | 185 | 186 | 187 | 188 | 189 | 190 | 191 | 192 | 193 | 194 | 195 | 196 | 197 | 198 | 199 | 200 | 201 | 202 | 203 | 204 | 205 | 206 | 207 | 208 | 209 | 210 | 211 | 212 | 213 | 214 | 215 | 216 | 217 | 218 | 219 | 220 | 221 | 222 | 223 | 224 | 225 | 226 | 227 | 228 | 229 | 230 | 231 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV33_generated_urdf/nao_head.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV33_generated_urdf/nao_legs.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | 72 | 73 | 74 | 75 | 76 | 77 | 78 | 79 | 80 | 81 | 82 | 83 | 84 | 85 | 86 | 87 | 88 | 89 | 90 | 91 | 92 | 93 | 94 | 95 | 96 | 97 | 98 | 99 | 100 | 101 | 102 | 103 | 104 | 105 | 106 | 107 | 108 | 109 | 110 | 111 | 112 | 113 | 114 | 115 | 116 | 117 | 118 | 119 | 120 | 121 | 122 | 123 | 124 | 125 | 126 | 127 | 128 | 129 | 130 | 131 | 132 | 133 | 134 | 135 | 136 | 137 | 138 | 139 | 140 | 141 | 142 | 143 | 144 | 145 | 146 | 147 | 148 | 149 | 150 | 151 | 152 | 153 | 154 | 155 | 156 | 157 | 158 | 159 | 160 | 161 | 162 | 163 | 164 | 165 | 166 | 167 | 168 | 169 | 170 | 171 | 172 | 173 | 174 | 175 | 176 | 177 | 178 | 179 | 180 | 181 | 182 | 183 | 184 | 185 | 186 | 187 | 188 | 189 | 190 | 191 | 192 | 193 | 194 | 195 | 196 | 197 | 198 | 199 | 200 | 201 | 202 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV33_generated_urdf/nao_material.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV33_generated_urdf/nao_robot.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV33_generated_urdf/nao_torso.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV40_generated_urdf/naoTransmission.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | transmission_interface/SimpleTransmission 15 | 16 | PositionJointInterface 17 | 18 | 19 | 20 | PositionJointInterface 21 | ${speed_red_type3A} 22 | 23 | 24 | 25 | transmission_interface/SimpleTransmission 26 | 27 | PositionJointInterface 28 | 29 | 30 | 31 | PositionJointInterface 32 | ${speed_red_type3B} 33 | 34 | 35 | 36 | 37 | 38 | 39 | transmission_interface/SimpleTransmission 40 | 41 | PositionJointInterface 42 | 43 | 44 | PositionJointInterface 45 | ${speed_red_type3A} 46 | 47 | 48 | 49 | transmission_interface/SimpleTransmission 50 | 51 | PositionJointInterface 52 | 53 | 54 | PositionJointInterface 55 | ${speed_red_type3B} 56 | 57 | 58 | 59 | transmission_interface/SimpleTransmission 60 | 61 | PositionJointInterface 62 | 63 | 64 | PositionJointInterface 65 | ${speed_red_type3A} 66 | 67 | 68 | 69 | transmission_interface/SimpleTransmission 70 | 71 | PositionJointInterface 72 | 73 | 74 | PositionJointInterface 75 | ${speed_red_type3B} 76 | 77 | 78 | 79 | 80 | transmission_interface/SimpleTransmission 81 | 82 | PositionJointInterface 83 | 84 | 85 | PositionJointInterface 86 | ${speed_red_type2A} 87 | 88 | 89 | 90 | transmission_interface/SimpleTransmission 91 | 92 | PositionJointInterface 93 | 94 | 95 | PositionJointInterface 96 | ${speed_red_type2B} 97 | 98 | 99 | 100 | 101 | 102 | 103 | 104 | 105 | 106 | 107 | transmission_interface/SimpleTransmission 108 | 109 | PositionJointInterface 110 | 111 | 112 | 113 | PositionJointInterface 114 | ${speed_red_type1A} 115 | 116 | 117 | 118 | transmission_interface/SimpleTransmission 119 | 120 | PositionJointInterface 121 | 122 | 123 | 124 | PositionJointInterface 125 | ${speed_red_type1A} 126 | 127 | 128 | 129 | transmission_interface/SimpleTransmission 130 | 131 | PositionJointInterface 132 | 133 | 134 | 135 | PositionJointInterface 136 | ${speed_red_type1B} 137 | 138 | 139 | 140 | transmission_interface/SimpleTransmission 141 | 142 | PositionJointInterface 143 | 144 | 145 | 146 | PositionJointInterface 147 | ${speed_red_type1B} 148 | 149 | 150 | 151 | transmission_interface/SimpleTransmission 152 | 153 | PositionJointInterface 154 | 155 | 156 | 157 | PositionJointInterface 158 | ${speed_red_type1B} 159 | 160 | 161 | 162 | transmission_interface/SimpleTransmission 163 | 164 | PositionJointInterface 165 | 166 | 167 | 168 | PositionJointInterface 169 | ${speed_red_type1A} 170 | 171 | 172 | 173 | 174 | 175 | 176 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV40_generated_urdf/nao_arms.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | 72 | 73 | 74 | 75 | 76 | 77 | 78 | 79 | 80 | 81 | 82 | 83 | 84 | 85 | 86 | 87 | 88 | 89 | 90 | 91 | 92 | 93 | 94 | 95 | 96 | 97 | 98 | 99 | 100 | 101 | 102 | 103 | 104 | 105 | 106 | 107 | 108 | 109 | 110 | 111 | 112 | 113 | 114 | 115 | 116 | 117 | 118 | 119 | 120 | 121 | 122 | 123 | 124 | 125 | 126 | 127 | 128 | 129 | 130 | 131 | 132 | 133 | 134 | 135 | 136 | 137 | 138 | 139 | 140 | 141 | 142 | 143 | 144 | 145 | 146 | 147 | 148 | 149 | 150 | 151 | 152 | 153 | 154 | 155 | 156 | 157 | 158 | 159 | 160 | 161 | 162 | 163 | 164 | 165 | 166 | 167 | 168 | 169 | 170 | 171 | 172 | 173 | 174 | 175 | 176 | 177 | 178 | 179 | 180 | 181 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV40_generated_urdf/nao_fingers.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | 72 | 73 | 74 | 75 | 76 | 77 | 78 | 79 | 80 | 81 | 82 | 83 | 84 | 85 | 86 | 87 | 88 | 89 | 90 | 91 | 92 | 93 | 94 | 95 | 96 | 97 | 98 | 99 | 100 | 101 | 102 | 103 | 104 | 105 | 106 | 107 | 108 | 109 | 110 | 111 | 112 | 113 | 114 | 115 | 116 | 117 | 118 | 119 | 120 | 121 | 122 | 123 | 124 | 125 | 126 | 127 | 128 | 129 | 130 | 131 | 132 | 133 | 134 | 135 | 136 | 137 | 138 | 139 | 140 | 141 | 142 | 143 | 144 | 145 | 146 | 147 | 148 | 149 | 150 | 151 | 152 | 153 | 154 | 155 | 156 | 157 | 158 | 159 | 160 | 161 | 162 | 163 | 164 | 165 | 166 | 167 | 168 | 169 | 170 | 171 | 172 | 173 | 174 | 175 | 176 | 177 | 178 | 179 | 180 | 181 | 182 | 183 | 184 | 185 | 186 | 187 | 188 | 189 | 190 | 191 | 192 | 193 | 194 | 195 | 196 | 197 | 198 | 199 | 200 | 201 | 202 | 203 | 204 | 205 | 206 | 207 | 208 | 209 | 210 | 211 | 212 | 213 | 214 | 215 | 216 | 217 | 218 | 219 | 220 | 221 | 222 | 223 | 224 | 225 | 226 | 227 | 228 | 229 | 230 | 231 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV40_generated_urdf/nao_head.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV40_generated_urdf/nao_legs.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | 72 | 73 | 74 | 75 | 76 | 77 | 78 | 79 | 80 | 81 | 82 | 83 | 84 | 85 | 86 | 87 | 88 | 89 | 90 | 91 | 92 | 93 | 94 | 95 | 96 | 97 | 98 | 99 | 100 | 101 | 102 | 103 | 104 | 105 | 106 | 107 | 108 | 109 | 110 | 111 | 112 | 113 | 114 | 115 | 116 | 117 | 118 | 119 | 120 | 121 | 122 | 123 | 124 | 125 | 126 | 127 | 128 | 129 | 130 | 131 | 132 | 133 | 134 | 135 | 136 | 137 | 138 | 139 | 140 | 141 | 142 | 143 | 144 | 145 | 146 | 147 | 148 | 149 | 150 | 151 | 152 | 153 | 154 | 155 | 156 | 157 | 158 | 159 | 160 | 161 | 162 | 163 | 164 | 165 | 166 | 167 | 168 | 169 | 170 | 171 | 172 | 173 | 174 | 175 | 176 | 177 | 178 | 179 | 180 | 181 | 182 | 183 | 184 | 185 | 186 | 187 | 188 | 189 | 190 | 191 | 192 | 193 | 194 | 195 | 196 | 197 | 198 | 199 | 200 | 201 | 202 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV40_generated_urdf/nao_material.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV40_generated_urdf/nao_robot.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV40_generated_urdf/nao_torso.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV50_generated_urdf/naoTransmission.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | transmission_interface/SimpleTransmission 15 | 16 | PositionJointInterface 17 | 18 | 19 | 20 | PositionJointInterface 21 | ${speed_red_type3A} 22 | 23 | 24 | 25 | transmission_interface/SimpleTransmission 26 | 27 | PositionJointInterface 28 | 29 | 30 | 31 | PositionJointInterface 32 | ${speed_red_type3B} 33 | 34 | 35 | 36 | 37 | 38 | 39 | transmission_interface/SimpleTransmission 40 | 41 | PositionJointInterface 42 | 43 | 44 | PositionJointInterface 45 | ${speed_red_type3A} 46 | 47 | 48 | 49 | transmission_interface/SimpleTransmission 50 | 51 | PositionJointInterface 52 | 53 | 54 | PositionJointInterface 55 | ${speed_red_type3B} 56 | 57 | 58 | 59 | transmission_interface/SimpleTransmission 60 | 61 | PositionJointInterface 62 | 63 | 64 | PositionJointInterface 65 | ${speed_red_type3A} 66 | 67 | 68 | 69 | transmission_interface/SimpleTransmission 70 | 71 | PositionJointInterface 72 | 73 | 74 | PositionJointInterface 75 | ${speed_red_type3B} 76 | 77 | 78 | 79 | 80 | transmission_interface/SimpleTransmission 81 | 82 | PositionJointInterface 83 | 84 | 85 | PositionJointInterface 86 | ${speed_red_type2A} 87 | 88 | 89 | 90 | transmission_interface/SimpleTransmission 91 | 92 | PositionJointInterface 93 | 94 | 95 | PositionJointInterface 96 | ${speed_red_type2B} 97 | 98 | 99 | 100 | 101 | 102 | 103 | 104 | 105 | 106 | 107 | transmission_interface/SimpleTransmission 108 | 109 | PositionJointInterface 110 | 111 | 112 | 113 | PositionJointInterface 114 | ${speed_red_type1A} 115 | 116 | 117 | 118 | transmission_interface/SimpleTransmission 119 | 120 | PositionJointInterface 121 | 122 | 123 | 124 | PositionJointInterface 125 | ${speed_red_type1A} 126 | 127 | 128 | 129 | transmission_interface/SimpleTransmission 130 | 131 | PositionJointInterface 132 | 133 | 134 | 135 | PositionJointInterface 136 | ${speed_red_type1B} 137 | 138 | 139 | 140 | transmission_interface/SimpleTransmission 141 | 142 | PositionJointInterface 143 | 144 | 145 | 146 | PositionJointInterface 147 | ${speed_red_type1B} 148 | 149 | 150 | 151 | transmission_interface/SimpleTransmission 152 | 153 | PositionJointInterface 154 | 155 | 156 | 157 | PositionJointInterface 158 | ${speed_red_type1B} 159 | 160 | 161 | 162 | transmission_interface/SimpleTransmission 163 | 164 | PositionJointInterface 165 | 166 | 167 | 168 | PositionJointInterface 169 | ${speed_red_type1A} 170 | 171 | 172 | 173 | 174 | 175 | 176 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV50_generated_urdf/nao_arms.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | 72 | 73 | 74 | 75 | 76 | 77 | 78 | 79 | 80 | 81 | 82 | 83 | 84 | 85 | 86 | 87 | 88 | 89 | 90 | 91 | 92 | 93 | 94 | 95 | 96 | 97 | 98 | 99 | 100 | 101 | 102 | 103 | 104 | 105 | 106 | 107 | 108 | 109 | 110 | 111 | 112 | 113 | 114 | 115 | 116 | 117 | 118 | 119 | 120 | 121 | 122 | 123 | 124 | 125 | 126 | 127 | 128 | 129 | 130 | 131 | 132 | 133 | 134 | 135 | 136 | 137 | 138 | 139 | 140 | 141 | 142 | 143 | 144 | 145 | 146 | 147 | 148 | 149 | 150 | 151 | 152 | 153 | 154 | 155 | 156 | 157 | 158 | 159 | 160 | 161 | 162 | 163 | 164 | 165 | 166 | 167 | 168 | 169 | 170 | 171 | 172 | 173 | 174 | 175 | 176 | 177 | 178 | 179 | 180 | 181 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV50_generated_urdf/nao_head.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV50_generated_urdf/nao_legs.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | 72 | 73 | 74 | 75 | 76 | 77 | 78 | 79 | 80 | 81 | 82 | 83 | 84 | 85 | 86 | 87 | 88 | 89 | 90 | 91 | 92 | 93 | 94 | 95 | 96 | 97 | 98 | 99 | 100 | 101 | 102 | 103 | 104 | 105 | 106 | 107 | 108 | 109 | 110 | 111 | 112 | 113 | 114 | 115 | 116 | 117 | 118 | 119 | 120 | 121 | 122 | 123 | 124 | 125 | 126 | 127 | 128 | 129 | 130 | 131 | 132 | 133 | 134 | 135 | 136 | 137 | 138 | 139 | 140 | 141 | 142 | 143 | 144 | 145 | 146 | 147 | 148 | 149 | 150 | 151 | 152 | 153 | 154 | 155 | 156 | 157 | 158 | 159 | 160 | 161 | 162 | 163 | 164 | 165 | 166 | 167 | 168 | 169 | 170 | 171 | 172 | 173 | 174 | 175 | 176 | 177 | 178 | 179 | 180 | 181 | 182 | 183 | 184 | 185 | 186 | 187 | 188 | 189 | 190 | 191 | 192 | 193 | 194 | 195 | 196 | 197 | 198 | 199 | 200 | 201 | 202 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV50_generated_urdf/nao_material.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV50_generated_urdf/nao_robot.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /nao_description/urdf/naoV50_generated_urdf/nao_torso.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /nao_description/urdf/nao_robot_v3.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | -------------------------------------------------------------------------------- /nao_description/urdf/nao_robot_v4.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | -------------------------------------------------------------------------------- /nao_description/urdf/visuals.xacro: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | 72 | 73 | 74 | 75 | 76 | 77 | 78 | 79 | 80 | 81 | 82 | 83 | 84 | 85 | 86 | 87 | 88 | 89 | 90 | 91 | 92 | 93 | 94 | 95 | 96 | 97 | 98 | 99 | 100 | 101 | 102 | 103 | 104 | 105 | 106 | 107 | 108 | 109 | 110 | 111 | 112 | 113 | 114 | 115 | 116 | 117 | 118 | 119 | 120 | 121 | 122 | 123 | 124 | 125 | 126 | 127 | 128 | 129 | 130 | 131 | 132 | 133 | 134 | 135 | 136 | 137 | -------------------------------------------------------------------------------- /nao_robot/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package nao_robot 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.5.15 (2016-11-23) 6 | ------------------- 7 | 8 | 0.5.14 (2016-01-23) 9 | ------------------- 10 | 11 | 0.5.13 (2016-01-16) 12 | ------------------- 13 | 14 | 0.5.12 (2016-01-01) 15 | ------------------- 16 | 17 | 0.5.11 (2015-08-11) 18 | ------------------- 19 | 20 | 0.5.10 (2015-07-31) 21 | ------------------- 22 | * remove nao_pose 23 | * Contributors: Karsten Knese 24 | 25 | 0.5.9 (2015-07-30) 26 | ------------------ 27 | 28 | 0.5.8 (2015-07-30) 29 | ------------------ 30 | 31 | 0.5.7 (2015-03-27) 32 | ------------------ 33 | 34 | 0.5.6 (2015-02-27) 35 | ------------------ 36 | 37 | 0.5.5 (2015-02-17) 38 | ------------------ 39 | 40 | 0.5.4 (2015-02-17) 41 | ------------------ 42 | 43 | 0.5.3 (2014-12-14) 44 | ------------------ 45 | 46 | 0.5.2 (2014-12-04) 47 | ------------------ 48 | 49 | 0.5.1 (2014-11-13) 50 | ------------------ 51 | 52 | 0.5.0 (2014-11-06) 53 | ------------------ 54 | * transfer nao_robot 55 | * 0.4.1 56 | * update changelogs 57 | * get the accent right in Séverin's name 58 | * 0.4.0 59 | * update changelogs 60 | * 0.3.0 61 | * update changelogs 62 | * update maintainers 63 | Armin, thank you for all your work, in ROS, Octomap and NAO. 64 | Good luck out of the university ! 65 | * "0.2.3" 66 | * Changelogs 67 | * {ahornung->ros-nao} 68 | * {ahornung->ros-nao} 69 | * Update nao_robot package.xml 70 | * "0.2.2" 71 | * changelog 72 | * "0.2.1" 73 | * Changelogs 74 | * "0.2.0" 75 | * Adding (edited) catkin-generated changelogs 76 | * Adding bugtracker and repo URLs to package manifests 77 | * Fix nao_robot metapackage xml 78 | * Add run_depends to nao_robot metapackage 79 | * Initial catkinization. 80 | Beware! Compilation of nao_sensors_cpp has been temporarily disabled. 81 | * Contributors: Armin Hornung, Karsten Knese, Miguel Sarabia, Séverin Lemaignan, Vincent Rabaud 82 | -------------------------------------------------------------------------------- /nao_robot/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(nao_robot) 3 | find_package(catkin REQUIRED) 4 | catkin_metapackage() 5 | -------------------------------------------------------------------------------- /nao_robot/package.xml: -------------------------------------------------------------------------------- 1 | 2 | nao_robot 3 | 0.5.15 4 | 5 |

The nao_robot metapackage contains some useful nodes to integrate the Nao humanoid robot into ROS. 6 | Check out the nao_extras stack for more functionality. 7 | The humanoid_navigation stack contains some more general packages for humanoid/biped robots.

8 |
9 | Séverin Lemaignan 10 | Vincent Rabaud 11 | Armin Hornung 12 | BSD 13 | 14 | http://www.ros.org/wiki/nao_robot 15 | https://github.com/ros-nao/nao_robot/issues 16 | https://github.com/ros-nao/nao_robot 17 | 18 | catkin 19 | 20 | 21 | 22 | 23 | nao_apps 24 | nao_bringup 25 | nao_description 26 | 27 |
28 | --------------------------------------------------------------------------------