quadruped_ros2_control/descriptions/deep_robotics/x30_description/urdf/robot.urdf

743 lines
25 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="x30">
<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">
<inertial>
<origin rpy="0 0 0" xyz="-0.0029257 7.5034e-06 0.020095"/>
<mass value="30.7"/>
<inertia ixx="0.364306" ixy="0.00018421" ixz="0.00027469" iyy="0.597627" iyz="0.00026784" izz="0.757267"/>
</inertial>
<visual>
<geometry>
<mesh filename="file:///home/hiverlab/ros2_ws/install/x30_description/share/x30_description/meshes/torso.dae"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.44 0.26 0.15"/>
</geometry>
</collision>
</link>
<link name="FL_HIP">
<inertial>
<origin rpy="0 0 0" xyz="-0.0018591 -0.011377 0.00027039"/>
<mass value="1.43"/>
<inertia ixx="0.0014068" ixy="-1.8545e-05" ixz="2.7664e-06" iyy="0.0026782" iyz="2.1221e-06" izz="0.0015918"/>
</inertial>
<visual>
<geometry>
<mesh filename="file:///home/hiverlab/ros2_ws/install/x30_description/share/x30_description/meshes/hip.dae"/>
</geometry>
<material name="grey"/>
</visual>
</link>
<joint name="FL_HipX" type="revolute">
<origin rpy="0 0 0" xyz="0.291 0.08 0"/>
<parent link="TORSO"/>
<child link="FL_HIP"/>
<axis xyz="-1 0 0"/>
<limit effort="84" lower="-0.323" upper="0.323" velocity="17.5"/>
</joint>
<link name="FL_THIGH">
<inertial>
<origin rpy="0 0 0" xyz="-0.0087581 -0.023554 -0.055162"/>
<mass value="4.0809"/>
<inertia ixx="0.012604" ixy="0.00020291" ixz="-0.00030875" iyy="0.0164" iyz="0.00036593" izz="0.0061084"/>
</inertial>
<visual>
<geometry>
<mesh filename="file:///home/hiverlab/ros2_ws/install/x30_description/share/x30_description/meshes/l_thigh.dae"/>
</geometry>
<material name="light-grey"/>
</visual>
<collision>
<origin xyz="-0.02 0 -0.13"/>
<geometry>
<cylinder length="0.25" radius="0.04"/>
</geometry>
</collision>
</link>
<joint name="FL_HipY" type="revolute">
<origin rpy="0 0 0" xyz="0 0.11675 0"/>
<parent link="FL_HIP"/>
<child link="FL_THIGH"/>
<axis xyz="0 -1 0"/>
<limit effort="84" lower="-2.967" upper="0.262" velocity="17.5"/>
</joint>
<link name="FL_SHANK">
<inertial>
<origin rpy="0 0 0" xyz="0.014851 2.0685e-05 -0.12283"/>
<mass value="0.71386"/>
<inertia ixx="0.0093039" ixy="1.7693e-07" ixz="0.00034843" iyy="0.0096272" iyz="-3.7717e-06" izz="0.00041542"/>
</inertial>
<visual>
<geometry>
<mesh filename="file:///home/hiverlab/ros2_ws/install/x30_description/share/x30_description/meshes/shank.dae"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0. -0.40 0." xyz="0.02 0 -0.046"/>
<geometry>
<cylinder length="0.1" radius="0.025"/>
</geometry>
</collision>
<collision>
<origin rpy="0. 0 0." xyz="0.045 0 -0.155"/>
<geometry>
<cylinder length="0.12" radius="0.025"/>
</geometry>
</collision>
<collision>
<origin rpy="0. 0.45 0." xyz="0.025 0 -0.246"/>
<geometry>
<cylinder length="0.08" radius="0.022"/>
</geometry>
</collision>
</link>
<joint name="FL_Knee" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.30"/>
<parent link="FL_THIGH"/>
<child link="FL_SHANK"/>
<axis xyz="0 -1 0"/>
<limit effort="160" lower="0.349" upper="2.531" velocity="16.1"/>
</joint>
<link name="FL_FOOT">
<inertial>
<mass value="0.06"/>
<inertia ixx="1e-12" ixy="0" ixz="0" iyy="1e-12" iyz="0" izz="1e-12"/>
</inertial>
<collision>
<geometry>
<sphere radius="0.03"/>
</geometry>
</collision>
</link>
<joint dont_collapse="true" name="FL_Ankle" type="fixed">
<origin xyz="0 0 -0.31"/>
<parent link="FL_SHANK"/>
<child link="FL_FOOT"/>
</joint>
<link name="FR_HIP">
<inertial>
<origin rpy="3.14159 0 0" xyz="-0.0018591 0.011377 -2.7675e-05"/>
<mass value="1.43"/>
<inertia ixx="0.0014068" ixy="1.8545e-05" ixz="-4.1487e-06" iyy="0.0026782" iyz="7.0795e-06" izz="0.0015918"/>
</inertial>
<visual>
<geometry>
<mesh filename="file:///home/hiverlab/ros2_ws/install/x30_description/share/x30_description/meshes/hip.dae"/>
</geometry>
<material name="grey"/>
</visual>
</link>
<joint name="FR_HipX" type="revolute">
<origin rpy="0 0 0" xyz="0.291 -0.08 0"/>
<parent link="TORSO"/>
<child link="FR_HIP"/>
<axis xyz="-1 0 0"/>
<limit effort="84" lower="-0.323" upper="0.323" velocity="17.5"/>
</joint>
<link name="FR_THIGH">
<inertial>
<origin rpy="0 0 0" xyz="-0.0087433 0.023551 -0.055154"/>
<mass value="4.0809"/>
<inertia ixx="0.012604" ixy="-0.00020374" ixz="-0.0003086" iyy="0.0164" iyz="-0.00036585" izz="0.0061086"/>
</inertial>
<visual>
<geometry>
<mesh filename="file:///home/hiverlab/ros2_ws/install/x30_description/share/x30_description/meshes/r_thigh.dae"/>
</geometry>
<material name="light-grey"/>
</visual>
<collision>
<origin xyz="-0.02 0 -0.13"/>
<geometry>
<cylinder length="0.25" radius="0.04"/>
</geometry>
</collision>
</link>
<joint name="FR_HipY" type="revolute">
<origin rpy="0 0 0" xyz="0 -0.11675 0"/>
<parent link="FR_HIP"/>
<child link="FR_THIGH"/>
<axis xyz="0 -1 0"/>
<limit effort="84" lower="-2.967" upper="0.262" velocity="17.5"/>
</joint>
<link name="FR_SHANK">
<inertial>
<origin rpy="0 0 0" xyz="0.014851 2.0687e-05 -0.12283"/>
<mass value="0.71386"/>
<inertia ixx="0.0093039" ixy="1.7692e-07" ixz="0.00034843" iyy="0.0096272" iyz="-3.7714e-06" izz="0.00041542"/>
</inertial>
<visual>
<geometry>
<mesh filename="file:///home/hiverlab/ros2_ws/install/x30_description/share/x30_description/meshes/shank.dae"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0. -0.40 0." xyz="0.02 0 -0.046"/>
<geometry>
<cylinder length="0.1" radius="0.025"/>
</geometry>
</collision>
<collision>
<origin rpy="0. 0 0." xyz="0.045 0 -0.155"/>
<geometry>
<cylinder length="0.12" radius="0.025"/>
</geometry>
</collision>
<collision>
<origin rpy="0. 0.45 0." xyz="0.025 0 -0.246"/>
<geometry>
<cylinder length="0.08" radius="0.022"/>
</geometry>
</collision>
</link>
<joint name="FR_Knee" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.30"/>
<parent link="FR_THIGH"/>
<child link="FR_SHANK"/>
<axis xyz="0 -1 0"/>
<limit effort="160" lower="0.349" upper="2.531" velocity="16.1"/>
</joint>
<link name="FR_FOOT">
<inertial>
<mass value="0.06"/>
<inertia ixx="1e-12" ixy="0" ixz="0" iyy="1e-12" iyz="0" izz="1e-12"/>
</inertial>
<collision>
<geometry>
<sphere radius="0.03"/>
</geometry>
</collision>
</link>
<joint dont_collapse="true" name="FR_Ankle" type="fixed">
<origin xyz="0 0 -0.31"/>
<parent link="FR_SHANK"/>
<child link="FR_FOOT"/>
</joint>
<link name="HL_HIP">
<inertial>
<origin rpy="0 3.14159 0" xyz="0.0018591 -0.011377 -2.7675e-05"/>
<mass value="1.43"/>
<inertia ixx="0.0014068" ixy="1.8545e-05" ixz="4.1487e-06" iyy="0.0026782" iyz="-7.0795e-06" izz="0.0015918"/>
</inertial>
<visual>
<geometry>
<mesh filename="file:///home/hiverlab/ros2_ws/install/x30_description/share/x30_description/meshes/hip.dae"/>
</geometry>
<material name="grey"/>
</visual>
</link>
<joint name="HL_HipX" type="revolute">
<origin rpy="0 0 0" xyz="-0.291 0.08 0"/>
<parent link="TORSO"/>
<child link="HL_HIP"/>
<axis xyz="-1 0 0"/>
<limit effort="84" lower="-0.323" upper="0.323" velocity="17.5"/>
</joint>
<link name="HL_THIGH">
<inertial>
<origin rpy="0 0 0" xyz="-0.0087581 -0.023554 -0.055162"/>
<mass value="4.0809"/>
<inertia ixx="0.012604" ixy="0.00020291" ixz="-0.00030875" iyy="0.0164" iyz="0.00036593" izz="0.0061084"/>
</inertial>
<visual>
<geometry>
<mesh filename="file:///home/hiverlab/ros2_ws/install/x30_description/share/x30_description/meshes/l_thigh.dae"/>
</geometry>
<material name="light-grey"/>
</visual>
<collision>
<origin xyz="-0.02 0 -0.13"/>
<geometry>
<cylinder length="0.25" radius="0.04"/>
</geometry>
</collision>
</link>
<joint name="HL_HipY" type="revolute">
<origin rpy="0 0 0" xyz="0 0.11675 0"/>
<parent link="HL_HIP"/>
<child link="HL_THIGH"/>
<axis xyz="0 -1 0"/>
<limit effort="84" lower="-2.967" upper="0.262" velocity="17.5"/>
</joint>
<link name="HL_SHANK">
<inertial>
<origin rpy="0 0 0" xyz="0.014851 2.0679e-05 -0.12283"/>
<mass value="0.71386"/>
<inertia ixx="0.0093039" ixy="1.7692e-07" ixz="0.00034843" iyy="0.0096272" iyz="-3.7714e-06" izz="0.00041542"/>
</inertial>
<visual>
<geometry>
<mesh filename="file:///home/hiverlab/ros2_ws/install/x30_description/share/x30_description/meshes/shank.dae"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0. -0.40 0." xyz="0.02 0 -0.046"/>
<geometry>
<cylinder length="0.1" radius="0.025"/>
</geometry>
</collision>
<collision>
<origin rpy="0. 0 0." xyz="0.045 0 -0.155"/>
<geometry>
<cylinder length="0.12" radius="0.025"/>
</geometry>
</collision>
<collision>
<origin rpy="0. 0.45 0." xyz="0.025 0 -0.246"/>
<geometry>
<cylinder length="0.08" radius="0.022"/>
</geometry>
</collision>
</link>
<joint name="HL_Knee" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.30"/>
<parent link="HL_THIGH"/>
<child link="HL_SHANK"/>
<axis xyz="0 -1 0"/>
<limit effort="160" lower="0.349" upper="2.531" velocity="16.1"/>
</joint>
<link name="HL_FOOT">
<inertial>
<mass value="0.06"/>
<inertia ixx="1e-12" ixy="0" ixz="0" iyy="1e-12" iyz="0" izz="1e-12"/>
</inertial>
<collision>
<geometry>
<sphere radius="0.03"/>
</geometry>
</collision>
</link>
<joint dont_collapse="true" name="HL_Ankle" type="fixed">
<origin xyz="0 0 -0.31"/>
<parent link="HL_SHANK"/>
<child link="HL_FOOT"/>
</joint>
<link name="HR_HIP">
<inertial>
<origin rpy="3.14159 3.14159 0" xyz="0.0018591 0.011377 0.00027039"/>
<mass value="1.43"/>
<inertia ixx="0.0014068" ixy="-1.8545e-05" ixz="-2.7664e-06" iyy="0.0026782" iyz="-2.1221e-06" izz="0.0015918"/>
</inertial>
<visual>
<geometry>
<mesh filename="file:///home/hiverlab/ros2_ws/install/x30_description/share/x30_description/meshes/hip.dae"/>
</geometry>
<material name="grey"/>
</visual>
</link>
<joint name="HR_HipX" type="revolute">
<origin rpy="0 0 0" xyz="-0.291 -0.08 0"/>
<parent link="TORSO"/>
<child link="HR_HIP"/>
<axis xyz="-1 0 0"/>
<limit effort="84" lower="-0.323" upper="0.323" velocity="17.5"/>
</joint>
<link name="HR_THIGH">
<inertial>
<origin rpy="0 0 0" xyz="-0.0087433 0.023551 -0.055154"/>
<mass value="4.0809"/>
<inertia ixx="0.012604" ixy="-0.00020374" ixz="-0.0003086" iyy="0.0164" iyz="-0.00036585" izz="0.0061086"/>
</inertial>
<visual>
<geometry>
<mesh filename="file:///home/hiverlab/ros2_ws/install/x30_description/share/x30_description/meshes/r_thigh.dae"/>
</geometry>
<material name="light-grey"/>
</visual>
<collision>
<origin xyz="-0.02 0 -0.13"/>
<geometry>
<cylinder length="0.25" radius="0.04"/>
</geometry>
</collision>
</link>
<joint name="HR_HipY" type="revolute">
<origin rpy="0 0 0" xyz="0 -0.11675 0"/>
<parent link="HR_HIP"/>
<child link="HR_THIGH"/>
<axis xyz="0 -1 0"/>
<limit effort="84" lower="-2.967" upper="0.262" velocity="17.5"/>
</joint>
<link name="HR_SHANK">
<inertial>
<origin rpy="0 0 0" xyz="0.014851 2.0679e-05 -0.12283"/>
<mass value="0.71386"/>
<inertia ixx="0.0093039" ixy="1.7692e-07" ixz="0.00034843" iyy="0.0096272" iyz="-3.7714e-06" izz="0.00041542"/>
</inertial>
<visual>
<geometry>
<mesh filename="file:///home/hiverlab/ros2_ws/install/x30_description/share/x30_description/meshes/shank.dae"/>
</geometry>
<material name="silver"/>
</visual>
<collision>
<origin rpy="0. -0.40 0." xyz="0.02 0 -0.046"/>
<geometry>
<cylinder length="0.1" radius="0.025"/>
</geometry>
</collision>
<collision>
<origin rpy="0. 0 0." xyz="0.045 0 -0.155"/>
<geometry>
<cylinder length="0.12" radius="0.025"/>
</geometry>
</collision>
<collision>
<origin rpy="0. 0.45 0." xyz="0.025 0 -0.246"/>
<geometry>
<cylinder length="0.08" radius="0.022"/>
</geometry>
</collision>
</link>
<joint name="HR_Knee" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.30"/>
<parent link="HR_THIGH"/>
<child link="HR_SHANK"/>
<axis xyz="0 -1 0"/>
<limit effort="160" lower="0.349" upper="2.531" velocity="16.1"/>
</joint>
<link name="HR_FOOT">
<inertial>
<mass value="0.06"/>
<inertia ixx="1e-12" ixy="0" ixz="0" iyy="1e-12" iyz="0" izz="1e-12"/>
</inertial>
<collision>
<geometry>
<sphere radius="0.03"/>
</geometry>
</collision>
</link>
<joint dont_collapse="true" name="HR_Ankle" type="fixed">
<origin xyz="0 0 -0.31"/>
<parent link="HR_SHANK"/>
<child link="HR_FOOT"/>
</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="deep-grey">
<color rgba="0.1 0.1 0.1 1.0"/>
</material>
<material name="grey">
<color rgba="0.2 0.2 0.2 1.0"/>
</material>
<material name="light-grey">
<color rgba="0.35 0.35 0.35 1.0"/>
</material>
<material name="silver">
<color rgba="0.9137254901960784 0.9137254901960784 0.8470588235294118 1.0"/>
</material>
<material name="white">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
<!-- 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>