161 lines
7.3 KiB
XML
161 lines
7.3 KiB
XML
<?xml version="1.0"?>
|
|
|
|
<robot 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.150"/>
|
|
<xacro:property name="trunk_length" value="0.647"/>
|
|
<xacro:property name="trunk_height" value="0.112"/>
|
|
<xacro:property name="hip_radius" value="0.046"/>
|
|
<xacro:property name="hip_length" value="0.0418"/>
|
|
<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.0374"/>
|
|
<xacro:property name="thigh_height" value="0.043"/>
|
|
<xacro:property name="calf_width" value="0.0208"/>
|
|
<xacro:property name="calf_height" value="0.016"/>
|
|
<xacro:property name="foot_radius" value="0.0265"/>
|
|
<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.0868"/>
|
|
<xacro:property name="thigh_length" value="0.25"/>
|
|
<xacro:property name="calf_length" value="0.25"/>
|
|
|
|
<!-- leg offset from trunk center value -->
|
|
<xacro:property name="leg_offset_x" value="0.2407"/>
|
|
<xacro:property name="leg_offset_y" value="0.051"/>
|
|
<xacro:property name="trunk_offset_z" value="0.01675"/>
|
|
<xacro:property name="hip_offset" value="0.083"/>
|
|
|
|
<!-- offset of link and rotor locations (left front) -->
|
|
<xacro:property name="hip_offset_x" value="0.2407"/>
|
|
<xacro:property name="hip_offset_y" value="0.051"/>
|
|
<xacro:property name="hip_offset_z" value="0.0"/>
|
|
<xacro:property name="hip_rotor_offset_x" value="0.139985"/>
|
|
<xacro:property name="hip_rotor_offset_y" value="0.051"/>
|
|
<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.0868"/>
|
|
<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.0298"/>
|
|
<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.25"/>
|
|
<xacro:property name="calf_rotor_offset_x" value="0.0"/>
|
|
<xacro:property name="calf_rotor_offset_y" value="-0.0997"/>
|
|
<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="${70*PI/180.0}"/>
|
|
<xacro:property name="hip_position_min" value="${-70*PI/180.0}"/>
|
|
<xacro:property name="hip_velocity_max" value="20"/>
|
|
<xacro:property name="hip_torque_max" value="35.278"/>
|
|
<xacro:property name="thigh_position_max" value="${240*PI/180.0}"/>
|
|
<xacro:property name="thigh_position_min" value="${-120*PI/180.0}"/>
|
|
<xacro:property name="thigh_velocity_max" value="20"/>
|
|
<xacro:property name="thigh_torque_max" value="35.278"/>
|
|
<xacro:property name="calf_position_max" value="${-37*PI/180.0}"/>
|
|
<xacro:property name="calf_position_min" value="${-159*PI/180.0}"/>
|
|
<xacro:property name="calf_velocity_max" value="15.89"/>
|
|
<xacro:property name="calf_torque_max" value="44.4"/>
|
|
|
|
<!-- dynamics inertial value total 23.0kg -->
|
|
<!-- trunk -->
|
|
<xacro:property name="trunk_mass" value="11.644"/>
|
|
<xacro:property name="trunk_com_x" value="0.008811"/>
|
|
<xacro:property name="trunk_com_y" value="0.003839"/>
|
|
<xacro:property name="trunk_com_z" value="0.000273"/>
|
|
<xacro:property name="trunk_ixx" value="0.051944892"/>
|
|
<xacro:property name="trunk_ixy" value="0.001703617"/>
|
|
<xacro:property name="trunk_ixz" value="0.000235941"/>
|
|
<xacro:property name="trunk_iyy" value="0.24693924"/>
|
|
<xacro:property name="trunk_iyz" value="0.000119783"/>
|
|
<xacro:property name="trunk_izz" value="0.270948307"/>
|
|
|
|
<!-- hip (left front) -->
|
|
<xacro:property name="hip_mass" value="1.993"/>
|
|
<xacro:property name="hip_com_x" value="-0.022191"/>
|
|
<xacro:property name="hip_com_y" value="0.015144"/>
|
|
<xacro:property name="hip_com_z" value="-0.000015"/>
|
|
<xacro:property name="hip_ixx" value="0.002446735"/>
|
|
<xacro:property name="hip_ixy" value="-0.00059805"/>
|
|
<xacro:property name="hip_ixz" value="0.000001945"/>
|
|
<xacro:property name="hip_iyy" value="0.003925876"/>
|
|
<xacro:property name="hip_iyz" value="0.000001284"/>
|
|
<xacro:property name="hip_izz" value="0.004148145"/>
|
|
|
|
<xacro:property name="hip_rotor_mass" value="0.146"/>
|
|
<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.000138702"/>
|
|
<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.000083352"/>
|
|
<xacro:property name="hip_rotor_iyz" value="0.0"/>
|
|
<xacro:property name="hip_rotor_izz" value="0.000083352"/>
|
|
|
|
<!-- thigh -->
|
|
<xacro:property name="thigh_mass" value="0.639"/>
|
|
<xacro:property name="thigh_com_x" value="-0.005607"/>
|
|
<xacro:property name="thigh_com_y" value="-0.003877"/>
|
|
<xacro:property name="thigh_com_z" value="-0.048199"/>
|
|
<xacro:property name="thigh_ixx" value="0.004173855"/>
|
|
<xacro:property name="thigh_ixy" value="0.000010284"/>
|
|
<xacro:property name="thigh_ixz" value="-0.000318874"/>
|
|
<xacro:property name="thigh_iyy" value="0.004343802"/>
|
|
<xacro:property name="thigh_iyz" value="0.000109233"/>
|
|
<xacro:property name="thigh_izz" value="0.000340136"/>
|
|
|
|
<xacro:property name="thigh_rotor_mass" value="0.146"/>
|
|
<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.000083352"/>
|
|
<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.000138702"/>
|
|
<xacro:property name="thigh_rotor_iyz" value="0.0"/>
|
|
<xacro:property name="thigh_rotor_izz" value="0.000083352"/>
|
|
|
|
<!-- calf -->
|
|
<xacro:property name="calf_mass" value="0.207"/>
|
|
<xacro:property name="calf_com_x" value="0.002781"/>
|
|
<xacro:property name="calf_com_y" value="0.000063"/>
|
|
<xacro:property name="calf_com_z" value="-0.142518"/>
|
|
<xacro:property name="calf_ixx" value="0.002129279"/>
|
|
<xacro:property name="calf_ixy" value="0.000000039"/>
|
|
<xacro:property name="calf_ixz" value="0.000005757"/>
|
|
<xacro:property name="calf_iyy" value="0.002141463"/>
|
|
<xacro:property name="calf_iyz" value="-0.000000516"/>
|
|
<xacro:property name="calf_izz" value="0.000037583"/>
|
|
|
|
<xacro:property name="calf_rotor_mass" value="0.132"/>
|
|
<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.000145463"/>
|
|
<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.000133031"/>
|
|
<xacro:property name="calf_rotor_iyz" value="0.0"/>
|
|
<xacro:property name="calf_rotor_izz" value="0.000145463"/>
|
|
|
|
<!-- foot -->
|
|
<xacro:property name="foot_mass" value="0.06"/>
|
|
|
|
</robot>
|