Created
July 1, 2014 00:30
-
-
Save jonbinney/a36405694f68d2f4339d to your computer and use it in GitHub Desktop.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
<?xml version="1.0" ?> | |
<!-- =================================================================================== --> | |
<!-- | This document was autogenerated by xacro from src/nao_robot/nao_description/urdf/nao_robot_v4.urdf.xacro | --> | |
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | --> | |
<!-- =================================================================================== --> | |
<robot name="nao" xmlns:xacro="http://ros.org/wiki/xacro"> | |
<!-- | |
ROS urdf definition of the Nao humanoid robot by Aldebaran Robotics | |
This is part of the Nao-Stack of University of Freiburg, available at: | |
http://code.google.com/p/alufr-ros-pkg/ | |
Authors: Armin Hornung, Stefan Osswald | |
Joint names and properties are according to the Nao-documentation of | |
Aldebaran Robotics ("Kinematics 4.0" for Nao V4.0). | |
This file loads a basic visualization of Nao and the structure (you need both) | |
--> | |
<material name="LightGrey"> | |
<color rgba="0.8 0.8 0.8 1.0"/> | |
</material> | |
<material name="Grey"> | |
<color rgba="0.6 0.6 0.6 1.0"/> | |
</material> | |
<material name="DarkGrey"> | |
<color rgba="0.3 0.3 0.3 1.0"/> | |
</material> | |
<material name="Black"> | |
<color rgba="0.1 0.1 0.1 1.0"/> | |
</material> | |
<link name="base_link"/> | |
<link name="torso"> | |
<!--<inertial> | |
<origin xyz="0 0 0" rpy="0 0 0"/> | |
<mass value="0"/> | |
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0" /> | |
</inertial> --> | |
<inertial> | |
<origin rpy="0 0 0" xyz="-0.00413 0.00009 0.04342"/> | |
<mass value="1.04956"/> | |
<inertia ixx="0.00487953284" ixy="-0.00001428591" ixz="-0.00019545651" iyy="0.00470360698" iyz="0.00002224589" izz="0.0015671352"/> | |
</inertial> | |
<visual> | |
<!-- one cylinder spanning over HipOffsetZ and NeckOffsetZ --> | |
<origin rpy="0 0 0" xyz="0 0 0.02075"/> | |
<geometry> | |
<cylinder length="0.2115" radius="0.015"/> | |
</geometry> | |
<material name="LightGrey"/> | |
</visual> | |
</link> | |
<link name="HeadYaw_link"> | |
<inertial> | |
<origin rpy="0 0 0" xyz="-0.00001 0.00014 -0.02742"/> | |
<mass value="0.06442"/> | |
<inertia ixx="0.00006223368" ixy="0.00000000042" ixz="0.00000007448" iyy="0.00006324431" iyz="0.00000010416" izz="0.00000549462"/> | |
</inertial> | |
</link> | |
<link name="HeadPitch_link"> | |
<inertial> | |
<origin rpy="0 0 0" xyz="-0.00112 -0.00003 0.05258"/> | |
<mass value="0.60533"/> | |
<inertia ixx="0.00208895741" ixy="0.00000549094" ixz="0.0001133995" iyy="1932222.63e-9" iyz="-0.00002803917" izz="0.00082257793"/> | |
</inertial> | |
<visual> | |
<origin rpy="1.57 0 0" xyz="0 0 0.058"/> | |
<geometry> | |
<cylinder length="0.14" radius="0.04"/> | |
</geometry> | |
<material name="LightGrey"/> | |
</visual> | |
</link> | |
<link name="gaze"/> | |
<link name="CameraTop_frame"> | |
</link> | |
<link name="CameraBottom_frame"> | |
</link> | |
<link name="l_wrist"/> | |
<link name="r_wrist"/> | |
<link name="l_gripper"> | |
</link> | |
<link name="r_gripper"> | |
</link> | |
<link name="LShoulderPitch_link"> | |
<inertial> | |
<origin rpy="0 0 0" xyz="-0.00165 0.02663 0.00014"/> | |
<mass value="0.07504"/> | |
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> | |
</inertial> | |
</link> | |
<link name="LElbowYaw_link"> | |
<inertial> | |
<origin rpy="0 0 0" xyz="-0.02744 0.00000 -0.00014"/> | |
<mass value="0.06483"/> | |
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> | |
</inertial> | |
</link> | |
<link name="LElbowRoll_link"> | |
<inertial> | |
<origin rpy="0 0 0" xyz="0.02552 0.00281 0.00090"/> | |
<mass value="0.07778"/> | |
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> | |
</inertial> | |
<visual> | |
<origin rpy="1.57079632679 0 1.57079632679" xyz="0.025325 0 0"/> | |
<geometry> | |
<cylinder length="0.05065" radius="0.015"/> | |
</geometry> | |
<material name="LightGrey"/> | |
</visual> | |
</link> | |
<link name="LWristYaw_link"> | |
<inertial> | |
<origin rpy="0 0 0" xyz="0.03434 0.00088 -0.00308"/> | |
<mass value="0.18533"/> | |
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> | |
</inertial> | |
<visual> | |
<origin rpy="1.57079632679 0 1.57079632679" xyz="0.029 0 0"/> | |
<geometry> | |
<cylinder length="0.058" radius="0.015"/> | |
</geometry> | |
<material name="LightGrey"/> | |
</visual> | |
</link> | |
<link name="RShoulderPitch_link"> | |
<inertial> | |
<origin rpy="0 0 0" xyz="-0.00165 -0.02663 0.00014"/> | |
<mass value="0.07504"/> | |
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> | |
</inertial> | |
</link> | |
<link name="RElbowYaw_link"> | |
<inertial> | |
<origin rpy="0 0 0" xyz="-0.02744 0.00000 -0.00014"/> | |
<mass value="0.06483"/> | |
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> | |
</inertial> | |
</link> | |
<link name="RElbowRoll_link"> | |
<inertial> | |
<origin rpy="0 0 0" xyz="0.02552 -0.00281 0.00090"/> | |
<mass value="0.07778"/> | |
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> | |
</inertial> | |
<visual> | |
<origin rpy="1.57079632679 0 1.57079632679" xyz="0.025325 0 0"/> | |
<geometry> | |
<cylinder length="0.05065" radius="0.015"/> | |
</geometry> | |
<material name="LightGrey"/> | |
</visual> | |
</link> | |
<link name="RWristYaw_link"> | |
<inertial> | |
<origin rpy="0 0 0" xyz="0.03434 -0.00088 -0.00308"/> | |
<mass value="0.18533"/> | |
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> | |
</inertial> | |
<visual> | |
<origin rpy="1.57079632679 0 1.57079632679" xyz="0.029 0 0"/> | |
<geometry> | |
<cylinder length="0.058" radius="0.015"/> | |
</geometry> | |
<material name="LightGrey"/> | |
</visual> | |
</link> | |
<link name="RShoulderRoll_link"> | |
<inertial> | |
<origin rpy="0 0 0" xyz="0.02429 -0.00952 0.00320"/> | |
<mass value="0.15794"/> | |
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> | |
</inertial> | |
<visual> | |
<origin rpy="1.57079632679 0 1.57079632679" xyz="0.045 0 0"/> | |
<geometry> | |
<cylinder length="0.09" radius="0.015"/> | |
</geometry> | |
<material name="LightGrey"/> | |
</visual> | |
</link> | |
<link name="LShoulderRoll_link"> | |
<inertial> | |
<origin rpy="0 0 0" xyz="0.02455 0.00563 0.00330"/> | |
<mass value="0.15777"/> | |
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> | |
</inertial> | |
<visual> | |
<origin rpy="1.57079632679 0 1.57079632679" xyz="0.045 0 0"/> | |
<geometry> | |
<cylinder length="0.09" radius="0.015"/> | |
</geometry> | |
<material name="LightGrey"/> | |
</visual> | |
</link> | |
<link name="l_ankle"/> | |
<link name="r_ankle"/> | |
<link name="l_sole"> | |
<visual> | |
<origin rpy="0 0 0" xyz="0.02 0 0.0075"/> | |
<geometry> | |
<box size="0.16 0.06 0.015"/> | |
</geometry> | |
<material name="LightGrey"/> | |
</visual> | |
</link> | |
<link name="r_sole"> | |
<visual> | |
<origin rpy="0 0 0" xyz="0.02 0 0.0075"/> | |
<geometry> | |
<box size="0.16 0.06 0.015"/> | |
</geometry> | |
<material name="LightGrey"/> | |
</visual> | |
</link> | |
<link name="LHipYawPitch_link"> | |
<inertial> | |
<origin rpy="0 0 0" xyz="-0.00773 -0.0115 0.0269"/> | |
<mass value="0.07050"/> | |
<!-- +/-0.00068 --> | |
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> | |
</inertial> | |
</link> | |
<link name="LHipRoll_link"> | |
<inertial> | |
<origin rpy="0 0 0" xyz="-0.01549 0.00029 -0.00516"/> | |
<mass value="0.13053"/> | |
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> | |
</inertial> | |
</link> | |
<link name="LHipPitch_link"> | |
<inertial> | |
<origin rpy="0 0 0" xyz="0.00139 0.00223 -0.05373"/> | |
<mass value="0.38972"/> | |
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> | |
</inertial> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 -0.05"/> | |
<geometry> | |
<cylinder length="0.1" radius="0.015"/> | |
</geometry> | |
<material name="LightGrey"/> | |
</visual> | |
</link> | |
<link name="LKneePitch_link"> | |
<inertial> | |
<origin rpy="0 0 0" xyz="0.00423 0.00223 -0.04937"/> | |
<mass value="0.29152"/> | |
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> | |
</inertial> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 -0.05"/> | |
<geometry> | |
<cylinder length="0.1" radius="0.015"/> | |
</geometry> | |
<material name="LightGrey"/> | |
</visual> | |
</link> | |
<link name="LAnklePitch_link"> | |
<inertial> | |
<origin rpy="0 0 0" xyz="0.00045 0.00029 0.00684"/> | |
<mass value="0.13415"/> | |
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> | |
</inertial> | |
</link> | |
<link name="LAnkleRoll_link"> | |
<inertial> | |
<origin rpy="0 0 0" xyz="0.02541 0.00331 -0.03239"/> | |
<mass value="0.16178"/> | |
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> | |
</inertial> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 -0.023"/> | |
<geometry> | |
<cylinder length="0.046" radius="0.015"/> | |
</geometry> | |
<material name="LightGrey"/> | |
</visual> | |
</link> | |
<link name="RHipYawPitch_link"> | |
<inertial> | |
<origin rpy="0 0 0" xyz="-0.00773 0.0115 0.0269"/> | |
<mass value="0.07050"/> | |
<!-- +/-0.00068 --> | |
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> | |
</inertial> | |
</link> | |
<link name="RHipRoll_link"> | |
<inertial> | |
<origin rpy="0 0 0" xyz="-0.01549 -0.00029 -0.00516"/> | |
<mass value="0.13053"/> | |
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> | |
</inertial> | |
</link> | |
<link name="RHipPitch_link"> | |
<inertial> | |
<origin rpy="0 0 0" xyz="0.00139 -0.00223 -0.05373"/> | |
<mass value="0.38972"/> | |
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> | |
</inertial> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 -0.05"/> | |
<geometry> | |
<cylinder length="0.1" radius="0.015"/> | |
</geometry> | |
<material name="LightGrey"/> | |
</visual> | |
</link> | |
<link name="RKneePitch_link"> | |
<inertial> | |
<origin rpy="0 0 0" xyz="0.00423 -0.00223 -0.04937"/> | |
<mass value="0.29152"/> | |
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> | |
</inertial> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 -0.05"/> | |
<geometry> | |
<cylinder length="0.1" radius="0.015"/> | |
</geometry> | |
<material name="LightGrey"/> | |
</visual> | |
</link> | |
<link name="RAnklePitch_link"> | |
<inertial> | |
<origin rpy="0 0 0" xyz="0.00045 -0.00029 0.00684"/> | |
<mass value="0.13415"/> | |
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> | |
</inertial> | |
</link> | |
<link name="RAnkleRoll_link"> | |
<inertial> | |
<origin rpy="0 0 0" xyz="0.02541 -0.00331 -0.03239"/> | |
<mass value="0.16178"/> | |
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> | |
</inertial> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 -0.023"/> | |
<geometry> | |
<cylinder length="0.046" radius="0.015"/> | |
</geometry> | |
<material name="LightGrey"/> | |
</visual> | |
</link> | |
<joint name="base_joint" type="fixed"> | |
<child link="torso"/> | |
<parent link="base_link"/> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
</joint> | |
<joint name="HeadYaw" type="revolute"> | |
<parent link="torso"/> | |
<child link="HeadYaw_link"/> | |
<!-- NeckOffsetZ --> | |
<origin rpy="0 0 0" xyz="0 0 0.1265"/> | |
<axis xyz="0 0 1"/> | |
<limit effort="30" lower="-2.0857" upper="2.0857" velocity="3.0"/> | |
</joint> | |
<joint name="HeadPitch" type="revolute"> | |
<parent link="HeadYaw_link"/> | |
<child link="HeadPitch_link"/> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<axis xyz="0 1 0"/> | |
<limit effort="30" lower="-0.6720" upper="0.5149" velocity="3.0"/> | |
</joint> | |
<joint name="gaze_joint" type="fixed"> | |
<parent link="HeadPitch_link"/> | |
<child link="gaze"/> | |
<origin xyz="0.0539 0 0.05"/> | |
</joint> | |
<joint name="CameraTop" type="fixed"> | |
<parent link="HeadPitch_link"/> | |
<child link="CameraTop_frame"/> | |
<!-- rotated by 1.2 degress --> | |
<origin rpy="-1.59174 0 -1.57079632679" xyz="0.05871 0 0.06364"/> | |
</joint> | |
<joint name="CameraBottom" type="fixed"> | |
<parent link="HeadPitch_link"/> | |
<child link="CameraBottom_frame"/> | |
<!-- rotated by 39.7 degrees --> | |
<origin rpy="-2.263692 0 -1.57079632679" xyz="0.05071 0 0.01774"/> | |
</joint> | |
<joint name="l_wrist_joint" type="fixed"> | |
<parent link="LWristYaw_link"/> | |
<child link="l_wrist"/> | |
<origin xyz="0 0 0"/> | |
</joint> | |
<joint name="r_wrist_joint" type="fixed"> | |
<parent link="RWristYaw_link"/> | |
<child link="r_wrist"/> | |
<origin xyz="0 0 0"/> | |
</joint> | |
<joint name="l_gripper_joint" type="fixed"> | |
<parent link="l_wrist"/> | |
<child link="l_gripper"/> | |
<origin xyz="0.058 0 -0.0159"/> | |
</joint> | |
<joint name="r_gripper_joint" type="fixed"> | |
<parent link="r_wrist"/> | |
<child link="r_gripper"/> | |
<origin xyz="0.058 0 -0.0159"/> | |
</joint> | |
<joint name="LElbowRoll" type="revolute"> | |
<parent link="LElbowYaw_link"/> | |
<child link="LElbowRoll_link"/> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<axis xyz="0 0 1"/> | |
<limit effort="30" lower="-1.5446" upper="-0.0349" velocity="3.0"/> | |
</joint> | |
<joint name="RElbowRoll" type="revolute"> | |
<parent link="RElbowYaw_link"/> | |
<child link="RElbowRoll_link"/> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<axis xyz="0 0 1"/> | |
<limit effort="30" lower="0.0349" upper="1.5446" velocity="3.0"/> | |
</joint> | |
<joint name="LShoulderRoll" type="revolute"> | |
<parent link="LShoulderPitch_link"/> | |
<child link="LShoulderRoll_link"/> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<axis xyz="0 0 1"/> | |
<limit effort="30" lower="-0.3142" upper="1.3265" velocity="3.0"/> | |
</joint> | |
<joint name="RShoulderRoll" type="revolute"> | |
<parent link="RShoulderPitch_link"/> | |
<child link="RShoulderRoll_link"/> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<axis xyz="0 0 1"/> | |
<limit effort="30" lower="-1.3265" upper="0.3142" velocity="3.0"/> | |
</joint> | |
<joint name="LShoulderPitch" type="revolute"> | |
<parent link="torso"/> | |
<child link="LShoulderPitch_link"/> | |
<origin rpy="0 0 0" xyz="0 0.098 0.1"/> | |
<axis xyz="0 1 0"/> | |
<limit effort="30" lower="-2.0857" upper="2.0857" velocity="3.0"/> | |
</joint> | |
<joint name="LElbowYaw" type="revolute"> | |
<parent link="LShoulderRoll_link"/> | |
<child link="LElbowYaw_link"/> | |
<origin rpy="0 0 0" xyz="0.105 0.015 0"/> | |
<axis xyz="1 0 0"/> | |
<limit effort="30" lower="-2.0857" upper="2.0857" velocity="3.0"/> | |
</joint> | |
<joint name="LWristYaw" type="revolute"> | |
<parent link="LElbowRoll_link"/> | |
<child link="LWristYaw_link"/> | |
<origin rpy="0 0 0" xyz="0.05595 0 0"/> | |
<axis xyz="1 0 0"/> | |
<limit effort="30" lower="-1.8238" upper="1.8238" velocity="3.0"/> | |
</joint> | |
<joint name="RShoulderPitch" type="revolute"> | |
<parent link="torso"/> | |
<child link="RShoulderPitch_link"/> | |
<origin rpy="0 0 0" xyz="0 -0.098 0.1"/> | |
<axis xyz="0 1 0"/> | |
<limit effort="30" lower="-2.0857" upper="2.0857" velocity="3.0"/> | |
</joint> | |
<joint name="RElbowYaw" type="revolute"> | |
<parent link="RShoulderRoll_link"/> | |
<child link="RElbowYaw_link"/> | |
<origin rpy="0 0 0" xyz="0.105 -0.015 0"/> | |
<axis xyz="1 0 0"/> | |
<limit effort="30" lower="-2.0857" upper="2.0857" velocity="3.0"/> | |
</joint> | |
<joint name="RWristYaw" type="revolute"> | |
<parent link="RElbowRoll_link"/> | |
<child link="RWristYaw_link"/> | |
<origin rpy="0 0 0" xyz="0.05595 0 0"/> | |
<axis xyz="1 0 0"/> | |
<limit effort="30" lower="-1.8238" upper="1.8238" velocity="3.0"/> | |
</joint> | |
<joint name="LHipYawPitch" type="revolute"> | |
<parent link="torso"/> | |
<child link="LHipYawPitch_link"/> | |
<origin rpy="0 0 0" xyz="0 0.05 -0.085"/> | |
<axis xyz="0 0.707106 -0.707106"/> | |
<limit effort="30" lower="-1.145303" upper="0.740810" velocity="3.0"/> | |
</joint> | |
<joint name="RHipYawPitch" type="revolute"> | |
<parent link="torso"/> | |
<child link="RHipYawPitch_link"/> | |
<origin rpy="0 0 0" xyz="0 -0.05 -0.085"/> | |
<axis xyz="0 0.707106 0.707106"/> | |
<limit effort="30" lower="-1.145303" upper="0.740810" velocity="3.0"/> | |
<mimic joint="LHipYawPitch" multiplier="1" offset="0"/> | |
</joint> | |
<joint name="LHipRoll" type="revolute"> | |
<parent link="LHipYawPitch_link"/> | |
<child link="LHipRoll_link"/> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<axis xyz="1 0 0"/> | |
<limit effort="30" lower="-0.379472" upper="0.790477" velocity="3.0"/> | |
</joint> | |
<joint name="RHipRoll" type="revolute"> | |
<parent link="RHipYawPitch_link"/> | |
<child link="RHipRoll_link"/> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<axis xyz="1 0 0"/> | |
<limit effort="30" lower="-0.738321" upper="0.414754" velocity="3.0"/> | |
</joint> | |
<joint name="LAnkleRoll" type="revolute"> | |
<parent link="LAnklePitch_link"/> | |
<child link="LAnkleRoll_link"/> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<axis xyz="1 0 0"/> | |
<limit effort="30" lower="-0.769001" upper="0.397880" velocity="3.0"/> | |
</joint> | |
<joint name="RAnkleRoll" type="revolute"> | |
<parent link="RAnklePitch_link"/> | |
<child link="RAnkleRoll_link"/> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<axis xyz="1 0 0"/> | |
<limit effort="30" lower="-0.388676" upper="0.785875" velocity="3.0"/> | |
</joint> | |
<joint name="l_ankle_joint" type="fixed"> | |
<parent link="LAnkleRoll_link"/> | |
<child link="l_ankle"/> | |
<origin xyz="0 0 0"/> | |
</joint> | |
<joint name="r_ankle_joint" type="fixed"> | |
<parent link="RAnkleRoll_link"/> | |
<child link="r_ankle"/> | |
<origin xyz="0 0 0"/> | |
</joint> | |
<joint name="l_sole_joint" type="fixed"> | |
<parent link="l_ankle"/> | |
<child link="l_sole"/> | |
<origin xyz="0 0 -0.04519"/> | |
</joint> | |
<joint name="r_sole_joint" type="fixed"> | |
<parent link="r_ankle"/> | |
<child link="r_sole"/> | |
<origin xyz="0 0 -0.04519"/> | |
</joint> | |
<joint name="LHipPitch" type="revolute"> | |
<parent link="LHipRoll_link"/> | |
<child link="LHipPitch_link"/> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<axis xyz="0 1 0"/> | |
<!--Nao V3 and V4--> | |
<!-- LHipPitch limits: -1.773912 .. 0.484090 --> | |
<!-- RHipPitch limits: -1.772308 .. 0.485624 --> | |
<limit effort="30" lower="-1.772308" upper="0.484090" velocity="3.0"/> | |
</joint> | |
<joint name="LKneePitch" type="revolute"> | |
<parent link="LHipPitch_link"/> | |
<child link="LKneePitch_link"/> | |
<origin rpy="0 0 0" xyz="0 0 -0.1"/> | |
<axis xyz="0 1 0"/> | |
<!-- LKneePitch limits: -0.092346 .. 2.112528 --> | |
<!-- RKneePitch limits: -0.103083 .. 2.120198 --> | |
<limit effort="30" lower="-0.092346" upper="2.112528" velocity="3.0"/> | |
</joint> | |
<joint name="LAnklePitch" type="revolute"> | |
<parent link="LKneePitch_link"/> | |
<child link="LAnklePitch_link"/> | |
<origin rpy="0 0 0" xyz="0 0 -0.10290"/> | |
<axis xyz="0 1 0"/> | |
<!-- LAnklePitch limits: -1.189516 .. 0.922747 --> | |
<!-- RAnklePitch limits: -1.186448 .. 0.932056 --> | |
<limit effort="30" lower="-1.186448" upper="0.922747" velocity="3.0"/> | |
</joint> | |
<joint name="RHipPitch" type="revolute"> | |
<parent link="RHipRoll_link"/> | |
<child link="RHipPitch_link"/> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<axis xyz="0 1 0"/> | |
<!--Nao V3 and V4--> | |
<!-- LHipPitch limits: -1.773912 .. 0.484090 --> | |
<!-- RHipPitch limits: -1.772308 .. 0.485624 --> | |
<limit effort="30" lower="-1.772308" upper="0.484090" velocity="3.0"/> | |
</joint> | |
<joint name="RKneePitch" type="revolute"> | |
<parent link="RHipPitch_link"/> | |
<child link="RKneePitch_link"/> | |
<origin rpy="0 0 0" xyz="0 0 -0.1"/> | |
<axis xyz="0 1 0"/> | |
<!-- LKneePitch limits: -0.092346 .. 2.112528 --> | |
<!-- RKneePitch limits: -0.103083 .. 2.120198 --> | |
<limit effort="30" lower="-0.092346" upper="2.112528" velocity="3.0"/> | |
</joint> | |
<joint name="RAnklePitch" type="revolute"> | |
<parent link="RKneePitch_link"/> | |
<child link="RAnklePitch_link"/> | |
<origin rpy="0 0 0" xyz="0 0 -0.10290"/> | |
<axis xyz="0 1 0"/> | |
<!-- LAnklePitch limits: -1.189516 .. 0.922747 --> | |
<!-- RAnklePitch limits: -1.186448 .. 0.932056 --> | |
<limit effort="30" lower="-1.186448" upper="0.922747" velocity="3.0"/> | |
</joint> | |
</robot> |
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment