Unverified Commit d5a11c47 authored by Carlos Mastalli's avatar Carlos Mastalli Committed by GitHub
Browse files

Merge pull request #102 from wxmerkt/topic/add-unitree-a1

Add Unitree A1 quadruped
parents 48a246c2 14ee1689
Pipeline #15785 passed with stage
in 1 minute and 43 seconds
......@@ -99,6 +99,15 @@ class RobotLoader(object):
return self.robot.q0
class A1Loader(RobotLoader):
path = 'a1_description'
urdf_filename = "a1.urdf"
urdf_subpath = "urdf"
srdf_filename = "a1.srdf"
ref_posture = "standing"
free_flyer = True
class ANYmalLoader(RobotLoader):
path = 'anymal_b_simple_description'
urdf_filename = "anymal.urdf"
......@@ -492,6 +501,7 @@ def loadIris():
ROBOTS = {
'a1': A1Loader,
'anymal': ANYmalLoader,
'anymal_kinova': ANYmalKinovaLoader,
'baxter': BaxterLoader,
......
# Unitree A1
upstream: https://github.com/unitreerobotics/unitree_ros/tree/master/robots/a1_description
license: MPL-2.0
### Modifications:
- Removed Gazebo and transmission tags
- Added SRDF
This source diff could not be displayed because it is too large. You can view the blob instead.
This source diff could not be displayed because it is too large. You can view the blob instead.
This source diff could not be displayed because it is too large. You can view the blob instead.
This source diff could not be displayed because it is too large. You can view the blob instead.
This source diff could not be displayed because it is too large. You can view the blob instead.
<?xml version="1.0" ?>
<robot name="a1">
<group name="whole_body">
<joint name="root_joint"/>
<joint name="FL_hip_joint"/>
<joint name="FL_thigh_joint"/>
<joint name="FL_calf_joint"/>
<joint name="RL_hip_joint"/>
<joint name="RL_thigh_joint"/>
<joint name="RL_calf_joint"/>
<joint name="FR_hip_joint"/>
<joint name="FR_thigh_joint"/>
<joint name="FR_calf_joint"/>
<joint name="RR_hip_joint"/>
<joint name="RR_thigh_joint"/>
<joint name="RR_calf_joint"/>
</group>
<virtual_joint name="root_joint" type="floating" parent_frame="world_frame" child_link="base"/>
<group name="lf_leg">
<joint name="FL_hip_joint"/>
<joint name="FL_thigh_joint"/>
<joint name="FL_calf_joint"/>
<chain base_link="base" tip_link="FL_foot"/>
</group>
<group name="lh_leg">
<joint name="RL_hip_joint"/>
<joint name="RL_thigh_joint"/>
<joint name="RL_calf_joint"/>
<chain base_link="base" tip_link="RL_foot"/>
</group>
<group name="rf_leg">
<joint name="FR_hip_joint"/>
<joint name="FR_thigh_joint"/>
<joint name="FR_calf_joint"/>
<chain base_link="base" tip_link="FR_foot"/>
</group>
<group name="rh_leg">
<joint name="RR_hip_joint"/>
<joint name="RR_thigh_joint"/>
<joint name="RR_calf_joint"/>
<chain base_link="base" tip_link="RR_foot"/>
</group>
<group name="all_legs">
<group name="lf_leg"/>
<group name="rf_leg"/>
<group name="lh_leg"/>
<group name="rh_leg"/>
</group>
<group name="r_legs">
<group name="rf_leg"/>
<group name="rh_leg"/>
</group>
<group name="l_legs">
<group name="lf_leg"/>
<group name="lh_leg"/>
</group>
<group name="f_legs">
<group name="lf_leg"/>
<group name="rf_leg"/>
</group>
<group name="h_legs">
<group name="lh_leg"/>
<group name="rh_leg"/>
</group>
<group name="ld_legs">
<group name="lf_leg"/>
<group name="rh_leg"/>
</group>
<group name="rd_legs">
<group name="rf_leg"/>
<group name="lh_leg"/>
</group>
<end_effector name="lf_foot" parent_link="FL_foot" group="lf_leg"/>
<end_effector name="rf_foot" parent_link="FR_foot" group="rf_leg"/>
<end_effector name="lh_foot" parent_link="RL_foot" group="lh_leg"/>
<end_effector name="rh_foot" parent_link="RR_foot" group="rh_leg"/>
<group_state name="standing" group="whole_body">
<joint name="root_joint" value="0. 0. 0.26 0. 0. 0. 1."/>
<joint name="FL_hip_joint" value="0."/>
<joint name="FL_thigh_joint" value="0.8"/>
<joint name="FL_calf_joint" value="-1.81"/>
<joint name="FR_hip_joint" value="0."/>
<joint name="FR_thigh_joint" value="0.8"/>
<joint name="FR_calf_joint" value="-1.81"/>
<joint name="RL_hip_joint" value="0."/>
<joint name="RL_thigh_joint" value="0.8"/>
<joint name="RL_calf_joint" value="-1.81"/>
<joint name="RR_hip_joint" value="0."/>
<joint name="RR_thigh_joint" value="0.8"/>
<joint name="RR_calf_joint" value="-1.81"/>
</group_state>
<disable_collisions link1="FL_calf" link2="FL_foot" reason="Adjacent"/>
<disable_collisions link1="FL_calf" link2="FL_hip" reason="Never"/>
<disable_collisions link1="FL_calf" link2="FL_thigh" reason="Adjacent"/>
<disable_collisions link1="FL_calf" link2="FL_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_calf" link2="FR_hip" reason="Never"/>
<disable_collisions link1="FL_calf" link2="FR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_calf" link2="RL_hip" reason="Never"/>
<disable_collisions link1="FL_calf" link2="RR_hip" reason="Never"/>
<disable_collisions link1="FL_calf" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_calf" link2="imu_link" reason="Never"/>
<disable_collisions link1="FL_calf" link2="trunk" reason="Never"/>
<disable_collisions link1="FL_foot" link2="FL_hip" reason="Never"/>
<disable_collisions link1="FL_foot" link2="FL_thigh" reason="Never"/>
<disable_collisions link1="FL_foot" link2="FL_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_foot" link2="FR_hip" reason="Never"/>
<disable_collisions link1="FL_foot" link2="FR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_foot" link2="RL_hip" reason="Never"/>
<disable_collisions link1="FL_foot" link2="RR_hip" reason="Never"/>
<disable_collisions link1="FL_foot" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_foot" link2="imu_link" reason="Never"/>
<disable_collisions link1="FL_hip" link2="FL_thigh" reason="Adjacent"/>
<disable_collisions link1="FL_hip" link2="FL_thigh_shoulder" reason="Adjacent"/>
<disable_collisions link1="FL_hip" link2="FR_calf" reason="Never"/>
<disable_collisions link1="FL_hip" link2="FR_foot" reason="Never"/>
<disable_collisions link1="FL_hip" link2="FR_hip" reason="Never"/>
<disable_collisions link1="FL_hip" link2="FR_thigh" reason="Never"/>
<disable_collisions link1="FL_hip" link2="FR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_hip" link2="RL_calf" reason="Never"/>
<disable_collisions link1="FL_hip" link2="RL_foot" reason="Never"/>
<disable_collisions link1="FL_hip" link2="RL_hip" reason="Never"/>
<disable_collisions link1="FL_hip" link2="RL_thigh" reason="Never"/>
<disable_collisions link1="FL_hip" link2="RL_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_hip" link2="RR_calf" reason="Never"/>
<disable_collisions link1="FL_hip" link2="RR_foot" reason="Never"/>
<disable_collisions link1="FL_hip" link2="RR_hip" reason="Never"/>
<disable_collisions link1="FL_hip" link2="RR_thigh" reason="Never"/>
<disable_collisions link1="FL_hip" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_hip" link2="imu_link" reason="Never"/>
<disable_collisions link1="FL_hip" link2="trunk" reason="Adjacent"/>
<disable_collisions link1="FL_thigh" link2="FL_thigh_shoulder" reason="Default"/>
<disable_collisions link1="FL_thigh" link2="FR_hip" reason="Never"/>
<disable_collisions link1="FL_thigh" link2="FR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_thigh" link2="RL_hip" reason="Never"/>
<disable_collisions link1="FL_thigh" link2="RL_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_thigh" link2="RR_hip" reason="Never"/>
<disable_collisions link1="FL_thigh" link2="RR_thigh" reason="Never"/>
<disable_collisions link1="FL_thigh" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_thigh" link2="imu_link" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="FR_calf" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="FR_foot" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="FR_hip" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="FR_thigh" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="FR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="RL_hip" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="RL_thigh" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="RL_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="RR_calf" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="RR_foot" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="RR_hip" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="RR_thigh" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="imu_link" reason="Never"/>
<disable_collisions link1="FL_thigh_shoulder" link2="trunk" reason="Never"/>
<disable_collisions link1="FR_calf" link2="FR_foot" reason="Adjacent"/>
<disable_collisions link1="FR_calf" link2="FR_hip" reason="Never"/>
<disable_collisions link1="FR_calf" link2="FR_thigh" reason="Adjacent"/>
<disable_collisions link1="FR_calf" link2="FR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FR_calf" link2="RL_hip" reason="Never"/>
<disable_collisions link1="FR_calf" link2="RL_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FR_calf" link2="RR_hip" reason="Never"/>
<disable_collisions link1="FR_calf" link2="imu_link" reason="Never"/>
<disable_collisions link1="FR_calf" link2="trunk" reason="Never"/>
<disable_collisions link1="FR_foot" link2="FR_hip" reason="Never"/>
<disable_collisions link1="FR_foot" link2="FR_thigh" reason="Never"/>
<disable_collisions link1="FR_foot" link2="FR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FR_foot" link2="RL_hip" reason="Never"/>
<disable_collisions link1="FR_foot" link2="RL_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FR_foot" link2="RR_hip" reason="Never"/>
<disable_collisions link1="FR_foot" link2="imu_link" reason="Never"/>
<disable_collisions link1="FR_hip" link2="FR_thigh" reason="Adjacent"/>
<disable_collisions link1="FR_hip" link2="FR_thigh_shoulder" reason="Adjacent"/>
<disable_collisions link1="FR_hip" link2="RL_calf" reason="Never"/>
<disable_collisions link1="FR_hip" link2="RL_foot" reason="Never"/>
<disable_collisions link1="FR_hip" link2="RL_hip" reason="Never"/>
<disable_collisions link1="FR_hip" link2="RL_thigh" reason="Never"/>
<disable_collisions link1="FR_hip" link2="RL_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FR_hip" link2="RR_calf" reason="Never"/>
<disable_collisions link1="FR_hip" link2="RR_foot" reason="Never"/>
<disable_collisions link1="FR_hip" link2="RR_hip" reason="Never"/>
<disable_collisions link1="FR_hip" link2="RR_thigh" reason="Never"/>
<disable_collisions link1="FR_hip" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FR_hip" link2="imu_link" reason="Never"/>
<disable_collisions link1="FR_hip" link2="trunk" reason="Adjacent"/>
<disable_collisions link1="FR_thigh" link2="FR_thigh_shoulder" reason="Default"/>
<disable_collisions link1="FR_thigh" link2="RL_calf" reason="Never"/>
<disable_collisions link1="FR_thigh" link2="RL_hip" reason="Never"/>
<disable_collisions link1="FR_thigh" link2="RL_thigh" reason="Never"/>
<disable_collisions link1="FR_thigh" link2="RL_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FR_thigh" link2="RR_hip" reason="Never"/>
<disable_collisions link1="FR_thigh" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FR_thigh" link2="imu_link" reason="Never"/>
<disable_collisions link1="FR_thigh_shoulder" link2="RL_calf" reason="Never"/>
<disable_collisions link1="FR_thigh_shoulder" link2="RL_foot" reason="Never"/>
<disable_collisions link1="FR_thigh_shoulder" link2="RL_hip" reason="Never"/>
<disable_collisions link1="FR_thigh_shoulder" link2="RL_thigh" reason="Never"/>
<disable_collisions link1="FR_thigh_shoulder" link2="RL_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FR_thigh_shoulder" link2="RR_hip" reason="Never"/>
<disable_collisions link1="FR_thigh_shoulder" link2="RR_thigh" reason="Never"/>
<disable_collisions link1="FR_thigh_shoulder" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="FR_thigh_shoulder" link2="imu_link" reason="Never"/>
<disable_collisions link1="FR_thigh_shoulder" link2="trunk" reason="Never"/>
<disable_collisions link1="RL_calf" link2="RL_foot" reason="Adjacent"/>
<disable_collisions link1="RL_calf" link2="RL_hip" reason="Never"/>
<disable_collisions link1="RL_calf" link2="RL_thigh" reason="Adjacent"/>
<disable_collisions link1="RL_calf" link2="RL_thigh_shoulder" reason="Never"/>
<disable_collisions link1="RL_calf" link2="RR_hip" reason="Never"/>
<disable_collisions link1="RL_calf" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="RL_calf" link2="imu_link" reason="Never"/>
<disable_collisions link1="RL_calf" link2="trunk" reason="Never"/>
<disable_collisions link1="RL_foot" link2="RL_hip" reason="Never"/>
<disable_collisions link1="RL_foot" link2="RL_thigh" reason="Never"/>
<disable_collisions link1="RL_foot" link2="RL_thigh_shoulder" reason="Never"/>
<disable_collisions link1="RL_foot" link2="RR_hip" reason="Never"/>
<disable_collisions link1="RL_foot" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="RL_foot" link2="imu_link" reason="Never"/>
<disable_collisions link1="RL_hip" link2="RL_thigh" reason="Adjacent"/>
<disable_collisions link1="RL_hip" link2="RL_thigh_shoulder" reason="Adjacent"/>
<disable_collisions link1="RL_hip" link2="RR_calf" reason="Never"/>
<disable_collisions link1="RL_hip" link2="RR_foot" reason="Never"/>
<disable_collisions link1="RL_hip" link2="RR_hip" reason="Never"/>
<disable_collisions link1="RL_hip" link2="RR_thigh" reason="Never"/>
<disable_collisions link1="RL_hip" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="RL_hip" link2="imu_link" reason="Never"/>
<disable_collisions link1="RL_hip" link2="trunk" reason="Adjacent"/>
<disable_collisions link1="RL_thigh" link2="RL_thigh_shoulder" reason="Default"/>
<disable_collisions link1="RL_thigh" link2="RR_hip" reason="Never"/>
<disable_collisions link1="RL_thigh" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="RL_thigh" link2="imu_link" reason="Never"/>
<disable_collisions link1="RL_thigh_shoulder" link2="RR_calf" reason="Never"/>
<disable_collisions link1="RL_thigh_shoulder" link2="RR_foot" reason="Never"/>
<disable_collisions link1="RL_thigh_shoulder" link2="RR_hip" reason="Never"/>
<disable_collisions link1="RL_thigh_shoulder" link2="RR_thigh" reason="Never"/>
<disable_collisions link1="RL_thigh_shoulder" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="RL_thigh_shoulder" link2="imu_link" reason="Never"/>
<disable_collisions link1="RL_thigh_shoulder" link2="trunk" reason="Never"/>
<disable_collisions link1="RR_calf" link2="RR_foot" reason="Adjacent"/>
<disable_collisions link1="RR_calf" link2="RR_hip" reason="Never"/>
<disable_collisions link1="RR_calf" link2="RR_thigh" reason="Adjacent"/>
<disable_collisions link1="RR_calf" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="RR_calf" link2="imu_link" reason="Never"/>
<disable_collisions link1="RR_calf" link2="trunk" reason="Never"/>
<disable_collisions link1="RR_foot" link2="RR_hip" reason="Never"/>
<disable_collisions link1="RR_foot" link2="RR_thigh" reason="Never"/>
<disable_collisions link1="RR_foot" link2="RR_thigh_shoulder" reason="Never"/>
<disable_collisions link1="RR_foot" link2="imu_link" reason="Never"/>
<disable_collisions link1="RR_hip" link2="RR_thigh" reason="Adjacent"/>
<disable_collisions link1="RR_hip" link2="RR_thigh_shoulder" reason="Adjacent"/>
<disable_collisions link1="RR_hip" link2="imu_link" reason="Never"/>
<disable_collisions link1="RR_hip" link2="trunk" reason="Adjacent"/>
<disable_collisions link1="RR_thigh" link2="RR_thigh_shoulder" reason="Default"/>
<disable_collisions link1="RR_thigh" link2="imu_link" reason="Never"/>
<disable_collisions link1="RR_thigh_shoulder" link2="imu_link" reason="Never"/>
<disable_collisions link1="RR_thigh_shoulder" link2="trunk" reason="Never"/>
<disable_collisions link1="imu_link" link2="trunk" reason="Adjacent"/>
</robot>
<?xml version="1.0" ?>
<!-- ==================================================================================================== -->
<!-- | This document was autogenerated by xacro, then had the Gazebo and transmission tags removed | -->
<!-- ==================================================================================================== -->
<robot name="a1">
<material name="black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>
<material name="blue">
<color rgba="0.0 0.0 0.8 1.0"/>
</material>
<material name="green">
<color rgba="0.0 0.8 0.0 1.0"/>
</material>
<material name="grey">
<color rgba="0.2 0.2 0.2 1.0"/>
</material>
<material name="silver">
<color rgba="0.9137254901960784 0.9137254901960784 0.8470588235294118 1.0"/>
</material>
<material name="orange">
<color rgba="1.0 0.4235294117647059 0.0392156862745098 1.0"/>
</material>
<material name="brown">
<color rgba="0.8705882352941177 0.8117647058823529 0.7647058823529411 1.0"/>
</material>
<material name="red">
<color rgba="0.8 0.0 0.0 1.0"/>
</material>
<material name="white">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
<link name="base">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.001 0.001 0.001"/>
</geometry>
</visual>
</link>
<joint name="floating_base" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="base"/>
<child link="trunk"/>
</joint>
<link name="trunk">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/a1_description/meshes/trunk.dae" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.267 0.194 0.114"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0041 -0.0005"/>
<mass value="6.0"/>
<inertia ixx="0.0158533" ixy="-3.66e-05" ixz="-6.11e-05" iyy="0.0377999" iyz="-2.75e-05" izz="0.0456542"/>
</inertial>
</link>
<joint name="imu_joint" type="fixed">
<parent link="trunk"/>
<child link="imu_link"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</joint>
<link name="imu_link">
<inertial>
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.001 0.001 0.001"/>
</geometry>
<material name="red"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size=".001 .001 .001"/>
</geometry>
</collision>
</link>
<joint name="FR_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="0.1805 -0.047 0"/>
<parent link="trunk"/>
<child link="FR_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="33.5" lower="-0.8028514559173915" upper="0.8028514559173915" velocity="21"/>
</joint>
<link name="FR_hip">
<visual>
<origin rpy="3.141592653589793 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/a1_description/meshes/hip.dae" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.04" radius="0.046"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.003311 -0.000635 3.1e-05"/>
<mass value="0.696"/>
<inertia ixx="0.000469246" ixy="9.409e-06" ixz="-3.42e-07" iyy="0.00080749" iyz="4.66e-07" izz="0.000552929"/>
</inertial>
</link>
<joint name="FR_hip_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 -0.081 0"/>
<parent link="FR_hip"/>
<child link="FR_thigh_shoulder"/>
</joint>
<!-- this link is only for collision -->
<link name="FR_thigh_shoulder">
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.032" radius="0.041"/>
</geometry>
</collision>
</link>
<joint name="FR_thigh_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 -0.0838 0"/>
<parent link="FR_hip"/>
<child link="FR_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="33.5" lower="-1.0471975511965976" upper="4.1887902047863905" velocity="21"/>
</joint>
<link name="FR_thigh">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/a1_description/meshes/thigh_mirror.dae" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1"/>
<geometry>
<box size="0.2 0.0245 0.034"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.003237 0.022327 -0.027326"/>
<mass value="1.013"/>
<inertia ixx="0.005529065" ixy="-4.825e-06" ixz="0.000343869" iyy="0.005139339" iyz="-2.2448e-05" izz="0.001367788"/>
</inertial>
</link>
<joint name="FR_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
<parent link="FR_thigh"/>
<child link="FR_calf"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="33.5" lower="-2.6965336943312392" upper="-0.9162978572970231" velocity="21"/>
</joint>
<link name="FR_calf">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/a1_description/meshes/calf.dae" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1"/>
<geometry>
<box size="0.2 0.016 0.016"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.006435 0.0 -0.107388"/>
<mass value="0.166"/>
<inertia ixx="0.002997972" ixy="0.0" ixz="-0.000141163" iyy="0.003014022" iyz="0.0" izz="3.2426e-05"/>
</inertial>
</link>
<joint name="FR_foot_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
<parent link="FR_calf"/>
<child link="FR_foot"/>
</joint>
<link name="FR_foot">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.01"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.02"/>
</geometry>
</collision>
<inertial>
<mass value="0.06"/>
<inertia ixx="9.600000000000001e-06" ixy="0.0" ixz="0.0" iyy="9.600000000000001e-06" iyz="0.0" izz="9.600000000000001e-06"/>
</inertial>
</link>
<joint name="FL_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="0.1805 0.047 0"/>
<parent link="trunk"/>
<child link="FL_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="33.5" lower="-0.8028514559173915" upper="0.8028514559173915" velocity="21"/>
</joint>
<link name="FL_hip">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/a1_description/meshes/hip.dae" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.04" radius="0.046"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.003311 0.000635 3.1e-05"/>
<mass value="0.696"/>
<inertia ixx="0.000469246" ixy="-9.409e-06" ixz="-3.42e-07" iyy="0.00080749" iyz="-4.66e-07" izz="0.000552929"/>
</inertial>
</link>
<joint name="FL_hip_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0.081 0"/>
<parent link="FL_hip"/>
<child link="FL_thigh_shoulder"/>
</joint>
<!-- this link is only for collision -->
<link name="FL_thigh_shoulder">
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.032" radius="0.041"/>
</geometry>
</collision>
</link>
<joint name="FL_thigh_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0.0838 0"/>
<parent link="FL_hip"/>
<child link="FL_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="33.5" lower="-1.0471975511965976" upper="4.1887902047863905" velocity="21"/>
</joint>
<link name="FL_thigh">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/a1_description/meshes/thigh.dae" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.1"/>
<geometry>
<box size="0.2 0.0245 0.034"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.003237 -0.022327 -0.027326"/>
<mass value="1.013"/>
<inertia ixx="0.005529065" ixy="4.825e-06" ixz="0.000343869" iyy="0.005139339" iyz="2.2448e-05" izz="0.001367788"/>
</inertial>
</link>
<joint name="FL_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.2"/>
<parent link="FL_thigh"/>