105 lines
4.7 KiB
Plaintext
105 lines
4.7 KiB
Plaintext
|
<?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"/>
|
||
|
|
||
|
<!-- 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"/>
|
||
|
<xacro:property name="hip_velocity_max" value="20"/>
|
||
|
<xacro:property name="hip_torque_max" value="100"/>
|
||
|
<xacro:property name="thigh_position_max" value="3.5"/>
|
||
|
<xacro:property name="thigh_position_min" value="-1.0"/>
|
||
|
<xacro:property name="thigh_velocity_max" value="20"/>
|
||
|
<xacro:property name="thigh_torque_max" value="100"/>
|
||
|
<xacro:property name="calf_position_max" value="-0.6"/>
|
||
|
<xacro:property name="calf_position_min" value="-2.6"/>
|
||
|
<xacro:property name="calf_velocity_max" value="20"/>
|
||
|
<xacro:property name="calf_torque_max" value="100"/>
|
||
|
|
||
|
<!-- dynamics inertial value -->
|
||
|
<!-- trunk -->
|
||
|
<xacro:property name="trunk_mass" value="18.276"/>
|
||
|
<xacro:property name="trunk_com_x" value="-0.01"/>
|
||
|
<xacro:property name="trunk_com_y" value="0.0"/>
|
||
|
<xacro:property name="trunk_com_z" value="0.00"/>
|
||
|
<xacro:property name="trunk_ixx" value="0.174426"/>
|
||
|
<xacro:property name="trunk_ixy" value="0.005544"/>
|
||
|
<xacro:property name="trunk_ixz" value="0.003278"/>
|
||
|
<xacro:property name="trunk_iyy" value="0.700100"/>
|
||
|
<xacro:property name="trunk_iyz" value="0.000007"/>
|
||
|
<xacro:property name="trunk_izz" value="0.785955"/>
|
||
|
|
||
|
<!-- hip (left front) -->
|
||
|
<xacro:property name="hip_mass" value="1.998"/>
|
||
|
<xacro:property name="hip_com_x" value="-0.020298"/>
|
||
|
<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.004066"/>
|
||
|
<xacro:property name="hip_ixy" value="-0.000288"/>
|
||
|
<xacro:property name="hip_ixz" value="0.000000"/>
|
||
|
<xacro:property name="hip_iyy" value="0.008775"/>
|
||
|
<xacro:property name="hip_iyz" value="-0.000000"/>
|
||
|
<xacro:property name="hip_izz" value="0.006060"/>
|
||
|
|
||
|
<!-- thigh -->
|
||
|
<xacro:property name="thigh_mass" value="3.444"/>
|
||
|
<xacro:property name="thigh_com_x" value="0.0050"/>
|
||
|
<xacro:property name="thigh_com_y" value="-0.0250"/>
|
||
|
<xacro:property name="thigh_com_z" value="-0.0512"/>
|
||
|
<xacro:property name="thigh_ixx" value="0.035982"/>
|
||
|
<xacro:property name="thigh_ixy" value="0.000032"/>
|
||
|
<xacro:property name="thigh_ixz" value="0.001385"/>
|
||
|
<xacro:property name="thigh_iyy" value="0.037758"/>
|
||
|
<xacro:property name="thigh_iyz" value="-0.004234"/>
|
||
|
<xacro:property name="thigh_izz" value="0.006637"/>
|
||
|
|
||
|
<!-- calf -->
|
||
|
<xacro:property name="calf_mass" value="0.803"/>
|
||
|
<xacro:property name="calf_com_x" value="0.00565"/>
|
||
|
<xacro:property name="calf_com_y" value="-0.000236"/>
|
||
|
<xacro:property name="calf_com_z" value="-0.150538"/>
|
||
|
<xacro:property name="calf_ixx" value="0.017617"/>
|
||
|
<xacro:property name="calf_ixy" value="0.000000"/>
|
||
|
<xacro:property name="calf_ixz" value="-0.000532"/>
|
||
|
<xacro:property name="calf_iyy" value="0.017722"/>
|
||
|
<xacro:property name="calf_iyz" value="-0.000030"/>
|
||
|
<xacro:property name="calf_izz" value="0.000409"/>
|
||
|
|
||
|
<!-- foot -->
|
||
|
<xacro:property name="foot_mass" value="0.05"/>
|
||
|
|
||
|
</robot>
|