mirror of
https://github.com/bjoernellens1/bot_mini_description.git
synced 2024-11-21 14:53:48 +00:00
commit
f3af38417f
@ -7,10 +7,10 @@
|
||||
<xacro:property name="PI" value="3.1415926535897931"/>
|
||||
<xacro:property name="base_mass" value="0.3" />
|
||||
<!-- arbitrary value for base mass -->
|
||||
<xacro:property name="base_width" value="0.25" />
|
||||
<xacro:property name="base_width" value="0.26" />
|
||||
<!-- Updated wheel spacing to 25cm -->
|
||||
<xacro:property name="base_length" value="0.34" />
|
||||
<xacro:property name="base_height" value="0.1" />
|
||||
<xacro:property name="base_height" value="0.123" />
|
||||
<xacro:property name="wheel_mass" value="0.3" />
|
||||
<!-- arbitrary value for wheel mass -->
|
||||
<xacro:property name="wheel_len" value="0.020" />
|
||||
@ -19,7 +19,8 @@
|
||||
<!-- arbitrary value for caster wheel mass -->
|
||||
<xacro:property name="caster_wheel_radius" value="0.04" />
|
||||
<xacro:property name="z_offset" value="-${base_height/2}" />
|
||||
<!-- Space btw top of beam and the each joint -->
|
||||
<!-- Offset of main Axis to center of base body (Axis of rotation for steering) -->
|
||||
<xacro:property name="base_offset" value="0.11" />
|
||||
|
||||
<!-- dummy link - used for ros2 control so it stops complaining?
|
||||
<link name="${prefix}dummy_link">
|
||||
@ -35,7 +36,7 @@
|
||||
<!-- Base Link -->
|
||||
<link name="${prefix}base_link">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 -0 0" />
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="file://$(find bot_mini_description)/mesh/base_link_visual.stl"/>
|
||||
</geometry>
|
||||
@ -50,7 +51,7 @@
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin xyz="-2.5368985414583082317e-17 0.083896718007622009261 -0.0037261823981863751235" rpy="0 0 0"/>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<mass value="8.4123950268139715547" />
|
||||
<inertia ixx="0.090166990291185383777" ixy="4.7429179749238352248e-18" ixz="1.4209310488728267579e-18" iyy="0.055481261106946747064" iyz="-0.01112159061226025876" izz="0.13051099377067149065" />
|
||||
</inertial>
|
||||
@ -63,15 +64,16 @@
|
||||
<joint name="${prefix}base_footprint_joint" type="fixed">
|
||||
<parent link="${prefix}base_link" />
|
||||
<child link="${prefix}base_footprint" />
|
||||
<origin xyz="0 0 ${z_offset}" rpy="0 0 0" />
|
||||
</joint>
|
||||
|
||||
<!-- right wheel joint -->
|
||||
<!-- fixed wheel joint for testing, type was continuous -->
|
||||
<joint name="${prefix}right_wheel_joint" type="continuous">
|
||||
<origin xyz="6.9388939039072283776e-17 -0.125 -0.05999999999999999778" rpy="-1.57079632679489678 -1.1660544913393859426e-16 6.9388939039072283776e-17" />
|
||||
<origin xyz="0 -0.125 ${z_offset}" rpy="${PI / 2} 0 0" />
|
||||
<parent link="${prefix}base_link" />
|
||||
<child link="${prefix}right_wheel" />
|
||||
<axis xyz="0 0 -1"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="1" velocity="20" />
|
||||
<joint_properties friction="0.0"/>
|
||||
</joint>
|
||||
@ -103,7 +105,7 @@
|
||||
<!-- fixed wheel joint for testing, type was continuous -->
|
||||
<!-- left wheel joint -->
|
||||
<joint name="${prefix}left_wheel_joint" type="continuous">
|
||||
<origin xyz="-5.5511151231257827021e-17 0.12500000000000005551 -0.060000000000000011657" rpy="1.570796326794896558 -1.6964751660994284333e-16 1.7347234759768063549e-16" />
|
||||
<origin xyz="0 0.125 ${z_offset}" rpy="${PI / 2} 0 0" />
|
||||
<parent link="${prefix}base_link" />
|
||||
<child link="${prefix}left_wheel" />
|
||||
<axis xyz="0 0 -1" />
|
||||
@ -137,7 +139,7 @@
|
||||
|
||||
<!-- caster wheel joint -->
|
||||
<joint name="${prefix}caster_wheel_joint" type="fixed">
|
||||
<origin xyz="-0.29000000000000003553 -1.236754434711827603e-16 -0.019999999999999969191" rpy="-5.5511151231257814695e-17 -0 3.141592653589793116" />
|
||||
<origin xyz="-${base_length / 2 + base_offset} 0 -0.02" rpy="0 0 ${PI}" />
|
||||
<parent link="${prefix}base_link" />
|
||||
<child link="${prefix}caster_wheel" />
|
||||
<axis xyz="0 0 1"/>
|
||||
@ -195,7 +197,7 @@
|
||||
|
||||
<!-- laser_joint -->
|
||||
<joint name="${prefix}laser_joint" type="fixed">
|
||||
<origin xyz="0.025000000000000001388 2.7755575615628913511e-17 0.025000000000000008327" rpy="-3.141592653589793116 -6.1629758220391519929e-33 1.1102230246251560474e-16" />
|
||||
<origin xyz="${base_length /2 -0.035 - base_offset} 0 0" rpy="0 0 0"/>
|
||||
<parent link="${prefix}base_link" />
|
||||
<child link="${prefix}laser_link" />
|
||||
<axis xyz="0 0 1"/>
|
||||
@ -230,7 +232,7 @@
|
||||
|
||||
<!-- Camera Joint -->
|
||||
<joint name="${prefix}camera_joint" type="fixed">
|
||||
<origin xyz="0.040000000000000007772 1.3877787807814456755e-17 -4.4408920985006270245e-18" rpy="6.1062266354383530837e-16 1.1102230246251567869e-16 3.141592653589793116" />
|
||||
<origin xyz="${base_length / 2 - base_offset} 0 0" rpy="0 0 ${PI}" />
|
||||
<parent link="${prefix}base_link" />
|
||||
<child link="${prefix}camera_link" />
|
||||
<axis xyz="0 0 1"/>
|
||||
|
Loading…
Reference in New Issue
Block a user