unitree_ros/robots/b1_description/xacro/b1.urdf

1212 lines
39 KiB
Plaintext
Raw Normal View History

2022-11-11 22:29:30 +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="b1_description">
<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">
2022-11-11 22:29:30 +08:00
<color rgba="0.9137254901960784 0.9137254901960784 0.8470588235294118 1.0"/>
</material>
<material name="orange">
2022-11-11 22:29:30 +08:00
<color rgba="1.0 0.4235294117647059 0.0392156862745098 1.0"/>
</material>
<material name="brown">
2022-11-11 22:29:30 +08:00
<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>
<!-- ros_control plugin -->
<gazebo>
<plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control">
<robotNamespace>/aliengo_gazebo</robotNamespace>
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
</plugin>
</gazebo>
<!-- Show the trajectory of trunk center. -->
<gazebo>
<plugin filename="libLinkPlot3DPlugin.so" name="3dplot">
<frequency>10</frequency>
<plot>
<link>base</link>
<pose>0 0 0 0 0 0</pose>
<material>Gazebo/Yellow</material>
</plot>
</plugin>
</gazebo>
<!-- Show the trajectory of foot. You can add another trajectory about another foot. -->
<!-- <gazebo>
<plugin name="3dplot" filename="libLinkPlot3DPlugin.so">
<frequency>100</frequency>
<plot>
<link>FL_foot</link>
<pose>0 0 0 0 0 0</pose>
<material>Gazebo/Green</material>
</plot>
</plugin>
</gazebo> -->
<gazebo>
<plugin filename="libgazebo_ros_force.so" name="gazebo_ros_force">
<bodyName>trunk</bodyName>
<topicName>/apply_force/trunk</topicName>
</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>
<!-- Foot contacts. -->
<gazebo reference="FR_calf">
<sensor name="FR_foot_contact" type="contact">
<update_rate>100</update_rate>
<plugin filename="libunitreeFootContactPlugin.so" name="contactPlugin"/>
<contact>
<collision>FR_calf_fixed_joint_lump__FR_foot_collision_1</collision>
</contact>
</sensor>
</gazebo>
<gazebo reference="FL_calf">
<sensor name="FL_foot_contact" type="contact">
<update_rate>100</update_rate>
<plugin filename="libunitreeFootContactPlugin.so" name="contactPlugin"/>
<contact>
<collision>FL_calf_fixed_joint_lump__FL_foot_collision_1</collision>
</contact>
</sensor>
</gazebo>
<gazebo reference="RR_calf">
<sensor name="RR_foot_contact" type="contact">
<update_rate>100</update_rate>
<plugin filename="libunitreeFootContactPlugin.so" name="contactPlugin"/>
<contact>
<collision>RR_calf_fixed_joint_lump__RR_foot_collision_1</collision>
</contact>
</sensor>
</gazebo>
<gazebo reference="RL_calf">
<sensor name="RL_foot_contact" type="contact">
<update_rate>100</update_rate>
<plugin filename="libunitreeFootContactPlugin.so" name="contactPlugin"/>
<contact>
<collision>RL_calf_fixed_joint_lump__RL_foot_collision_1</collision>
</contact>
</sensor>
</gazebo>
<!-- Visualization of Foot contacts. -->
<gazebo reference="FR_foot">
<visual>
<plugin filename="libunitreeDrawForcePlugin.so" name="drawForcePlugin">
<topicName>FR_foot_contact</topicName>
</plugin>
</visual>
</gazebo>
<gazebo reference="FL_foot">
<visual>
<plugin filename="libunitreeDrawForcePlugin.so" name="drawForcePlugin">
<topicName>FL_foot_contact</topicName>
</plugin>
</visual>
</gazebo>
<gazebo reference="RR_foot">
<visual>
<plugin filename="libunitreeDrawForcePlugin.so" name="drawForcePlugin">
<topicName>RR_foot_contact</topicName>
</plugin>
</visual>
</gazebo>
<gazebo reference="RL_foot">
<visual>
<plugin filename="libunitreeDrawForcePlugin.so" name="drawForcePlugin">
<topicName>RL_foot_contact</topicName>
</plugin>
</visual>
</gazebo>
<gazebo reference="base">
<material>Gazebo/Green</material>
<turnGravityOff>false</turnGravityOff>
</gazebo>
<gazebo reference="trunk">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="stick_link">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<material>Gazebo/White</material>
</gazebo>
<gazebo reference="imu_link">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<material>Gazebo/Red</material>
</gazebo>
<!-- FL leg -->
<gazebo reference="FL_hip">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<material>Gazebo/DarkGrey</material>
</gazebo>
<gazebo reference="FL_thigh">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<material>Gazebo/DarkGrey</material>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="FL_calf">
<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>
<material>Gazebo/DarkGrey</material>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<!-- FR leg -->
<gazebo reference="FR_hip">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<material>Gazebo/DarkGrey</material>
</gazebo>
<gazebo reference="FR_thigh">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<material>Gazebo/DarkGrey</material>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="FR_calf">
<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>
<material>Gazebo/DarkGrey</material>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<!-- RL leg -->
<gazebo reference="RL_hip">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<material>Gazebo/DarkGrey</material>
</gazebo>
<gazebo reference="RL_thigh">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<material>Gazebo/DarkGrey</material>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="RL_calf">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
</gazebo>
<gazebo reference="RL_foot">
<mu1>0.6</mu1>
<mu2>0.6</mu2>
<self_collide>1</self_collide>
<material>Gazebo/DarkGrey</material>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<!-- RR leg -->
<gazebo reference="RR_hip">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<material>Gazebo/DarkGrey</material>
</gazebo>
<gazebo reference="RR_thigh">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
<material>Gazebo/DarkGrey</material>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
<gazebo reference="RR_calf">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<self_collide>1</self_collide>
</gazebo>
<gazebo reference="RR_foot">
<mu1>0.6</mu1>
<mu2>0.6</mu2>
<self_collide>1</self_collide>
<material>Gazebo/DarkGrey</material>
<kp value="1000000.0"/>
<kd value="1.0"/>
</gazebo>
2022-11-11 22:29:30 +08:00
<!-- 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>
<box size="0.001 0.001 0.001"/>
</geometry>
</visual>
</link>
<joint name="floating_base" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="base"/>
<child link="trunk"/>
</joint>
<link name="trunk">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://b1_description/meshes/trunk.dae" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.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.dae" scale="1 1 1"/>
</geometry>
</collision> -->
<inertial>
2022-11-11 22:29:30 +08:00
<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="trunk"/>
<child link="imu_link"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</joint>
<link name="imu_link">
<inertial>
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.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="trunk"/>
<child link="FR_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
2022-11-11 22:29:30 +08:00
<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="trunk"/>
<child link="FR_hip_rotor"/>
</joint>
<link name="FR_hip">
<visual>
2022-11-11 22:29:30 +08:00
<origin rpy="3.141592653589793 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://b1_description/meshes/hip.dae" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
2022-11-11 22:29:30 +08:00
<origin rpy="1.5707963267948966 0 0" xyz="0 -0.12675 0"/>
<geometry>
<cylinder length="0.04" radius="0.09"/>
</geometry>
</collision>
<inertial>
2022-11-11 22:29:30 +08:00
<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>
2022-11-11 22:29:30 +08:00
<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"/>
2022-11-11 22:29:30 +08:00
<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.dae" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
2022-11-11 22:29:30 +08:00
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.175"/>
<geometry>
<box size="0.35 0.05 0.08"/>
</geometry>
</collision>
<inertial>
2022-11-11 22:29:30 +08:00
<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"/>
2022-11-11 22:29:30 +08:00
<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.dae" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
2022-11-11 22:29:30 +08:00
<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>
2022-11-11 22:29:30 +08:00
<cylinder length="0.02" radius="0.05"/>
</geometry>
</collision>
<inertial>
2022-11-11 22:29:30 +08:00
<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>
2022-11-11 22:29:30 +08:00
<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="trunk"/>
<child link="FL_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
2022-11-11 22:29:30 +08:00
<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="trunk"/>
<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.dae" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
2022-11-11 22:29:30 +08:00
<origin rpy="1.5707963267948966 0 0" xyz="0 0.12675 0"/>
<geometry>
<cylinder length="0.04" radius="0.09"/>
</geometry>
</collision>
<inertial>
2022-11-11 22:29:30 +08:00
<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>
2022-11-11 22:29:30 +08:00
<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"/>
2022-11-11 22:29:30 +08:00
<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.dae" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
2022-11-11 22:29:30 +08:00
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.175"/>
<geometry>
<box size="0.35 0.05 0.08"/>
</geometry>
</collision>
<inertial>
2022-11-11 22:29:30 +08:00
<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"/>
2022-11-11 22:29:30 +08:00
<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.dae" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
2022-11-11 22:29:30 +08:00
<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>
2022-11-11 22:29:30 +08:00
<cylinder length="0.02" radius="0.05"/>
</geometry>
</collision>
<inertial>
2022-11-11 22:29:30 +08:00
<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>
2022-11-11 22:29:30 +08:00
<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="trunk"/>
<child link="RR_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
2022-11-11 22:29:30 +08:00
<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="trunk"/>
<child link="RR_hip_rotor"/>
</joint>
<link name="RR_hip">
<visual>
2022-11-11 22:29:30 +08:00
<origin rpy="3.141592653589793 3.141592653589793 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://b1_description/meshes/hip.dae" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
2022-11-11 22:29:30 +08:00
<origin rpy="1.5707963267948966 0 0" xyz="0 -0.12675 0"/>
<geometry>
<cylinder length="0.04" radius="0.09"/>
</geometry>
</collision>
<inertial>
2022-11-11 22:29:30 +08:00
<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>
2022-11-11 22:29:30 +08:00
<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"/>
2022-11-11 22:29:30 +08:00
<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.dae" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
2022-11-11 22:29:30 +08:00
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.175"/>
<geometry>
<box size="0.35 0.05 0.08"/>
</geometry>
</collision>
<inertial>
2022-11-11 22:29:30 +08:00
<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"/>
2022-11-11 22:29:30 +08:00
<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.dae" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
2022-11-11 22:29:30 +08:00
<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>
2022-11-11 22:29:30 +08:00
<cylinder length="0.02" radius="0.05"/>
</geometry>
</collision>
<inertial>
2022-11-11 22:29:30 +08:00
<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>
2022-11-11 22:29:30 +08:00
<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="trunk"/>
<child link="RL_hip"/>
<axis xyz="1 0 0"/>
<dynamics damping="0" friction="0"/>
2022-11-11 22:29:30 +08:00
<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="trunk"/>
<child link="RL_hip_rotor"/>
</joint>
<link name="RL_hip">
<visual>
2022-11-11 22:29:30 +08:00
<origin rpy="0 3.141592653589793 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://b1_description/meshes/hip.dae" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
2022-11-11 22:29:30 +08:00
<origin rpy="1.5707963267948966 0 0" xyz="0 0.12675 0"/>
<geometry>
<cylinder length="0.04" radius="0.09"/>
</geometry>
</collision>
<inertial>
2022-11-11 22:29:30 +08:00
<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>
2022-11-11 22:29:30 +08:00
<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"/>
2022-11-11 22:29:30 +08:00
<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.dae" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
2022-11-11 22:29:30 +08:00
<origin rpy="0 1.5707963267948966 0" xyz="0 0 -0.175"/>
<geometry>
<box size="0.35 0.05 0.08"/>
</geometry>
</collision>
<inertial>
2022-11-11 22:29:30 +08:00
<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"/>
2022-11-11 22:29:30 +08:00
<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.dae" scale="1 1 1"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
2022-11-11 22:29:30 +08:00
<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>
2022-11-11 22:29:30 +08:00
<cylinder length="0.02" radius="0.05"/>
</geometry>
</collision>
<inertial>
2022-11-11 22:29:30 +08:00
<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>
2022-11-11 22:29:30 +08:00
<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>