Go2Py/locomotion/src/robots/b1_description/urdf/b1_description_mj.urdf

965 lines
32 KiB
XML

<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from robot.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="b1_description">
<mujoco>
<compiler
meshdir="../meshes/"
discardvisual="false"
/>
</mujoco>
<link name="world"/>
<joint name="floating_base" type="floating">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="world"/>
<child link="base"/>
</joint>
<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>
<!-- Rotor related joint and link is only for demonstrate location. -->
<!-- Actually, the rotor will rotate and the joint is not fixed. Reduction ratio should be considered. -->
<!-- Debug mode will hung up the robot, use "true" or "false" to switch it. -->
<!-- <xacro:if value="$(arg DEBUG)">
<link name="world"/>
<joint name="base_static_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="world"/>
<child link="base"/>
</joint>
</xacro:if> -->
<link name="base">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://b1_description/meshes/trunk.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.647 0.3 0.15"/>
</geometry>
</collision>
<!-- <collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://b1_description/meshes/trunk.stl" scale="1 1 1"/>
</geometry>
</collision> -->
<inertial>
<origin rpy="0 0 0" xyz="0.008987 0.002243 0.003013"/>
<mass value="25"/>
<inertia ixx="0.183142146" ixy="-0.001379002" ixz="-0.027956055" iyy="0.756327752" iyz="0.000193774" izz="0.783777558"/>
</inertial>
</link>
<joint name="imu_joint" type="fixed">
<parent link="base"/>
<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.000001" 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.3455 -0.072 0"/>
<parent link="base"/>
<child link="FR_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="91.0035" lower="-0.75" upper="0.75" velocity="19.69"/>
</joint>
<joint name="FR_hip_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.1955 -0.072 0"/>
<parent link="base"/>
<child link="FR_hip_rotor"/>
</joint>
<link name="FR_hip">
<visual>
<origin rpy="3.141592653589793 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://b1_description/meshes/hip.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 -0.12675 0"/>
<geometry>
<cylinder length="0.04" radius="0.09"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.020298 -0.009758 0.000109"/>
<mass value="2.1"/>
<inertia ixx="0.00406608" ixy="0.000288071" ixz="-4.371e-06" iyy="0.008775259" iyz="-1.811e-06" izz="0.006060348"/>
</inertial>
</link>
<link name="FR_hip_rotor">
<visual>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.199"/>
<inertia ixx="0.00039249" ixy="0.0" ixz="0.0" iyy="0.000219397" iyz="0.0" izz="0.000219397"/>
</inertial>
</link>
<joint name="FR_thigh_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 -0.12675 0"/>
<parent link="FR_hip"/>
<child link="FR_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="93.33" lower="-1.0" upper="3.5" velocity="23.32"/>
</joint>
<joint name="FR_thigh_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.0 -0.00935 0"/>
<parent link="FR_hip"/>
<child link="FR_thigh_rotor"/>
</joint>
<link name="FR_thigh">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://b1_description/meshes/thigh_mirror.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.175"/>
<geometry>
<box size="0.35 0.05 0.08"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.000235 0.028704 -0.054169"/>
<mass value="3.934"/>
<inertia ixx="0.044459086" ixy="-0.000128738" ixz="-0.002343913" iyy="0.046023457" iyz="-0.006032996" izz="0.008696078"/>
</inertial>
</link>
<link name="FR_thigh_rotor">
<visual>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.266"/>
<inertia ixx="0.000485657" ixy="0.0" ixz="0.0" iyy="0.00091885" iyz="0.0" izz="0.000485657"/>
</inertial>
</link>
<joint name="FR_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.35"/>
<parent link="FR_thigh"/>
<child link="FR_calf"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="140" lower="-2.6" upper="-0.6" velocity="15.55"/>
</joint>
<joint name="FR_calf_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.0 0.0519 0"/>
<parent link="FR_thigh"/>
<child link="FR_calf_rotor"/>
</joint>
<link name="FR_calf">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://b1_description/meshes/calf.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.175"/>
<geometry>
<box size="0.35 0.04 0.05"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.005237 0.0 -0.202805"/>
<mass value="0.857"/>
<inertia ixx="0.015011003" ixy="5.2e-08" ixz="0.000250042" iyy="0.015159462" iyz="4.61e-07" izz="0.000375749"/>
</inertial>
</link>
<link name="FR_calf_rotor">
<visual>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.266"/>
<inertia ixx="0.000485657" ixy="0.0" ixz="0.0" iyy="0.00091885" iyz="0.0" izz="0.000485657"/>
</inertial>
</link>
<joint name="FR_foot_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.35"/>
<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.03"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.04"/>
</geometry>
</collision>
<inertial>
<mass value="0.05"/>
<inertia ixx="3.2000000000000005e-05" ixy="0.0" ixz="0.0" iyy="3.2000000000000005e-05" iyz="0.0" izz="3.2000000000000005e-05"/>
</inertial>
</link>
<transmission name="FR_hip_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FR_hip_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FR_hip_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="FR_thigh_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FR_thigh_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FR_thigh_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="FR_calf_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FR_calf_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FR_calf_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="FL_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="0.3455 0.072 0"/>
<parent link="base"/>
<child link="FL_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="91.0035" lower="-0.75" upper="0.75" velocity="19.69"/>
</joint>
<joint name="FL_hip_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.1955 0.072 0"/>
<parent link="base"/>
<child link="FL_hip_rotor"/>
</joint>
<link name="FL_hip">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://b1_description/meshes/hip.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0.12675 0"/>
<geometry>
<cylinder length="0.04" radius="0.09"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.020298 0.009758 0.000109"/>
<mass value="2.1"/>
<inertia ixx="0.00406608" ixy="-0.000288071" ixz="-4.371e-06" iyy="0.008775259" iyz="1.811e-06" izz="0.006060348"/>
</inertial>
</link>
<link name="FL_hip_rotor">
<visual>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.199"/>
<inertia ixx="0.00039249" ixy="0.0" ixz="0.0" iyy="0.000219397" iyz="0.0" izz="0.000219397"/>
</inertial>
</link>
<joint name="FL_thigh_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0.12675 0"/>
<parent link="FL_hip"/>
<child link="FL_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="93.33" lower="-1.0" upper="3.5" velocity="23.32"/>
</joint>
<joint name="FL_thigh_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.0 0.00935 0"/>
<parent link="FL_hip"/>
<child link="FL_thigh_rotor"/>
</joint>
<link name="FL_thigh">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://b1_description/meshes/thigh.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.175"/>
<geometry>
<box size="0.35 0.05 0.08"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.000235 -0.028704 -0.054169"/>
<mass value="3.934"/>
<inertia ixx="0.044459086" ixy="0.000128738" ixz="-0.002343913" iyy="0.046023457" iyz="0.006032996" izz="0.008696078"/>
</inertial>
</link>
<link name="FL_thigh_rotor">
<visual>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.266"/>
<inertia ixx="0.000485657" ixy="0.0" ixz="0.0" iyy="0.00091885" iyz="0.0" izz="0.000485657"/>
</inertial>
</link>
<joint name="FL_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.35"/>
<parent link="FL_thigh"/>
<child link="FL_calf"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="140" lower="-2.6" upper="-0.6" velocity="15.55"/>
</joint>
<joint name="FL_calf_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.0 -0.0519 0"/>
<parent link="FL_thigh"/>
<child link="FL_calf_rotor"/>
</joint>
<link name="FL_calf">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://b1_description/meshes/calf.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.175"/>
<geometry>
<box size="0.35 0.04 0.05"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.005237 0.0 -0.202805"/>
<mass value="0.857"/>
<inertia ixx="0.015011003" ixy="5.2e-08" ixz="0.000250042" iyy="0.015159462" iyz="4.61e-07" izz="0.000375749"/>
</inertial>
</link>
<link name="FL_calf_rotor">
<visual>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.266"/>
<inertia ixx="0.000485657" ixy="0.0" ixz="0.0" iyy="0.00091885" iyz="0.0" izz="0.000485657"/>
</inertial>
</link>
<joint name="FL_foot_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.35"/>
<parent link="FL_calf"/>
<child link="FL_foot"/>
</joint>
<link name="FL_foot">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.03"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.04"/>
</geometry>
</collision>
<inertial>
<mass value="0.05"/>
<inertia ixx="3.2000000000000005e-05" ixy="0.0" ixz="0.0" iyy="3.2000000000000005e-05" iyz="0.0" izz="3.2000000000000005e-05"/>
</inertial>
</link>
<transmission name="FL_hip_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FL_hip_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FL_hip_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="FL_thigh_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FL_thigh_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FL_thigh_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="FL_calf_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FL_calf_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FL_calf_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="RR_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="-0.3455 -0.072 0"/>
<parent link="base"/>
<child link="RR_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="91.0035" lower="-0.75" upper="0.75" velocity="19.69"/>
</joint>
<joint name="RR_hip_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="-0.1955 -0.072 0"/>
<parent link="base"/>
<child link="RR_hip_rotor"/>
</joint>
<link name="RR_hip">
<visual>
<origin rpy="3.141592653589793 3.141592653589793 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://b1_description/meshes/hip.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 -0.12675 0"/>
<geometry>
<cylinder length="0.04" radius="0.09"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.020298 -0.009758 0.000109"/>
<mass value="2.1"/>
<inertia ixx="0.00406608" ixy="-0.000288071" ixz="4.371e-06" iyy="0.008775259" iyz="-1.811e-06" izz="0.006060348"/>
</inertial>
</link>
<link name="RR_hip_rotor">
<visual>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.199"/>
<inertia ixx="0.00039249" ixy="0.0" ixz="0.0" iyy="0.000219397" iyz="0.0" izz="0.000219397"/>
</inertial>
</link>
<joint name="RR_thigh_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 -0.12675 0"/>
<parent link="RR_hip"/>
<child link="RR_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="93.33" lower="-1.0" upper="3.5" velocity="23.32"/>
</joint>
<joint name="RR_thigh_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.0 -0.00935 0"/>
<parent link="RR_hip"/>
<child link="RR_thigh_rotor"/>
</joint>
<link name="RR_thigh">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://b1_description/meshes/thigh_mirror.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.175"/>
<geometry>
<box size="0.35 0.05 0.08"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.000235 0.028704 -0.054169"/>
<mass value="3.934"/>
<inertia ixx="0.044459086" ixy="-0.000128738" ixz="-0.002343913" iyy="0.046023457" iyz="-0.006032996" izz="0.008696078"/>
</inertial>
</link>
<link name="RR_thigh_rotor">
<visual>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.266"/>
<inertia ixx="0.000485657" ixy="0.0" ixz="0.0" iyy="0.00091885" iyz="0.0" izz="0.000485657"/>
</inertial>
</link>
<joint name="RR_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.35"/>
<parent link="RR_thigh"/>
<child link="RR_calf"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="140" lower="-2.6" upper="-0.6" velocity="15.55"/>
</joint>
<joint name="RR_calf_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.0 0.0519 0"/>
<parent link="RR_thigh"/>
<child link="RR_calf_rotor"/>
</joint>
<link name="RR_calf">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://b1_description/meshes/calf.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.175"/>
<geometry>
<box size="0.35 0.04 0.05"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.005237 0.0 -0.202805"/>
<mass value="0.857"/>
<inertia ixx="0.015011003" ixy="5.2e-08" ixz="0.000250042" iyy="0.015159462" iyz="4.61e-07" izz="0.000375749"/>
</inertial>
</link>
<link name="RR_calf_rotor">
<visual>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.266"/>
<inertia ixx="0.000485657" ixy="0.0" ixz="0.0" iyy="0.00091885" iyz="0.0" izz="0.000485657"/>
</inertial>
</link>
<joint name="RR_foot_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.35"/>
<parent link="RR_calf"/>
<child link="RR_foot"/>
</joint>
<link name="RR_foot">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.03"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.04"/>
</geometry>
</collision>
<inertial>
<mass value="0.05"/>
<inertia ixx="3.2000000000000005e-05" ixy="0.0" ixz="0.0" iyy="3.2000000000000005e-05" iyz="0.0" izz="3.2000000000000005e-05"/>
</inertial>
</link>
<transmission name="RR_hip_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="RR_hip_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="RR_hip_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="RR_thigh_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="RR_thigh_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="RR_thigh_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="RR_calf_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="RR_calf_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="RR_calf_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<joint name="RL_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="-0.3455 0.072 0"/>
<parent link="base"/>
<child link="RL_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="91.0035" lower="-0.75" upper="0.75" velocity="19.69"/>
</joint>
<joint name="RL_hip_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="-0.1955 0.072 0"/>
<parent link="base"/>
<child link="RL_hip_rotor"/>
</joint>
<link name="RL_hip">
<visual>
<origin rpy="0 3.141592653589793 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://b1_description/meshes/hip.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0.12675 0"/>
<geometry>
<cylinder length="0.04" radius="0.09"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.020298 0.009758 0.000109"/>
<mass value="2.1"/>
<inertia ixx="0.00406608" ixy="0.000288071" ixz="4.371e-06" iyy="0.008775259" iyz="1.811e-06" izz="0.006060348"/>
</inertial>
</link>
<link name="RL_hip_rotor">
<visual>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.199"/>
<inertia ixx="0.00039249" ixy="0.0" ixz="0.0" iyy="0.000219397" iyz="0.0" izz="0.000219397"/>
</inertial>
</link>
<joint name="RL_thigh_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0.12675 0"/>
<parent link="RL_hip"/>
<child link="RL_thigh"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="93.33" lower="-1.0" upper="3.5" velocity="23.32"/>
</joint>
<joint name="RL_thigh_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.0 0.00935 0"/>
<parent link="RL_hip"/>
<child link="RL_thigh_rotor"/>
</joint>
<link name="RL_thigh">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://b1_description/meshes/thigh.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.175"/>
<geometry>
<box size="0.35 0.05 0.08"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.000235 -0.028704 -0.054169"/>
<mass value="3.934"/>
<inertia ixx="0.044459086" ixy="0.000128738" ixz="-0.002343913" iyy="0.046023457" iyz="0.006032996" izz="0.008696078"/>
</inertial>
</link>
<link name="RL_thigh_rotor">
<visual>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.266"/>
<inertia ixx="0.000485657" ixy="0.0" ixz="0.0" iyy="0.00091885" iyz="0.0" izz="0.000485657"/>
</inertial>
</link>
<joint name="RL_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.35"/>
<parent link="RL_thigh"/>
<child link="RL_calf"/>
<axis xyz="0 1 0"/>
<dynamics damping="0" friction="0"/>
<limit effort="140" lower="-2.6" upper="-0.6" velocity="15.55"/>
</joint>
<joint name="RL_calf_rotor_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.0 -0.0519 0"/>
<parent link="RL_thigh"/>
<child link="RL_calf_rotor"/>
</joint>
<link name="RL_calf">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://b1_description/meshes/calf.stl" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.175"/>
<geometry>
<box size="0.35 0.04 0.05"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.005237 0.0 -0.202805"/>
<mass value="0.857"/>
<inertia ixx="0.015011003" ixy="5.2e-08" ixz="0.000250042" iyy="0.015159462" iyz="4.61e-07" izz="0.000375749"/>
</inertial>
</link>
<link name="RL_calf_rotor">
<visual>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.02" radius="0.05"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<mass value="0.266"/>
<inertia ixx="0.000485657" ixy="0.0" ixz="0.0" iyy="0.00091885" iyz="0.0" izz="0.000485657"/>
</inertial>
</link>
<joint name="RL_foot_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0 -0.35"/>
<parent link="RL_calf"/>
<child link="RL_foot"/>
</joint>
<link name="RL_foot">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.03"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.04"/>
</geometry>
</collision>
<inertial>
<mass value="0.05"/>
<inertia ixx="3.2000000000000005e-05" ixy="0.0" ixz="0.0" iyy="3.2000000000000005e-05" iyz="0.0" izz="3.2000000000000005e-05"/>
</inertial>
</link>
<transmission name="RL_hip_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="RL_hip_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="RL_hip_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="RL_thigh_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="RL_thigh_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="RL_thigh_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="RL_calf_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="RL_calf_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="RL_calf_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- <xacro:stairs stairs="15" xpos="0" ypos="2.0" zpos="0" /> -->
</robot>