532 lines
24 KiB
XML
532 lines
24 KiB
XML
<?xml version="1.0" encoding="utf-8"?>
|
|
<!-- =================================================================================== -->
|
|
<!-- Copyright 2019 ANYbotics, https://www.anybotics.com -->
|
|
<!-- =================================================================================== -->
|
|
<!-- This file contains the description of the ANYmal B robot. -->
|
|
<robot name="anymal"
|
|
xmlns:xacro="http://www.ros.org/wiki/xacro">
|
|
<!-- Material for the visual primitives -->
|
|
<material name="anymal_material">
|
|
<color rgba="0.7 0.7 0.7 1.0"/>
|
|
</material>
|
|
<!-- Base link -->
|
|
<link name="base">
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="../meshes/anymal_base.dae" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
<!-- <material name="anymal_material"/> -->
|
|
</visual>
|
|
<collision>
|
|
<!-- Main Body -->
|
|
<origin rpy="0 0 0" xyz="0 0 0.08"/>
|
|
<geometry>
|
|
<box size="0.531 0.27 0.24"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="-0.001960558279 -0.001413217745 0.050207125344"/>
|
|
<mass value="16.793507758"/>
|
|
<inertia ixx="0.217391101503" ixy="-0.00132873239126" ixz="-0.00228200226173" iyy="0.639432546734" iyz="-0.00138078263145" izz="0.62414077654"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="LF_HIP">
|
|
<visual>
|
|
<origin rpy="0 0 0.0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="../meshes/anymal_hip_l.dae" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
<!-- <material name="anymal_material"/> -->
|
|
</visual>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0.064516258147 -0.003787101702 -0.000152184388"/>
|
|
<mass value="1.42462064"/>
|
|
<inertia ixx="0.00243023349564" ixy="-1.53023971e-05" ixz="-2.1819095354e-05" iyy="0.00230257239103" iyz="2.6473021273e-05" izz="0.0019806759227"/>
|
|
</inertial>
|
|
</link>
|
|
<!-- Hip joint -->
|
|
<joint name="LF_HAA" type="revolute">
|
|
<parent link="base"/>
|
|
<child link="LF_HIP"/>
|
|
<origin xyz="0.277 0.116 0.0"/>
|
|
<axis xyz="1 0 0"/>
|
|
<limit command_effort="80" current="10" effort="80" gear_velocity="10" lower="-9.42" upper="9.42" velocity="15"/>
|
|
<dynamics damping="0.0" friction="0.0"/>
|
|
</joint>
|
|
<link name="LF_THIGH">
|
|
<visual>
|
|
<origin rpy="0 0 0.0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="../meshes/anymal_thigh_l.dae" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
<!-- <material name="anymal_material"/> -->
|
|
</visual>
|
|
<collision>
|
|
<!-- KFE actuator -->
|
|
<origin rpy="1.57079632679 0 0" xyz="0.0 0.069 -0.25"/>
|
|
<geometry>
|
|
<cylinder length="0.12" radius="0.06"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="-0.003897968082 0.054226618537 -0.214583373795"/>
|
|
<mass value="1.634976467"/>
|
|
<inertia ixx="0.0120367944369" ixy="6.762065206e-05" ixz="0.000287806340448" iyy="0.0120643637939" iyz="-0.00140610131218" izz="0.00249422574881"/>
|
|
</inertial>
|
|
</link>
|
|
<!-- Thigh joint -->
|
|
<joint name="LF_HFE" type="revolute">
|
|
<parent link="LF_HIP"/>
|
|
<child link="LF_THIGH"/>
|
|
<origin xyz="0.0635 0.041 0.0"/>
|
|
<axis xyz="0 1 0"/>
|
|
<limit command_effort="80" effort="80" lower="-9.42" upper="9.42" velocity="20"/>
|
|
<dynamics damping="0.0" friction="0.0"/>
|
|
</joint>
|
|
<link name="LF_SHANK">
|
|
<visual>
|
|
<origin rpy="0 0 0.0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="../meshes/anymal_shank_l.dae" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
<!-- <material name="anymal_material"/> -->
|
|
</visual>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0.030816858139 -0.004617229294 0.000893125713"/>
|
|
<mass value="0.207204302"/>
|
|
<inertia ixx="0.0002104880248" ixy="-5.6750980345e-05" ixz="1.0127699391e-05" iyy="0.000676270210023" iyz="-8.22869024e-07" izz="0.000545032674924"/>
|
|
</inertial>
|
|
</link>
|
|
<!-- Shank joint -->
|
|
<joint name="LF_KFE" type="revolute">
|
|
<parent link="LF_THIGH"/>
|
|
<child link="LF_SHANK"/>
|
|
<origin xyz="0.0 0.109 -0.25"/>
|
|
<axis xyz="0 1 0"/>
|
|
<limit command_effort="80" effort="80" lower="-9.42" upper="9.42" velocity="20"/>
|
|
<dynamics damping="0.0" friction="0.0"/>
|
|
</joint>
|
|
<!-- Shank to Adapter joint -->
|
|
<joint name="LF_SHANK_TO_ADAPTER" type="fixed">
|
|
<parent link="LF_SHANK"/>
|
|
<child link="LF_ADAPTER"/>
|
|
<origin rpy="0.0 0.0 0.0" xyz="0.1 -0.02 0.0"/>
|
|
</joint>
|
|
<!-- Adapter link -->
|
|
<link name="LF_ADAPTER">
|
|
<visual>
|
|
<origin rpy="0 0 0.0" xyz="0 0 0.032"/>
|
|
<geometry>
|
|
<mesh filename="../meshes/anymal_foot.dae" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
<!-- <material name="anymal_material"/> -->
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 -0.160625"/>
|
|
<geometry>
|
|
<cylinder length="0.25" radius="0.015"/>
|
|
</geometry>
|
|
<!-- <material name="anymal_material"/> -->
|
|
</collision>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="-8.66e-10 -1.472e-09 -0.244345749188"/>
|
|
<mass value="0.140170767"/>
|
|
<inertia ixx="0.00159938741862" ixy="-9.32e-13" ixz="1.039e-11" iyy="0.00159938741932" iyz="1.7563e-11" izz="5.4423177329e-05"/>
|
|
</inertial>
|
|
</link>
|
|
<!-- Adapter to Foot joint -->
|
|
<joint name="LF_ADAPTER_TO_FOOT" type="fixed" dont_collapse="true">
|
|
<parent link="LF_ADAPTER"/>
|
|
<child link="LF_FOOT"/>
|
|
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 -0.32125"/>
|
|
</joint>
|
|
<!-- Foot link -->
|
|
<link name="LF_FOOT">
|
|
<collision>
|
|
<origin xyz="0 0 0.02325"/>
|
|
<geometry>
|
|
<sphere radius="0.031"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0 0 0.02325"/>
|
|
<mass value="0.05"/>
|
|
<inertia ixx="0.001" ixy="-2.63048e-07" ixz="6.815581e-06" iyy="0.001" iyz="-6.815583e-06" izz="8.319196e-06"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="RF_HIP">
|
|
<visual>
|
|
<origin rpy="0 0 0.0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="../meshes/anymal_hip_r.dae" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
<!-- <material name="anymal_material"/> -->
|
|
</visual>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0.064516258147 0.003787101702 -0.000152184388"/>
|
|
<mass value="1.42462064"/>
|
|
<inertia ixx="0.00243023349564" ixy="1.53023971e-05" ixz="-2.1819095354e-05" iyy="0.00230257239103" iyz="-2.6473021273e-05" izz="0.0019806759227"/>
|
|
</inertial>
|
|
</link>
|
|
<!-- Hip joint -->
|
|
<joint name="RF_HAA" type="revolute">
|
|
<parent link="base"/>
|
|
<child link="RF_HIP"/>
|
|
<origin xyz="0.277 -0.116 0.0"/>
|
|
<axis xyz="1 0 0"/>
|
|
<limit command_effort="80" effort="80" lower="-9.42" upper="9.42" velocity="20"/>
|
|
<dynamics damping="0.0" friction="0.0"/>
|
|
</joint>
|
|
<link name="RF_THIGH">
|
|
<visual>
|
|
<origin rpy="0 0 0.0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="../meshes/anymal_thigh_r.dae" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
<!-- <material name="anymal_material"/> -->
|
|
</visual>
|
|
<collision>
|
|
<!-- KFE actuator -->
|
|
<origin rpy="1.57079632679 0 0" xyz="0.0 -0.069 -0.25"/>
|
|
<geometry>
|
|
<cylinder length="0.12" radius="0.06"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="-0.003897968082 -0.054226618537 -0.214583373795"/>
|
|
<mass value="1.634976467"/>
|
|
<inertia ixx="0.0120367944369" ixy="-6.762065206e-05" ixz="0.000287806340448" iyy="0.0120643637939" iyz="0.00140610131218" izz="0.00249422574881"/>
|
|
</inertial>
|
|
</link>
|
|
<!-- Thigh joint -->
|
|
<joint name="RF_HFE" type="revolute">
|
|
<parent link="RF_HIP"/>
|
|
<child link="RF_THIGH"/>
|
|
<origin xyz="0.0635 -0.041 0.0"/>
|
|
<axis xyz="0 1 0"/>
|
|
<limit command_effort="80" effort="80" lower="-9.42" upper="9.42" velocity="20"/>
|
|
<dynamics damping="0.0" friction="0.0"/>
|
|
</joint>
|
|
<link name="RF_SHANK">
|
|
<visual>
|
|
<origin rpy="0 0 0.0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="../meshes/anymal_shank_r.dae" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
<!-- <material name="anymal_material"/> -->
|
|
</visual>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0.030816858139 0.004617229294 0.000893125713"/>
|
|
<mass value="0.207204302"/>
|
|
<inertia ixx="0.0002104880248" ixy="5.6750980345e-05" ixz="1.0127699391e-05" iyy="0.000676270210023" iyz="8.22869024e-07" izz="0.000545032674924"/>
|
|
</inertial>
|
|
</link>
|
|
<!-- Shank joint -->
|
|
<joint name="RF_KFE" type="revolute">
|
|
<parent link="RF_THIGH"/>
|
|
<child link="RF_SHANK"/>
|
|
<origin xyz="0.0 -0.109 -0.25"/>
|
|
<axis xyz="0 1 0"/>
|
|
<limit command_effort="80" effort="80" lower="-9.42" upper="9.42" velocity="20"/>
|
|
<dynamics damping="0.0" friction="0.0"/>
|
|
</joint>
|
|
<!-- Shank to Adapter joint -->
|
|
<joint name="RF_SHANK_TO_ADAPTER" type="fixed">
|
|
<parent link="RF_SHANK"/>
|
|
<child link="RF_ADAPTER"/>
|
|
<origin rpy="-0.0 0.0 -0.0" xyz="0.1 0.02 0.0"/>
|
|
</joint>
|
|
<!-- Adapter link -->
|
|
<link name="RF_ADAPTER">
|
|
<visual>
|
|
<origin rpy="0 0 0.0" xyz="0 0 0.032"/>
|
|
<geometry>
|
|
<mesh filename="../meshes/anymal_foot.dae" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
<!-- <material name="anymal_material"/> -->
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 -0.160625"/>
|
|
<geometry>
|
|
<cylinder length="0.25" radius="0.015"/>
|
|
</geometry>
|
|
<!-- <material name="anymal_material"/> -->
|
|
</collision>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="-8.66e-10 -1.472e-09 -0.244345749188"/>
|
|
<mass value="0.140170767"/>
|
|
<inertia ixx="0.00159938741862" ixy="-9.32e-13" ixz="1.039e-11" iyy="0.00159938741932" iyz="1.7563e-11" izz="5.4423177329e-05"/>
|
|
</inertial>
|
|
</link>
|
|
<!-- Adapter to Foot joint -->
|
|
<joint name="RF_ADAPTER_TO_FOOT" type="fixed" dont_collapse="true">
|
|
<parent link="RF_ADAPTER"/>
|
|
<child link="RF_FOOT"/>
|
|
<origin rpy="-0.0 0.0 -0.0" xyz="0.0 -0.0 -0.32125"/>
|
|
</joint>
|
|
<!-- Foot link -->
|
|
<link name="RF_FOOT">
|
|
<collision>
|
|
<origin xyz="0 0 0.02325"/>
|
|
<geometry>
|
|
<sphere radius="0.031"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0 0 0.02325"/>
|
|
<mass value="0.05"/>
|
|
<inertia ixx="0.001" ixy="-2.63048e-07" ixz="6.815581e-06" iyy="0.001" iyz="-6.815583e-06" izz="8.319196e-06"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="LH_HIP">
|
|
<visual>
|
|
<origin rpy="0 0 -3.14159265359" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="../meshes/anymal_hip_r.dae" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
<!-- <material name="anymal_material"/> -->
|
|
</visual>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="-0.064516258147 -0.003787101702 -0.000152184388"/>
|
|
<mass value="1.42462064"/>
|
|
<inertia ixx="0.00243023349564" ixy="1.53023971e-05" ixz="2.1819095354e-05" iyy="0.00230257239103" iyz="2.6473021273e-05" izz="0.0019806759227"/>
|
|
</inertial>
|
|
</link>
|
|
<!-- Hip joint -->
|
|
<joint name="LH_HAA" type="revolute">
|
|
<parent link="base"/>
|
|
<child link="LH_HIP"/>
|
|
<origin xyz="-0.277 0.116 0.0"/>
|
|
<axis xyz="1 0 0"/>
|
|
<limit command_effort="80" current="10" effort="80" gear_velocity="10" lower="-9.42" upper="9.42" velocity="15"/>
|
|
<dynamics damping="0.0" friction="0.0"/>
|
|
</joint>
|
|
<link name="LH_THIGH">
|
|
<visual>
|
|
<origin rpy="0 0 -3.14159265359" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="../meshes/anymal_thigh_r.dae" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
<!-- <material name="anymal_material"/> -->
|
|
</visual>
|
|
<collision>
|
|
<!-- KFE actuator -->
|
|
<origin rpy="1.57079632679 0 0" xyz="0.0 0.069 -0.25"/>
|
|
<geometry>
|
|
<cylinder length="0.12" radius="0.06"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0.003897968082 0.054226618537 -0.214583373795"/>
|
|
<mass value="1.634976467"/>
|
|
<inertia ixx="0.0120367944369" ixy="-6.762065206e-05" ixz="-0.000287806340448" iyy="0.0120643637939" iyz="-0.00140610131218" izz="0.00249422574881"/>
|
|
</inertial>
|
|
</link>
|
|
<!-- Thigh joint -->
|
|
<joint name="LH_HFE" type="revolute">
|
|
<parent link="LH_HIP"/>
|
|
<child link="LH_THIGH"/>
|
|
<origin xyz="-0.0635 0.041 0.0"/>
|
|
<axis xyz="0 1 0"/>
|
|
<limit command_effort="80" effort="80" lower="-9.42" upper="9.42" velocity="20"/>
|
|
<dynamics damping="0.0" friction="0.0"/>
|
|
</joint>
|
|
<link name="LH_SHANK">
|
|
<visual>
|
|
<origin rpy="0 0 -3.14159265359" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="../meshes/anymal_shank_r.dae" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
<!-- <material name="anymal_material"/> -->
|
|
</visual>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="-0.030816858139 -0.004617229294 0.000893125713"/>
|
|
<mass value="0.207204302"/>
|
|
<inertia ixx="0.0002104880248" ixy="5.6750980345e-05" ixz="-1.0127699391e-05" iyy="0.000676270210023" iyz="-8.22869024e-07" izz="0.000545032674924"/>
|
|
</inertial>
|
|
</link>
|
|
<!-- Shank joint -->
|
|
<joint name="LH_KFE" type="revolute">
|
|
<parent link="LH_THIGH"/>
|
|
<child link="LH_SHANK"/>
|
|
<origin xyz="-0.0 0.109 -0.25"/>
|
|
<axis xyz="0 1 0"/>
|
|
<limit command_effort="80" effort="80" lower="-9.42" upper="9.42" velocity="20"/>
|
|
<dynamics damping="0.0" friction="0.0"/>
|
|
</joint>
|
|
<!-- Shank to Adapter joint -->
|
|
<joint name="LH_SHANK_TO_ADAPTER" type="fixed">
|
|
<parent link="LH_SHANK"/>
|
|
<child link="LH_ADAPTER"/>
|
|
<origin rpy="0.0 -0.0 -0.0" xyz="-0.1 -0.02 0.0"/>
|
|
</joint>
|
|
<!-- Adapter link -->
|
|
<link name="LH_ADAPTER">
|
|
<visual>
|
|
<origin rpy="0 0 -3.14159265359" xyz="0 0 0.032"/>
|
|
<geometry>
|
|
<mesh filename="../meshes/anymal_foot.dae" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
<!-- <material name="anymal_material"/> -->
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 -0.160625"/>
|
|
<geometry>
|
|
<cylinder length="0.25" radius="0.015"/>
|
|
</geometry>
|
|
<!-- <material name="anymal_material"/> -->
|
|
</collision>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="-8.66e-10 -1.472e-09 -0.244345749188"/>
|
|
<mass value="0.140170767"/>
|
|
<inertia ixx="0.00159938741862" ixy="-9.32e-13" ixz="1.039e-11" iyy="0.00159938741932" iyz="1.7563e-11" izz="5.4423177329e-05"/>
|
|
</inertial>
|
|
</link>
|
|
<!-- Adapter to Foot joint -->
|
|
<joint name="LH_ADAPTER_TO_FOOT" type="fixed" dont_collapse="true">
|
|
<parent link="LH_ADAPTER"/>
|
|
<child link="LH_FOOT"/>
|
|
<origin rpy="0.0 -0.0 -0.0" xyz="-0.0 0.0 -0.32125"/>
|
|
</joint>
|
|
<!-- Foot link -->
|
|
<link name="LH_FOOT">
|
|
<collision>
|
|
<origin xyz="0 0 0.02325"/>
|
|
<geometry>
|
|
<sphere radius="0.031"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0 0 0.02325"/>
|
|
<mass value="0.05"/>
|
|
<inertia ixx="0.001" ixy="-2.63048e-07" ixz="6.815581e-06" iyy="0.001" iyz="-6.815583e-06" izz="8.319196e-06"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="RH_HIP">
|
|
<visual>
|
|
<origin rpy="0 0 -3.14159265359" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="../meshes/anymal_hip_l.dae" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
<!-- <material name="anymal_material"/> -->
|
|
</visual>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="-0.064516258147 0.003787101702 -0.000152184388"/>
|
|
<mass value="1.42462064"/>
|
|
<inertia ixx="0.00243023349564" ixy="-1.53023971e-05" ixz="2.1819095354e-05" iyy="0.00230257239103" iyz="-2.6473021273e-05" izz="0.0019806759227"/>
|
|
</inertial>
|
|
</link>
|
|
<!-- Hip joint -->
|
|
<joint name="RH_HAA" type="revolute">
|
|
<parent link="base"/>
|
|
<child link="RH_HIP"/>
|
|
<origin xyz="-0.277 -0.116 0.0"/>
|
|
<axis xyz="1 0 0"/>
|
|
<limit command_effort="80" current="10" effort="80" gear_velocity="10" lower="-9.42" upper="9.42" velocity="15"/>
|
|
<dynamics damping="0.0" friction="0.0"/>
|
|
</joint>
|
|
<link name="RH_THIGH">
|
|
<visual>
|
|
<origin rpy="0 0 -3.14159265359" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="../meshes/anymal_thigh_l.dae" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
<!-- <material name="anymal_material"/> -->
|
|
</visual>
|
|
<collision>
|
|
<!-- KFE actuator -->
|
|
<origin rpy="1.57079632679 0 0" xyz="0.0 -0.069 -0.25"/>
|
|
<geometry>
|
|
<cylinder length="0.12" radius="0.06"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0.003897968082 -0.054226618537 -0.214583373795"/>
|
|
<mass value="1.634976467"/>
|
|
<inertia ixx="0.0120367944369" ixy="6.762065206e-05" ixz="-0.000287806340448" iyy="0.0120643637939" iyz="0.00140610131218" izz="0.00249422574881"/>
|
|
</inertial>
|
|
</link>
|
|
<!-- Thigh joint -->
|
|
<joint name="RH_HFE" type="revolute">
|
|
<parent link="RH_HIP"/>
|
|
<child link="RH_THIGH"/>
|
|
<origin xyz="-0.0635 -0.041 0.0"/>
|
|
<axis xyz="0 1 0"/>
|
|
<limit command_effort="80" effort="80" lower="-9.42" upper="9.42" velocity="20"/>
|
|
<dynamics damping="0.0" friction="0.0"/>
|
|
</joint>
|
|
<link name="RH_SHANK">
|
|
<visual>
|
|
<origin rpy="0 0 -3.14159265359" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="../meshes/anymal_shank_l.dae" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
<!-- <material name="anymal_material"/> -->
|
|
</visual>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="-0.030816858139 0.004617229294 0.000893125713"/>
|
|
<mass value="0.207204302"/>
|
|
<inertia ixx="0.0002104880248" ixy="-5.6750980345e-05" ixz="-1.0127699391e-05" iyy="0.000676270210023" iyz="8.22869024e-07" izz="0.000545032674924"/>
|
|
</inertial>
|
|
</link>
|
|
<!-- Shank joint -->
|
|
<joint name="RH_KFE" type="revolute">
|
|
<parent link="RH_THIGH"/>
|
|
<child link="RH_SHANK"/>
|
|
<origin xyz="-0.0 -0.109 -0.25"/>
|
|
<axis xyz="0 1 0"/>
|
|
<limit command_effort="80" effort="80" lower="-9.42" upper="9.42" velocity="20"/>
|
|
<dynamics damping="0.0" friction="0.0"/>
|
|
</joint>
|
|
<!-- Shank to Adapter joint -->
|
|
<joint name="RH_SHANK_TO_ADAPTER" type="fixed">
|
|
<parent link="RH_SHANK"/>
|
|
<child link="RH_ADAPTER"/>
|
|
<origin rpy="-0.0 -0.0 0.0" xyz="-0.1 0.02 0.0"/>
|
|
</joint>
|
|
<!-- Adapter link -->
|
|
<link name="RH_ADAPTER">
|
|
<visual>
|
|
<origin rpy="0 0 -3.14159265359" xyz="0 0 0.032"/>
|
|
<geometry>
|
|
<mesh filename="../meshes/anymal_foot.dae" scale="0.001 0.001 0.001"/>
|
|
</geometry>
|
|
<!-- <material name="anymal_material"/> -->
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 -0.160625"/>
|
|
<geometry>
|
|
<cylinder length="0.25" radius="0.015"/>
|
|
</geometry>
|
|
<!-- <material name="anymal_material"/> -->
|
|
</collision>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="-8.66e-10 -1.472e-09 -0.244345749188"/>
|
|
<mass value="0.140170767"/>
|
|
<inertia ixx="0.00159938741862" ixy="-9.32e-13" ixz="1.039e-11" iyy="0.00159938741932" iyz="1.7563e-11" izz="5.4423177329e-05"/>
|
|
</inertial>
|
|
</link>
|
|
<!-- Adapter to Foot joint -->
|
|
<joint name="RH_ADAPTER_TO_FOOT" type="fixed" dont_collapse="true">
|
|
<parent link="RH_ADAPTER"/>
|
|
<child link="RH_FOOT"/>
|
|
<origin rpy="-0.0 -0.0 0.0" xyz="-0.0 -0.0 -0.32125"/>
|
|
</joint>
|
|
<!-- Foot link -->
|
|
<link name="RH_FOOT">
|
|
<collision>
|
|
<origin xyz="0 0 0.02325"/>
|
|
<geometry>
|
|
<sphere radius="0.031"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<origin rpy="0 0 0" xyz="0 0 0.02325"/>
|
|
<mass value="0.05"/>
|
|
<inertia ixx="0.001" ixy="-2.63048e-07" ixz="6.815581e-06" iyy="0.001" iyz="-6.815583e-06" izz="8.319196e-06"/>
|
|
</inertial>
|
|
</link>
|
|
</robot>
|
|
|