unitree_ros/robots/b1_description/xacro/const.xacro

161 lines
7.6 KiB
Plaintext
Raw Normal View History

<?xml version="1.0"?>
<robot name="b1_description" xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- Constants for robot dimensions -->
<xacro:property name="PI" value="3.1415926535897931"/>
<xacro:property name="stick_mass" value="0.00001"/>
<!-- simplified collision value -->
<xacro:property name="trunk_width" value="0.30"/>
<xacro:property name="trunk_length" value="0.647"/>
<xacro:property name="trunk_height" value="0.15"/>
<xacro:property name="hip_radius" value="0.09"/>
<xacro:property name="hip_length" value="0.04"/>
<xacro:property name="thigh_shoulder_radius" value="0.044"/>
<xacro:property name="thigh_shoulder_length" value="0.08"/>
<xacro:property name="thigh_width" value="0.05"/>
<xacro:property name="thigh_height" value="0.08"/>
<xacro:property name="calf_width" value="0.04"/>
<xacro:property name="calf_height" value="0.05"/>
<xacro:property name="foot_radius" value="0.04"/>
<xacro:property name="stick_radius" value="0.01"/>
<xacro:property name="stick_length" value="0.2"/>
<!-- kinematic value -->
<xacro:property name="thigh_offset" value="0.12675"/>
<xacro:property name="thigh_length" value="0.35"/>
<xacro:property name="calf_length" value="0.35"/>
<!-- leg offset from trunk center value -->
<xacro:property name="leg_offset_x" value="0.3455"/>
<xacro:property name="leg_offset_y" value="0.072"/>
<xacro:property name="trunk_offset_z" value="0.01675"/>
<xacro:property name="hip_offset" value="0.12675"/>
2022-11-11 02:20:34 +08:00
<!-- offset of link and rotor locations (left front) -->
<xacro:property name="hip_offset_x" value="0.3455"/>
<xacro:property name="hip_offset_y" value="0.072"/>
<xacro:property name="hip_offset_z" value="0.0"/>
<xacro:property name="hip_rotor_offset_x" value="0.1955"/>
<xacro:property name="hip_rotor_offset_y" value="0.072"/>
<xacro:property name="hip_rotor_offset_z" value="0.0"/>
<xacro:property name="thigh_offset_x" value="0"/>
<xacro:property name="thigh_offset_y" value="0.12675"/>
<xacro:property name="thigh_offset_z" value="0.0"/>
<xacro:property name="thigh_rotor_offset_x" value="0.0"/>
<xacro:property name="thigh_rotor_offset_y" value="0.00935"/>
<xacro:property name="thigh_rotor_offset_z" value="0.0"/>
<xacro:property name="calf_offset_x" value="0.0"/>
<xacro:property name="calf_offset_y" value="0.0"/>
<xacro:property name="calf_offset_z" value="-0.35"/>
<xacro:property name="calf_rotor_offset_x" value="0.0"/>
<xacro:property name="calf_rotor_offset_y" value="-0.0519"/>
<xacro:property name="calf_rotor_offset_z" value="0.0"/>
<!-- joint limits -->
<xacro:property name="damping" value="0"/>
<xacro:property name="friction" value="0"/>
<xacro:property name="hip_position_max" value="0.75"/>
<xacro:property name="hip_position_min" value="-0.75"/>
2022-11-11 02:00:55 +08:00
<xacro:property name="hip_velocity_max" value="19.69"/>
<xacro:property name="hip_torque_max" value="91.0035"/>
<xacro:property name="thigh_position_max" value="3.5"/>
<xacro:property name="thigh_position_min" value="-1.0"/>
2022-11-11 02:00:55 +08:00
<xacro:property name="thigh_velocity_max" value="23.32"/>
2022-11-11 22:29:30 +08:00
<xacro:property name="thigh_torque_max" value="93.33"/>
<xacro:property name="calf_position_max" value="-0.6"/>
<xacro:property name="calf_position_min" value="-2.6"/>
2022-11-11 02:00:55 +08:00
<xacro:property name="calf_velocity_max" value="15.55"/>
2022-11-11 22:29:30 +08:00
<xacro:property name="calf_torque_max" value="140"/>
<!-- dynamics inertial value -->
<!-- trunk -->
2022-11-11 02:00:55 +08:00
<xacro:property name="trunk_mass" value="25"/>
<xacro:property name="trunk_com_x" value="0.008987"/>
<xacro:property name="trunk_com_y" value="0.002243"/>
<xacro:property name="trunk_com_z" value="0.003013"/>
<xacro:property name="trunk_ixx" value="0.183142146"/>
<xacro:property name="trunk_ixy" value="-0.001379002"/>
<xacro:property name="trunk_ixz" value="-0.027956055"/>
<xacro:property name="trunk_iyy" value="0.756327752"/>
<xacro:property name="trunk_iyz" value="0.000193774"/>
<xacro:property name="trunk_izz" value="0.783777558"/>
<!-- hip (left front) -->
2022-11-11 02:00:55 +08:00
<xacro:property name="hip_mass" value="2.1"/>
<xacro:property name="hip_com_x" value="-0.020298"/>
2022-11-11 02:00:55 +08:00
<xacro:property name="hip_com_y" value="0.009758"/>
<xacro:property name="hip_com_z" value="0.000109"/>
<xacro:property name="hip_ixx" value="0.00406608"/>
<xacro:property name="hip_ixy" value="-0.000288071"/>
<xacro:property name="hip_ixz" value="-0.000004371"/>
<xacro:property name="hip_iyy" value="0.008775259"/>
<xacro:property name="hip_iyz" value="0.000001811"/>
<xacro:property name="hip_izz" value="0.006060348"/>
<xacro:property name="hip_rotor_mass" value="0.199"/>
<xacro:property name="hip_rotor_com_x" value="0.0"/>
<xacro:property name="hip_rotor_com_y" value="0.0"/>
<xacro:property name="hip_rotor_com_z" value="0.0"/>
<xacro:property name="hip_rotor_ixx" value="0.00039249"/>
<xacro:property name="hip_rotor_ixy" value="0.0"/>
<xacro:property name="hip_rotor_ixz" value="0.0"/>
<xacro:property name="hip_rotor_iyy" value="0.000219397"/>
<xacro:property name="hip_rotor_iyz" value="0.0"/>
<xacro:property name="hip_rotor_izz" value="0.000219397"/>
<!-- thigh -->
2022-11-11 02:00:55 +08:00
<xacro:property name="thigh_mass" value="3.934"/>
<xacro:property name="thigh_com_x" value="-0.000235"/>
<xacro:property name="thigh_com_y" value="-0.028704"/>
<xacro:property name="thigh_com_z" value="-0.054169"/>
<xacro:property name="thigh_ixx" value="0.044459086"/>
<xacro:property name="thigh_ixy" value="0.000128738"/>
<xacro:property name="thigh_ixz" value="-0.002343913"/>
<xacro:property name="thigh_iyy" value="0.046023457"/>
<xacro:property name="thigh_iyz" value="0.006032996"/>
<xacro:property name="thigh_izz" value="0.008696078"/>
<xacro:property name="thigh_rotor_mass" value="0.266"/>
<xacro:property name="thigh_rotor_com_x" value="0.0"/>
<xacro:property name="thigh_rotor_com_y" value="0.0"/>
<xacro:property name="thigh_rotor_com_z" value="0.0"/>
<xacro:property name="thigh_rotor_ixx" value="0.000485657"/>
<xacro:property name="thigh_rotor_ixy" value="0.0"/>
<xacro:property name="thigh_rotor_ixz" value="0.0"/>
<xacro:property name="thigh_rotor_iyy" value="0.00091885"/>
<xacro:property name="thigh_rotor_iyz" value="0.0"/>
<xacro:property name="thigh_rotor_izz" value="0.000485657"/>
<!-- calf -->
2022-11-11 02:00:55 +08:00
<xacro:property name="calf_mass" value="0.857"/>
<xacro:property name="calf_com_x" value="0.005237"/>
<xacro:property name="calf_com_y" value="0.0"/>
<xacro:property name="calf_com_z" value="-0.202805"/>
<xacro:property name="calf_ixx" value="0.015011003"/>
<xacro:property name="calf_ixy" value="0.000000052"/>
<xacro:property name="calf_ixz" value="0.000250042"/>
<xacro:property name="calf_iyy" value="0.015159462"/>
<xacro:property name="calf_iyz" value="0.000000461"/>
<xacro:property name="calf_izz" value="0.000375749"/>
<xacro:property name="calf_rotor_mass" value="0.266"/>
<xacro:property name="calf_rotor_com_x" value="0.0"/>
<xacro:property name="calf_rotor_com_y" value="0.0"/>
<xacro:property name="calf_rotor_com_z" value="0.0"/>
<xacro:property name="calf_rotor_ixx" value="0.000485657"/>
<xacro:property name="calf_rotor_ixy" value="0.0"/>
<xacro:property name="calf_rotor_ixz" value="0.0"/>
<xacro:property name="calf_rotor_iyy" value="0.00091885"/>
<xacro:property name="calf_rotor_iyz" value="0.0"/>
<xacro:property name="calf_rotor_izz" value="0.000485657"/>
<!-- foot -->
<xacro:property name="foot_mass" value="0.05"/>
</robot>