quadruped_ros2_control/descriptions/deep_robotics/lite3_description/urdf/robot.urdf

840 lines
27 KiB
Plaintext
Raw Normal View History

2024-10-09 21:17:45 +08:00
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from robot.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="lite3">
<gazebo>
<plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control">
<robotNamespace>/lite3_gazebo</robotNamespace>
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
</plugin>
</gazebo>
<gazebo reference="imu_link">
<gravity>true</gravity>
<sensor name="imu_sensor" type="imu">
<always_on>true</always_on>
<update_rate>1000</update_rate>
<visualize>true</visualize>
<topic>__default_topic__</topic>
<plugin filename="libgazebo_ros_imu_sensor.so" name="imu_plugin">
<topicName>trunk_imu</topicName>
<bodyName>imu_link</bodyName>
<updateRateHZ>1000.0</updateRateHZ>
<gaussianNoise>0.0</gaussianNoise>
<xyzOffset>0 0 0</xyzOffset>
<rpyOffset>0 0 0</rpyOffset>
<frameName>imu_link</frameName>
</plugin>
<pose>0 0 0 0 0 0</pose>
</sensor>
</gazebo>
<gazebo reference="imu_link">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<!-- Foot contacts. -->
<gazebo reference="FR_SHANK">
<sensor name="FR_foot_contact" type="contact">
<update_rate>100</update_rate>
<plugin filename="libRobotFootContactPlugin.so" name="contactPlugin"/>
<contact>
<collision>FR_SHANK_fixed_joint_lump__FR_FOOT_collision_1</collision>
</contact>
</sensor>
</gazebo>
<gazebo reference="FL_SHANK">
<sensor name="FL_foot_contact" type="contact">
<update_rate>100</update_rate>
<plugin filename="libRobotFootContactPlugin.so" name="contactPlugin"/>
<contact>
<collision>FL_SHANK_fixed_joint_lump__FL_FOOT_collision_1</collision>
</contact>
</sensor>
</gazebo>
<gazebo reference="HR_SHANK">
<sensor name="RR_foot_contact" type="contact">
<update_rate>100</update_rate>
<plugin filename="libRobotFootContactPlugin.so" name="contactPlugin"/>
<contact>
<collision>HR_SHANK_fixed_joint_lump__HR_FOOT_collision_1</collision>
</contact>
</sensor>
</gazebo>
<gazebo reference="HL_SHANK">
<sensor name="RL_foot_contact" type="contact">
<update_rate>100</update_rate>
<plugin filename="libRobotFootContactPlugin.so" name="contactPlugin"/>
<contact>
<collision>HL_SHANK_fixed_joint_lump__HL_FOOT_collision_1</collision>
</contact>
</sensor>
</gazebo>
<gazebo reference="TORSO">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="FL_HIP">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<gazebo reference="FL_THIGH">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="FL_SHANK">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
</gazebo>
<gazebo reference="FL_FOOT">
<mu1>0.6</mu1>
<mu2>0.6</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="FR_HIP">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<gazebo reference="FR_THIGH">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="FR_SHANK">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
</gazebo>
<gazebo reference="FR_FOOT">
<mu1>0.6</mu1>
<mu2>0.6</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="HL_HIP">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<gazebo reference="HL_THIGH">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="HL_SHANK">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
</gazebo>
<gazebo reference="HL_FOOT">
<mu1>0.6</mu1>
<mu2>0.6</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="HR_HIP">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
<gazebo reference="HR_THIGH">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="HR_SHANK">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
</gazebo>
<gazebo reference="HR_FOOT">
<mu1>0.6</mu1>
<mu2>0.6</mu2>
<self_collide>1</self_collide>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<joint name="imu_joint" type="fixed">
<parent link="TORSO"/>
<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>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size=".001 .001 .001"/>
</geometry>
</collision>
</link>
<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="TORSO"/>
</joint>
<link name="TORSO">
<visual>
<origin rpy="0 0 3.1416" xyz="0.0 0.0 0.0"/>
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/lite3_description/share/lite3_description/meshes/Lite3.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.35 0.184 0.08"/>
</geometry>
</collision>
</link>
<link name="INERTIA">
<inertial>
<origin xyz="0.004098 -0.000663 -0.002069"/>
<mass value="4.130"/>
<inertia ixx="0.016982120" ixy="2.1294E-05" ixz="6.0763E-05" iyy="0.030466501" iyz="1.7968E-05" izz="0.042609956"/>
</inertial>
</link>
<joint name="Torso2Inertia" type="fixed">
<parent link="TORSO"/>
<child link="INERTIA"/>
</joint>
<link name="FL_HIP">
<inertial>
<origin xyz="-0.0047 -0.0091 -0.0018"/>
<mass value="0.428"/>
<inertia ixx="0.00014538" ixy="8.1579E-07" ixz="-1.264E-05" iyy="0.00024024" iyz="1.3443E-06" izz="0.00013038"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.05 0.0 0.0"/>
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/lite3_description/share/lite3_description/meshes/FL_HIP.dae"/>
</geometry>
</visual>
</link>
<joint name="FL_HipX" type="revolute">
<origin xyz="0.1745 0.062 0"/>
<parent link="TORSO"/>
<child link="FL_HIP"/>
<axis xyz="-1 0 0"/>
<limit effort="24" lower="-0.42" upper="0.42" velocity="26"/>
</joint>
<link name="FL_THIGH">
<inertial>
<origin xyz="-0.00523 -0.0216 -0.0273"/>
<mass value="0.61"/>
<inertia ixx="0.001" ixy="-2.5E-06" ixz="-1.12E-04" iyy="0.00116" iyz="3.75E-07" izz="2.68E-04"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/lite3_description/share/lite3_description/meshes/l_thigh.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 -0.08"/>
<geometry>
<box size="0.02 0.02 0.16"/>
</geometry>
</collision>
</link>
<joint name="FL_HipY" type="revolute">
<origin xyz="0 0.0985 0"/>
<parent link="FL_HIP"/>
<child link="FL_THIGH"/>
<axis xyz="0 -1 0"/>
<limit effort="24" lower="-2.67" upper="0.314" velocity="26"/>
</joint>
<link name="FL_SHANK">
<inertial>
<origin xyz="0.00585 -8.732E-07 -0.12"/>
<mass value="0.115"/>
<inertia ixx="6.68E-04" ixy="-1.24E-08" ixz="6.91E-06" iyy="6.86E-04" iyz="5.65E-09" izz="3.155E-05"/>
</inertial>
<visual>
<origin rpy="3.14 -1.42 0" xyz="0.0 0.0 0.0"/>
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/lite3_description/share/lite3_description/meshes/SHANK.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 -0.09"/>
<geometry>
<box size="0.02 0.02 0.18"/>
</geometry>
</collision>
</link>
<joint name="FL_Knee" type="revolute">
<origin xyz="0 0 -0.20"/>
<parent link="FL_THIGH"/>
<child link="FL_SHANK"/>
<axis xyz="0 -1 0"/>
<limit effort="36" lower="0.6" upper="2.72" velocity="17"/>
</joint>
<link name="FL_FOOT">
<inertial>
<mass value="1E-12"/>
<inertia ixx="1E-12" ixy="0" ixz="0" iyy="1E-12" iyz="0" izz="1E-12"/>
</inertial>
<collision>
<geometry>
<sphere radius="0.013"/>
</geometry>
</collision>
</link>
<joint name="FL_Ankle" type="fixed">
<origin xyz="0 0 -0.21"/>
<parent link="FL_SHANK"/>
<child link="FL_FOOT"/>
</joint>
<link name="FR_HIP">
<inertial>
<origin xyz="-0.0047 0.0091 -0.0018"/>
<mass value="0.428"/>
<inertia ixx="0.00014538" ixy="-8.1551E-07" ixz="-1.2639E-05" iyy="0.00024024" iyz="-1.3441E-06" izz="0.00013038"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.05 0.0 0.0"/>
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/lite3_description/share/lite3_description/meshes/FR_HIP.dae"/>
</geometry>
</visual>
</link>
<joint name="FR_HipX" type="revolute">
<origin xyz="0.1745 -0.062 0"/>
<parent link="TORSO"/>
<child link="FR_HIP"/>
<axis xyz="-1 0 0"/>
<limit effort="24" lower="-0.42" upper="0.42" velocity="26"/>
</joint>
<link name="FR_THIGH">
<inertial>
<origin xyz="-0.00523 0.0216 -0.0273"/>
<mass value="0.61"/>
<inertia ixx="0.001" ixy="2.5E-06" ixz="-1.12E-04" iyy="0.00116" iyz="-3.75E-07" izz="2.68E-04"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/lite3_description/share/lite3_description/meshes/r_thigh.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 -0.08"/>
<geometry>
<box size="0.02 0.02 0.16"/>
</geometry>
</collision>
</link>
<joint name="FR_HipY" type="revolute">
<origin xyz="0 -0.0985 0"/>
<parent link="FR_HIP"/>
<child link="FR_THIGH"/>
<axis xyz="0 -1 0"/>
<limit effort="24" lower="-2.67" upper="0.314" velocity="26"/>
</joint>
<link name="FR_SHANK">
<inertial>
<origin xyz="0.00585 -8.732E-07 -0.12"/>
<mass value="0.115"/>
<inertia ixx="6.68E-04" ixy="-1.24E-08" ixz="6.91E-06" iyy="6.86E-04" iyz="5.65E-09" izz="3.155E-05"/>
</inertial>
<visual>
<origin rpy="3.14 -1.42 0" xyz="0.0 0.0 0.0"/>
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/lite3_description/share/lite3_description/meshes/SHANK.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 -0.09"/>
<geometry>
<box size="0.02 0.02 0.18"/>
</geometry>
</collision>
</link>
<joint name="FR_Knee" type="revolute">
<origin xyz="0 0 -0.20"/>
<parent link="FR_THIGH"/>
<child link="FR_SHANK"/>
<axis xyz="0 -1 0"/>
<limit effort="36" lower="0.6" upper="2.72" velocity="17"/>
</joint>
<link name="FR_FOOT">
<inertial>
<mass value="1E-12"/>
<inertia ixx="1E-12" ixy="0" ixz="0" iyy="1E-12" iyz="0" izz="1E-12"/>
</inertial>
<collision>
<geometry>
<sphere radius="0.013"/>
</geometry>
</collision>
</link>
<joint name="FR_Ankle" type="fixed">
<origin xyz="0 0 -0.21"/>
<parent link="FR_SHANK"/>
<child link="FR_FOOT"/>
</joint>
<link name="HL_HIP">
<inertial>
<origin xyz="0.0047 -0.0091 -0.0018"/>
<mass value="0.428"/>
<inertia ixx="0.00014538" ixy="-8.1585E-07" ixz="1.2639E-05" iyy="0.00024024" iyz="1.3444E-06" izz="0.00013038"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.05 0.0 0.0"/>
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/lite3_description/share/lite3_description/meshes/HL_HIP.dae"/>
</geometry>
</visual>
</link>
<joint name="HL_HipX" type="revolute">
<origin xyz="-0.1745 0.062 0"/>
<parent link="TORSO"/>
<child link="HL_HIP"/>
<axis xyz="-1 0 0"/>
<limit effort="24" lower="-0.42" upper="0.42" velocity="26"/>
</joint>
<link name="HL_THIGH">
<inertial>
<origin xyz="-0.00523 -0.0216 -0.0273"/>
<mass value="0.61"/>
<inertia ixx="0.001" ixy="-2.5E-06" ixz="-1.12E-04" iyy="0.00116" iyz="3.75E-07" izz="2.68E-04"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/lite3_description/share/lite3_description/meshes/l_thigh.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 -0.08"/>
<geometry>
<box size="0.02 0.02 0.16"/>
</geometry>
</collision>
</link>
<joint name="HL_HipY" type="revolute">
<origin xyz="0 0.0985 0"/>
<parent link="HL_HIP"/>
<child link="HL_THIGH"/>
<axis xyz="0 -1 0"/>
<limit effort="24" lower="-2.67" upper="0.314" velocity="26"/>
</joint>
<link name="HL_SHANK">
<inertial>
<origin xyz="0.00585 -8.732E-07 -0.12"/>
<mass value="0.115"/>
<inertia ixx="6.68E-04" ixy="-1.24E-08" ixz="6.91E-06" iyy="6.86E-04" iyz="5.65E-09" izz="3.155E-05"/>
</inertial>
<visual>
<origin rpy="3.14 -1.42 0" xyz="0.0 0.0 0.0"/>
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/lite3_description/share/lite3_description/meshes/SHANK.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 -0.09"/>
<geometry>
<box size="0.02 0.02 0.18"/>
</geometry>
</collision>
</link>
<joint name="HL_Knee" type="revolute">
<origin xyz="0 0 -0.20"/>
<parent link="HL_THIGH"/>
<child link="HL_SHANK"/>
<axis xyz="0 -1 0"/>
<limit effort="36" lower="0.6" upper="2.72" velocity="17"/>
</joint>
<link name="HL_FOOT">
<inertial>
<mass value="1E-12"/>
<inertia ixx="1E-12" ixy="0" ixz="0" iyy="1E-12" iyz="0" izz="1E-12"/>
</inertial>
<collision>
<geometry>
<sphere radius="0.013"/>
</geometry>
</collision>
</link>
<joint name="HL_Ankle" type="fixed">
<origin xyz="0 0 -0.21"/>
<parent link="HL_SHANK"/>
<child link="HL_FOOT"/>
</joint>
<link name="HR_HIP">
<inertial>
<origin xyz="0.0047 0.0091 -0.0018"/>
<mass value="0.428"/>
<inertia ixx="0.00014538" ixy="8.1545E-07" ixz="1.2639E-05" iyy="0.00024024" iyz="-1.344E-06" izz="0.00013038"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.05 0.0 0.0"/>
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/lite3_description/share/lite3_description/meshes/HR_HIP.dae"/>
</geometry>
</visual>
</link>
<joint name="HR_HipX" type="revolute">
<origin xyz="-0.1745 -0.062 0"/>
<parent link="TORSO"/>
<child link="HR_HIP"/>
<axis xyz="-1 0 0"/>
<limit effort="24" lower="-0.42" upper="0.42" velocity="26"/>
</joint>
<link name="HR_THIGH">
<inertial>
<origin xyz="-0.00523 0.0216 -0.0273"/>
<mass value="0.61"/>
<inertia ixx="0.001" ixy="2.5E-06" ixz="-1.12E-04" iyy="0.00116" iyz="-3.75E-07" izz="2.68E-04"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/lite3_description/share/lite3_description/meshes/r_thigh.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 -0.08"/>
<geometry>
<box size="0.02 0.02 0.16"/>
</geometry>
</collision>
</link>
<joint name="HR_HipY" type="revolute">
<origin xyz="0 -0.0985 0"/>
<parent link="HR_HIP"/>
<child link="HR_THIGH"/>
<axis xyz="0 -1 0"/>
<limit effort="24" lower="-2.67" upper="0.314" velocity="26"/>
</joint>
<link name="HR_SHANK">
<inertial>
<origin xyz="0.00585 -8.732E-07 -0.12"/>
<mass value="0.115"/>
<inertia ixx="6.68E-04" ixy="-1.24E-08" ixz="6.91E-06" iyy="6.86E-04" iyz="5.65E-09" izz="3.155E-05"/>
</inertial>
<visual>
<origin rpy="3.14 -1.42 0" xyz="0.0 0.0 0.0"/>
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/lite3_description/share/lite3_description/meshes/SHANK.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 -0.09"/>
<geometry>
<box size="0.02 0.02 0.18"/>
</geometry>
</collision>
</link>
<joint name="HR_Knee" type="revolute">
<origin xyz="0 0 -0.20"/>
<parent link="HR_THIGH"/>
<child link="HR_SHANK"/>
<axis xyz="0 -1 0"/>
<limit effort="36" lower="0.6" upper="2.72" velocity="17"/>
</joint>
<link name="HR_FOOT">
<inertial>
<mass value="1E-12"/>
<inertia ixx="1E-12" ixy="0" ixz="0" iyy="1E-12" iyz="0" izz="1E-12"/>
</inertial>
<collision>
<geometry>
<sphere radius="0.013"/>
</geometry>
</collision>
</link>
<joint name="HR_Ankle" type="fixed">
<origin xyz="0 0 -0.21"/>
<parent link="HR_SHANK"/>
<child link="HR_FOOT"/>
</joint>
<!-- FL transmissions -->
<transmission name="FL_HipX_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FL_HipX">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FL_HipX_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="FL_HipY_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FL_HipY">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FL_HipY_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="FL_Knee_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FL_Knee">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FL_Knee_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- FR transmissions -->
<transmission name="FR_HipX_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FR_HipX">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FR_HipX_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="FR_HipY_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FR_HipY">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FR_HipY_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="FR_Knee_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FR_Knee">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FR_Knee_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- HL transmissions -->
<transmission name="HL_HipX_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="HL_HipX">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="HL_HipX_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="HL_HipY_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="HL_HipY">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="HL_HipY_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="HL_Knee_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="HL_Knee">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="HL_Knee_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- HR transmissions -->
<transmission name="HR_HipX_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="HR_HipX">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="HR_HipX_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="HR_HipY_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="HR_HipY">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="HR_HipY_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="HR_Knee_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="HR_Knee">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="HR_Knee_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<ros2_control name="UnitreeSystem" type="system">
<hardware>
<plugin>hardware_unitree_mujoco/HardwareUnitree</plugin>
</hardware>
<joint name="FR_HipX">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FR_HipY">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FR_Knee">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FL_HipX">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FL_HipY">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FL_Knee">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HR_HipX">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HR_HipY">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HR_Knee">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HL_HipX">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HL_HipY">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HL_Knee">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<sensor name="imu_sensor">
<state_interface name="orientation.w"/>
<state_interface name="orientation.x"/>
<state_interface name="orientation.y"/>
<state_interface name="orientation.z"/>
<state_interface name="angular_velocity.x"/>
<state_interface name="angular_velocity.y"/>
<state_interface name="angular_velocity.z"/>
<state_interface name="linear_acceleration.x"/>
<state_interface name="linear_acceleration.y"/>
<state_interface name="linear_acceleration.z"/>
</sensor>
<sensor name="foot_force">
<state_interface name="FR"/>
<state_interface name="FL"/>
<state_interface name="HR"/>
<state_interface name="HL"/>
</sensor>
</ros2_control>
</robot>