quadruped_ros2_control/descriptions/xiaomi/cyberdog_description/urdf/robot.urdf

1324 lines
43 KiB
Plaintext
Raw Normal View History

2024-10-01 19:10:23 +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="cyber_dog">
<ros2_control name="UnitreeSystem" type="system">
<hardware>
<plugin>hardware_unitree_mujoco/HardwareUnitree</plugin>
</hardware>
<joint name="FR_hip_joint">
<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_thigh_joint">
<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_calf_joint">
<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_hip_joint">
<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_thigh_joint">
<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_calf_joint">
<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="RR_hip_joint">
<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="RR_thigh_joint">
<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="RR_calf_joint">
<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="RL_hip_joint">
<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="RL_thigh_joint">
<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="RL_calf_joint">
<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="RR"/>
<state_interface name="RL"/>
</sensor>
</ros2_control>
<link name="base_link">
<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_link"/>
<child link="body"/>
</joint>
<link name="body">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/cyberdog_description/share/cyberdog_description/meshes/body.dae" scale="1 1 1"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.236 0.19 0.109"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.0273 -0.000242 0.0143"/>
<mass value="4.03"/>
<inertia ixx="0.0185" ixy="-0.000173" ixz="-0.0102" iyy="0.0517" iyz="-2.83e-05" izz="0.0483"/>
</inertial>
</link>
<joint name="imu_joint" type="fixed">
<parent link="body"/>
<child link="imu_link"/>
<origin rpy="0 0 0" xyz="33.4e-3 -17.2765e-3 51.0469e-3"/>
</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>
<joint name="scan_joint" type="fixed">
<parent link="body"/>
<child link="lidar_link"/>
<origin rpy="0 0 0" xyz="0.21425 0 0.0908"/>
</joint>
<link name="lidar_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>
</link>
<joint name="D435_camera_joint" type="fixed">
<parent link="body"/>
<child link="D435_camera_link"/>
<origin rpy="0 0 0" xyz="271.994e-3 25e-3 114.912e-3"/>
</joint>
<link name="D435_camera_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>
<joint name="RGB_camera_joint" type="fixed">
<parent link="body"/>
<child link="RGB_camera_link"/>
<origin rpy="0 0 0" xyz="275.76e-3 0 125.794e-3"/>
</joint>
<link name="RGB_camera_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>
<joint name="AI_camera_joint" type="fixed">
<parent link="body"/>
<child link="AI_camera_link"/>
<origin rpy="0 0 0" xyz="290.228e-3 0 147.420e-3"/>
</joint>
<link name="AI_camera_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>
<joint name="FR_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="0.164 -0.042 0"/>
<parent link="body"/>
<child link="FR_abad"/>
<axis xyz="1 0 0"/>
<dynamics damping="0.01" friction="0.1"/>
<limit effort="12.0001" lower="-0.6806784082777885" upper="0.6806784082777885" velocity="30.9971"/>
</joint>
<link name="FR_abad">
<visual>
<origin rpy="3.141592653589793 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/cyberdog_description/share/cyberdog_description/meshes/abad.dae" scale="1 1 1"/>
</geometry>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.035" radius="0.039"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.00392 -0.015 -0.000306"/>
<mass value="0.354"/>
<inertia ixx="0.00019" ixy="2.7e-05" ixz="-3.44e-07" iyy="0.000276" iyz="-1.95e-06" izz="0.000233"/>
</inertial>
</link>
<joint name="FR_abad_rotor_fix" type="fixed">
<origin rpy="0 0 0" xyz="-0.0642303 0 0"/>
<parent link="FR_abad"/>
<child link="FR_abad_rotor"/>
</joint>
<!-- this link is only for abad rotor inertial -->
<link name="FR_abad_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.0567"/>
<inertia ixx="2.53e-05" ixy="0" ixz="0" iyy="4.78e-05" iyz="0" izz="2.53e-05"/>
</inertial>
</link>
<joint name="FR_abad_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 -0.059 0"/>
<parent link="FR_abad"/>
<child link="FR_hip_shoulder"/>
</joint>
<link name="FR_hip_shoulder">
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.035" radius="0.039"/>
</geometry>
</collision>
</link>
<joint name="FR_thigh_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 -0.094 0"/>
<parent link="FR_abad"/>
<child link="FR_hip"/>
<axis xyz="0 1 0"/>
<dynamics damping="0.01" friction="0.1"/>
<limit effort="12.0001" lower="-1.3264502315156903" upper="2.792526803190927" velocity="30.9971"/>
</joint>
<link name="FR_hip">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/cyberdog_description/share/cyberdog_description/meshes/hip_mirror.dae" scale="1 1 1"/>
</geometry>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.06"/>
<geometry>
<box size="0.12 0.025 0.034"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.00212 0.0212 -0.0184"/>
<mass value="0.482"/>
<inertia ixx="0.00101" ixy="-2.23e-05" ixz="-3.85e-05" iyy="0.000983" iyz="-0.000199" izz="0.000347"/>
</inertial>
</link>
<joint name="FR_hip_rotor_fix" type="fixed">
<origin rpy="0 0 0" xyz="0 0.07577 0"/>
<parent link="FR_hip"/>
<child link="FR_hip_rotor"/>
</joint>
<!-- this link is only for hip rotor inertial -->
<link name="FR_hip_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.0567"/>
<inertia ixx="2.53e-05" ixy="0" ixz="0" iyy="4.78e-05" iyz="0" izz="2.53e-05"/>
</inertial>
</link>
<joint name="FR_knee_rotor_fix" type="fixed">
<origin rpy="0 0 0" xyz="0 0.0342303 0"/>
<parent link="FR_hip"/>
<child link="FR_knee_rotor"/>
</joint>
<!-- this link is only for knee rotor inertial -->
<link name="FR_knee_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.0567"/>
<inertia ixx="2.53e-05" ixy="0" ixz="0" iyy="4.78e-05" iyz="0" izz="2.53e-05"/>
</inertial>
</link>
<joint name="FR_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.12"/>
<parent link="FR_hip"/>
<child link="FR_knee"/>
<axis xyz="0 1 0"/>
<dynamics damping="0.01" friction="0.1"/>
<limit effort="12.0001" lower="-2.5307274153917776" upper="-0.5235987755982988" velocity="30.9971"/>
</joint>
<link name="FR_knee">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/cyberdog_description/share/cyberdog_description/meshes/knee.dae" scale="1 1 1"/>
</geometry>
</visual>
<collision>
<origin rpy="0 3.141592653589793 0" xyz="0 0 -0.091705"/>
<geometry>
<box size="0.016 0.016 0.18341"/>
</geometry>
</collision>
<collision name="FR_knee_rubber">
<origin rpy="0 3.141592653589793 0" xyz="-0.01 0 -0.007"/>
<geometry>
<sphere radius="0.016"/>
</geometry>
<surface>
<contact>
<ode>
<max_vel>0.00001</max_vel>
<min_depth>0.0</min_depth>
</ode>
</contact>
</surface>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.0006 -4.72e-05 -0.0893"/>
<mass value="0.116"/>
<inertia ixx="0.000668" ixy="3e-09" ixz="2.37e-05" iyy="0.000674" iyz="6.03e-07" izz="1.54e-05"/>
</inertial>
</link>
<joint name="FR_foot_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0.0055 0 -0.17390999999999998"/>
<parent link="FR_knee"/>
<child link="FR_foot"/>
</joint>
<link name="FR_foot">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.009"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.019"/>
</geometry>
<surface>
<contact>
<ode>
<max_vel>0.001</max_vel>
<min_depth>0.0</min_depth>
</ode>
</contact>
</surface>
</collision>
</link>
<transmission name="FR_abad_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FR_abad_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FR_abad_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>&quot;7.75&quot;</mechanicalReduction>
</actuator>
</transmission>
<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>&quot;7.75&quot;</mechanicalReduction>
</actuator>
</transmission>
<transmission name="FR_knee_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FR_knee_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FR_knee_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>&quot;7.75&quot;</mechanicalReduction>
</actuator>
</transmission>
<gazebo reference="FR_abad">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<visual>
<material>
<ambient>.5 .5 .5 1.0</ambient>
<diffuse>.5 .5 .5 1.0</diffuse>
<specular>.5 .5 .5 1.0</specular>
</material>
</visual>
</gazebo>
<gazebo reference="FR_hip">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<visual>
<material>
<ambient>.05 .05 .05 1.0</ambient>
<diffuse>.05 .05 .05 1.0</diffuse>
<specular>.05 .05 .05 1.0</specular>
</material>
</visual>
</gazebo>
<gazebo reference="FR_knee">
<mu1>0.7</mu1>
<mu2>0.7</mu2>
<self_collide>1</self_collide>
<visual>
<material>
<ambient>.5 .5 .5 1.0</ambient>
<diffuse>.5 .5 .5 1.0</diffuse>
<specular>.5 .5 .5 1.0</specular>
</material>
</visual>
</gazebo>
<gazebo reference="FR_foot">
<mu1>0.7</mu1>
<mu2>0.7</mu2>
<self_collide>1</self_collide>
<visual>
<material>
<ambient>.5 .5 .5 1.0</ambient>
<diffuse>.5 .5 .5 1.0</diffuse>
<specular>.5 .5 .5 1.0</specular>
</material>
</visual>
</gazebo>
<joint name="FL_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="0.164 0.042 0"/>
<parent link="body"/>
<child link="FL_abad"/>
<axis xyz="1 0 0"/>
<dynamics damping="0.01" friction="0.1"/>
<limit effort="12.0001" lower="-0.6806784082777885" upper="0.6806784082777885" velocity="30.9971"/>
</joint>
<link name="FL_abad">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/cyberdog_description/share/cyberdog_description/meshes/abad.dae" scale="1 1 1"/>
</geometry>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.035" radius="0.039"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.00392 0.015 -0.000306"/>
<mass value="0.354"/>
<inertia ixx="0.00019" ixy="-2.7e-05" ixz="-3.44e-07" iyy="0.000276" iyz="1.95e-06" izz="0.000233"/>
</inertial>
</link>
<joint name="FL_abad_rotor_fix" type="fixed">
<origin rpy="0 0 0" xyz="-0.0642303 0 0"/>
<parent link="FL_abad"/>
<child link="FL_abad_rotor"/>
</joint>
<!-- this link is only for abad rotor inertial -->
<link name="FL_abad_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.0567"/>
<inertia ixx="2.53e-05" ixy="0" ixz="0" iyy="4.78e-05" iyz="0" izz="2.53e-05"/>
</inertial>
</link>
<joint name="FL_abad_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0.059 0"/>
<parent link="FL_abad"/>
<child link="FL_hip_shoulder"/>
</joint>
<link name="FL_hip_shoulder">
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.035" radius="0.039"/>
</geometry>
</collision>
</link>
<joint name="FL_thigh_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0.094 0"/>
<parent link="FL_abad"/>
<child link="FL_hip"/>
<axis xyz="0 1 0"/>
<dynamics damping="0.01" friction="0.1"/>
<limit effort="12.0001" lower="-1.3264502315156903" upper="2.792526803190927" velocity="30.9971"/>
</joint>
<link name="FL_hip">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/cyberdog_description/share/cyberdog_description/meshes/hip.dae" scale="1 1 1"/>
</geometry>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.06"/>
<geometry>
<box size="0.12 0.025 0.034"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.00212 -0.0212 -0.0184"/>
<mass value="0.482"/>
<inertia ixx="0.00101" ixy="2.23e-05" ixz="-3.85e-05" iyy="0.000983" iyz="0.000199" izz="0.000347"/>
</inertial>
</link>
<joint name="FL_hip_rotor_fix" type="fixed">
<origin rpy="0 0 0" xyz="0 -0.07577 0"/>
<parent link="FL_hip"/>
<child link="FL_hip_rotor"/>
</joint>
<!-- this link is only for hip rotor inertial -->
<link name="FL_hip_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.0567"/>
<inertia ixx="2.53e-05" ixy="0" ixz="0" iyy="4.78e-05" iyz="0" izz="2.53e-05"/>
</inertial>
</link>
<joint name="FL_knee_rotor_fix" type="fixed">
<origin rpy="0 0 0" xyz="0 -0.0342303 0"/>
<parent link="FL_hip"/>
<child link="FL_knee_rotor"/>
</joint>
<!-- this link is only for knee rotor inertial -->
<link name="FL_knee_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.0567"/>
<inertia ixx="2.53e-05" ixy="0" ixz="0" iyy="4.78e-05" iyz="0" izz="2.53e-05"/>
</inertial>
</link>
<joint name="FL_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.12"/>
<parent link="FL_hip"/>
<child link="FL_knee"/>
<axis xyz="0 1 0"/>
<dynamics damping="0.01" friction="0.1"/>
<limit effort="12.0001" lower="-2.5307274153917776" upper="-0.5235987755982988" velocity="30.9971"/>
</joint>
<link name="FL_knee">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/cyberdog_description/share/cyberdog_description/meshes/knee.dae" scale="1 1 1"/>
</geometry>
</visual>
<collision>
<origin rpy="0 3.141592653589793 0" xyz="0 0 -0.091705"/>
<geometry>
<box size="0.016 0.016 0.18341"/>
</geometry>
</collision>
<collision name="FL_knee_rubber">
<origin rpy="0 3.141592653589793 0" xyz="-0.01 0 -0.007"/>
<geometry>
<sphere radius="0.016"/>
</geometry>
<surface>
<contact>
<ode>
<max_vel>0.00001</max_vel>
<min_depth>0.0</min_depth>
</ode>
</contact>
</surface>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.0006 -4.72e-05 -0.0893"/>
<mass value="0.116"/>
<inertia ixx="0.000668" ixy="3e-09" ixz="2.37e-05" iyy="0.000674" iyz="6.03e-07" izz="1.54e-05"/>
</inertial>
</link>
<joint name="FL_foot_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0.0055 0 -0.17390999999999998"/>
<parent link="FL_knee"/>
<child link="FL_foot"/>
</joint>
<link name="FL_foot">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.009"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.019"/>
</geometry>
<surface>
<contact>
<ode>
<max_vel>0.001</max_vel>
<min_depth>0.0</min_depth>
</ode>
</contact>
</surface>
</collision>
</link>
<transmission name="FL_abad_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FL_abad_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FL_abad_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>&quot;7.75&quot;</mechanicalReduction>
</actuator>
</transmission>
<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>&quot;7.75&quot;</mechanicalReduction>
</actuator>
</transmission>
<transmission name="FL_knee_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="FL_knee_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="FL_knee_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>&quot;7.75&quot;</mechanicalReduction>
</actuator>
</transmission>
<gazebo reference="FL_abad">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<visual>
<material>
<ambient>.5 .5 .5 1.0</ambient>
<diffuse>.5 .5 .5 1.0</diffuse>
<specular>.5 .5 .5 1.0</specular>
</material>
</visual>
</gazebo>
<gazebo reference="FL_hip">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<visual>
<material>
<ambient>.05 .05 .05 1.0</ambient>
<diffuse>.05 .05 .05 1.0</diffuse>
<specular>.05 .05 .05 1.0</specular>
</material>
</visual>
</gazebo>
<gazebo reference="FL_knee">
<mu1>0.7</mu1>
<mu2>0.7</mu2>
<self_collide>1</self_collide>
<visual>
<material>
<ambient>.5 .5 .5 1.0</ambient>
<diffuse>.5 .5 .5 1.0</diffuse>
<specular>.5 .5 .5 1.0</specular>
</material>
</visual>
</gazebo>
<gazebo reference="FL_foot">
<mu1>0.7</mu1>
<mu2>0.7</mu2>
<self_collide>1</self_collide>
<visual>
<material>
<ambient>.5 .5 .5 1.0</ambient>
<diffuse>.5 .5 .5 1.0</diffuse>
<specular>.5 .5 .5 1.0</specular>
</material>
</visual>
</gazebo>
<joint name="RR_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="-0.164 -0.042 0"/>
<parent link="body"/>
<child link="RR_abad"/>
<axis xyz="1 0 0"/>
<dynamics damping="0.01" friction="0.1"/>
<limit effort="12.0001" lower="-0.6806784082777885" upper="0.6806784082777885" velocity="30.9971"/>
</joint>
<link name="RR_abad">
<visual>
<origin rpy="3.141592653589793 3.141592653589793 0" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/cyberdog_description/share/cyberdog_description/meshes/abad.dae" scale="1 1 1"/>
</geometry>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.035" radius="0.039"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.00392 -0.015 -0.000306"/>
<mass value="0.354"/>
<inertia ixx="0.00019" ixy="-2.7e-05" ixz="3.44e-07" iyy="0.000276" iyz="-1.95e-06" izz="0.000233"/>
</inertial>
</link>
<joint name="RR_abad_rotor_fix" type="fixed">
<origin rpy="0 0 0" xyz="0.0642303 0 0"/>
<parent link="RR_abad"/>
<child link="RR_abad_rotor"/>
</joint>
<!-- this link is only for abad rotor inertial -->
<link name="RR_abad_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.0567"/>
<inertia ixx="2.53e-05" ixy="0" ixz="0" iyy="4.78e-05" iyz="0" izz="2.53e-05"/>
</inertial>
</link>
<joint name="RR_abad_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 -0.059 0"/>
<parent link="RR_abad"/>
<child link="RR_hip_shoulder"/>
</joint>
<link name="RR_hip_shoulder">
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.035" radius="0.039"/>
</geometry>
</collision>
</link>
<joint name="RR_thigh_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 -0.094 0"/>
<parent link="RR_abad"/>
<child link="RR_hip"/>
<axis xyz="0 1 0"/>
<dynamics damping="0.01" friction="0.1"/>
<limit effort="12.0001" lower="-0.9773843811168246" upper="3.141592653589793" velocity="30.9971"/>
</joint>
<link name="RR_hip">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/cyberdog_description/share/cyberdog_description/meshes/hip_mirror.dae" scale="1 1 1"/>
</geometry>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.06"/>
<geometry>
<box size="0.12 0.025 0.034"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.00212 0.0212 -0.0184"/>
<mass value="0.482"/>
<inertia ixx="0.00101" ixy="-2.23e-05" ixz="-3.85e-05" iyy="0.000983" iyz="-0.000199" izz="0.000347"/>
</inertial>
</link>
<joint name="RR_hip_rotor_fix" type="fixed">
<origin rpy="0 0 0" xyz="0 0.07577 0"/>
<parent link="RR_hip"/>
<child link="RR_hip_rotor"/>
</joint>
<!-- this link is only for hip rotor inertial -->
<link name="RR_hip_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.0567"/>
<inertia ixx="2.53e-05" ixy="0" ixz="0" iyy="4.78e-05" iyz="0" izz="2.53e-05"/>
</inertial>
</link>
<joint name="RR_knee_rotor_fix" type="fixed">
<origin rpy="0 0 0" xyz="0 0.0342303 0"/>
<parent link="RR_hip"/>
<child link="RR_knee_rotor"/>
</joint>
<!-- this link is only for knee rotor inertial -->
<link name="RR_knee_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.0567"/>
<inertia ixx="2.53e-05" ixy="0" ixz="0" iyy="4.78e-05" iyz="0" izz="2.53e-05"/>
</inertial>
</link>
<joint name="RR_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.12"/>
<parent link="RR_hip"/>
<child link="RR_knee"/>
<axis xyz="0 1 0"/>
<dynamics damping="0.01" friction="0.1"/>
<limit effort="12.0001" lower="-2.5307274153917776" upper="-0.5235987755982988" velocity="30.9971"/>
</joint>
<link name="RR_knee">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/cyberdog_description/share/cyberdog_description/meshes/knee.dae" scale="1 1 1"/>
</geometry>
</visual>
<collision>
<origin rpy="0 3.141592653589793 0" xyz="0 0 -0.091705"/>
<geometry>
<box size="0.016 0.016 0.18341"/>
</geometry>
</collision>
<collision name="RR_knee_rubber">
<origin rpy="0 3.141592653589793 0" xyz="-0.01 0 -0.007"/>
<geometry>
<sphere radius="0.016"/>
</geometry>
<surface>
<contact>
<ode>
<max_vel>0.00001</max_vel>
<min_depth>0.0</min_depth>
</ode>
</contact>
</surface>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.0006 -4.72e-05 -0.0893"/>
<mass value="0.116"/>
<inertia ixx="0.000668" ixy="3e-09" ixz="2.37e-05" iyy="0.000674" iyz="6.03e-07" izz="1.54e-05"/>
</inertial>
</link>
<joint name="RR_foot_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0.0055 0 -0.17390999999999998"/>
<parent link="RR_knee"/>
<child link="RR_foot"/>
</joint>
<link name="RR_foot">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.009"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.019"/>
</geometry>
<surface>
<contact>
<ode>
<max_vel>0.001</max_vel>
<min_depth>0.0</min_depth>
</ode>
</contact>
</surface>
</collision>
</link>
<transmission name="RR_abad_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="RR_abad_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="RR_abad_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>&quot;7.75&quot;</mechanicalReduction>
</actuator>
</transmission>
<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>&quot;7.75&quot;</mechanicalReduction>
</actuator>
</transmission>
<transmission name="RR_knee_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="RR_knee_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="RR_knee_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>&quot;7.75&quot;</mechanicalReduction>
</actuator>
</transmission>
<gazebo reference="RR_abad">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<visual>
<material>
<ambient>.5 .5 .5 1.0</ambient>
<diffuse>.5 .5 .5 1.0</diffuse>
<specular>.5 .5 .5 1.0</specular>
</material>
</visual>
</gazebo>
<gazebo reference="RR_hip">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<visual>
<material>
<ambient>.05 .05 .05 1.0</ambient>
<diffuse>.05 .05 .05 1.0</diffuse>
<specular>.05 .05 .05 1.0</specular>
</material>
</visual>
</gazebo>
<gazebo reference="RR_knee">
<mu1>0.7</mu1>
<mu2>0.7</mu2>
<self_collide>1</self_collide>
<visual>
<material>
<ambient>.5 .5 .5 1.0</ambient>
<diffuse>.5 .5 .5 1.0</diffuse>
<specular>.5 .5 .5 1.0</specular>
</material>
</visual>
</gazebo>
<gazebo reference="RR_foot">
<mu1>0.7</mu1>
<mu2>0.7</mu2>
<self_collide>1</self_collide>
<visual>
<material>
<ambient>.5 .5 .5 1.0</ambient>
<diffuse>.5 .5 .5 1.0</diffuse>
<specular>.5 .5 .5 1.0</specular>
</material>
</visual>
</gazebo>
<joint name="RL_hip_joint" type="revolute">
<origin rpy="0 0 0" xyz="-0.164 0.042 0"/>
<parent link="body"/>
<child link="RL_abad"/>
<axis xyz="1 0 0"/>
<dynamics damping="0.01" friction="0.1"/>
<limit effort="12.0001" lower="-0.6806784082777885" upper="0.6806784082777885" velocity="30.9971"/>
</joint>
<link name="RL_abad">
<visual>
<origin rpy="0 3.141592653589793 0" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/cyberdog_description/share/cyberdog_description/meshes/abad.dae" scale="1 1 1"/>
</geometry>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.035" radius="0.039"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.00392 0.015 -0.000306"/>
<mass value="0.354"/>
<inertia ixx="0.00019" ixy="2.7e-05" ixz="3.44e-07" iyy="0.000276" iyz="1.95e-06" izz="0.000233"/>
</inertial>
</link>
<joint name="RL_abad_rotor_fix" type="fixed">
<origin rpy="0 0 0" xyz="0.0642303 0 0"/>
<parent link="RL_abad"/>
<child link="RL_abad_rotor"/>
</joint>
<!-- this link is only for abad rotor inertial -->
<link name="RL_abad_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.0567"/>
<inertia ixx="2.53e-05" ixy="0" ixz="0" iyy="4.78e-05" iyz="0" izz="2.53e-05"/>
</inertial>
</link>
<joint name="RL_abad_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0 0.059 0"/>
<parent link="RL_abad"/>
<child link="RL_hip_shoulder"/>
</joint>
<link name="RL_hip_shoulder">
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.035" radius="0.039"/>
</geometry>
</collision>
</link>
<joint name="RL_thigh_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0.094 0"/>
<parent link="RL_abad"/>
<child link="RL_hip"/>
<axis xyz="0 1 0"/>
<dynamics damping="0.01" friction="0.1"/>
<limit effort="12.0001" lower="-0.9773843811168246" upper="3.141592653589793" velocity="30.9971"/>
</joint>
<link name="RL_hip">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/cyberdog_description/share/cyberdog_description/meshes/hip.dae" scale="1 1 1"/>
</geometry>
</visual>
<collision>
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.06"/>
<geometry>
<box size="0.12 0.025 0.034"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.00212 -0.0212 -0.0184"/>
<mass value="0.482"/>
<inertia ixx="0.00101" ixy="2.23e-05" ixz="-3.85e-05" iyy="0.000983" iyz="0.000199" izz="0.000347"/>
</inertial>
</link>
<joint name="RL_hip_rotor_fix" type="fixed">
<origin rpy="0 0 0" xyz="0 -0.07577 0"/>
<parent link="RL_hip"/>
<child link="RL_hip_rotor"/>
</joint>
<!-- this link is only for hip rotor inertial -->
<link name="RL_hip_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.0567"/>
<inertia ixx="2.53e-05" ixy="0" ixz="0" iyy="4.78e-05" iyz="0" izz="2.53e-05"/>
</inertial>
</link>
<joint name="RL_knee_rotor_fix" type="fixed">
<origin rpy="0 0 0" xyz="0 -0.0342303 0"/>
<parent link="RL_hip"/>
<child link="RL_knee_rotor"/>
</joint>
<!-- this link is only for knee rotor inertial -->
<link name="RL_knee_rotor">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.0567"/>
<inertia ixx="2.53e-05" ixy="0" ixz="0" iyy="4.78e-05" iyz="0" izz="2.53e-05"/>
</inertial>
</link>
<joint name="RL_calf_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 -0.12"/>
<parent link="RL_hip"/>
<child link="RL_knee"/>
<axis xyz="0 1 0"/>
<dynamics damping="0.01" friction="0.1"/>
<limit effort="12.0001" lower="-2.5307274153917776" upper="-0.5235987755982988" velocity="30.9971"/>
</joint>
<link name="RL_knee">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/tlab-uav/ros2_ws/install/cyberdog_description/share/cyberdog_description/meshes/knee.dae" scale="1 1 1"/>
</geometry>
</visual>
<collision>
<origin rpy="0 3.141592653589793 0" xyz="0 0 -0.091705"/>
<geometry>
<box size="0.016 0.016 0.18341"/>
</geometry>
</collision>
<collision name="RL_knee_rubber">
<origin rpy="0 3.141592653589793 0" xyz="-0.01 0 -0.007"/>
<geometry>
<sphere radius="0.016"/>
</geometry>
<surface>
<contact>
<ode>
<max_vel>0.00001</max_vel>
<min_depth>0.0</min_depth>
</ode>
</contact>
</surface>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.0006 -4.72e-05 -0.0893"/>
<mass value="0.116"/>
<inertia ixx="0.000668" ixy="3e-09" ixz="2.37e-05" iyy="0.000674" iyz="6.03e-07" izz="1.54e-05"/>
</inertial>
</link>
<joint name="RL_foot_fixed" type="fixed">
<origin rpy="0 0 0" xyz="0.0055 0 -0.17390999999999998"/>
<parent link="RL_knee"/>
<child link="RL_foot"/>
</joint>
<link name="RL_foot">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.009"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.019"/>
</geometry>
<surface>
<contact>
<ode>
<max_vel>0.001</max_vel>
<min_depth>0.0</min_depth>
</ode>
</contact>
</surface>
</collision>
</link>
<transmission name="RL_abad_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="RL_abad_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="RL_abad_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>&quot;7.75&quot;</mechanicalReduction>
</actuator>
</transmission>
<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>&quot;7.75&quot;</mechanicalReduction>
</actuator>
</transmission>
<transmission name="RL_knee_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="RL_knee_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="RL_knee_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>&quot;7.75&quot;</mechanicalReduction>
</actuator>
</transmission>
<gazebo reference="RL_abad">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<visual>
<material>
<ambient>.5 .5 .5 1.0</ambient>
<diffuse>.5 .5 .5 1.0</diffuse>
<specular>.5 .5 .5 1.0</specular>
</material>
</visual>
</gazebo>
<gazebo reference="RL_hip">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<visual>
<material>
<ambient>.05 .05 .05 1.0</ambient>
<diffuse>.05 .05 .05 1.0</diffuse>
<specular>.05 .05 .05 1.0</specular>
</material>
</visual>
</gazebo>
<gazebo reference="RL_knee">
<mu1>0.7</mu1>
<mu2>0.7</mu2>
<self_collide>1</self_collide>
<visual>
<material>
<ambient>.5 .5 .5 1.0</ambient>
<diffuse>.5 .5 .5 1.0</diffuse>
<specular>.5 .5 .5 1.0</specular>
</material>
</visual>
</gazebo>
<gazebo reference="RL_foot">
<mu1>0.7</mu1>
<mu2>0.7</mu2>
<self_collide>1</self_collide>
<visual>
<material>
<ambient>.5 .5 .5 1.0</ambient>
<diffuse>.5 .5 .5 1.0</diffuse>
<specular>.5 .5 .5 1.0</specular>
</material>
</visual>
</gazebo>
<!-- This link is only for head collision -->
<joint name="head_joint" type="fixed">
<parent link="body"/>
<child link="head"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</joint>
<link name="head">
<collision>
<origin rpy="0 0 0" xyz="0.256 0 0.120"/>
<geometry>
<box size="0.076 0.060 0.040"/>
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="0.225 0 0.150"/>
<geometry>
<box size="0.020 0.080 0.100"/>
</geometry>
</collision>
</link>
<gazebo reference="body">
<visual>
<material>
<ambient>.1 .1 .1 1.0</ambient>
<diffuse>.1 .1 .1 1.0</diffuse>
<specular>.1 .1 .1 1.0</specular>
</material>
</visual>
</gazebo>
</robot>