mirror of
https://github.com/bjoernellens1/bot_mini_description.git
synced 2024-11-21 14:53:48 +00:00
update
This commit is contained in:
parent
ed2c5df2b0
commit
0cc7afdd6a
@ -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" />
|
||||
@ -35,7 +35,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>
|
||||
@ -63,12 +63,13 @@
|
||||
<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="$(base_length/2) -0.125 ${z_offset}" rpy="0 0 0" />
|
||||
<parent link="${prefix}base_link" />
|
||||
<child link="${prefix}right_wheel" />
|
||||
<axis xyz="0 0 -1"/>
|
||||
@ -103,7 +104,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="${(base_length/2)} 0.125 ${z_offset}" rpy="0 0 0" />
|
||||
<parent link="${prefix}base_link" />
|
||||
<child link="${prefix}left_wheel" />
|
||||
<axis xyz="0 0 -1" />
|
||||
@ -137,7 +138,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)} 0 -0.02" rpy="0 0 ${PI}" />
|
||||
<parent link="${prefix}base_link" />
|
||||
<child link="${prefix}caster_wheel" />
|
||||
<axis xyz="0 0 1"/>
|
||||
@ -195,7 +196,7 @@
|
||||
|
||||
<!-- laser_joint -->
|
||||
<joint name="${prefix}laser_joint" type="fixed">
|
||||
<origin xyz="0 ${base_length/2} ${z_offset}" rpy="0 0 0"/>
|
||||
<origin xyz="${(base_length/2)-0.035} 0 0" rpy="0 0 0"/>
|
||||
<parent link="${prefix}base_link" />
|
||||
<child link="${prefix}laser_link" />
|
||||
<axis xyz="0 0 1"/>
|
||||
@ -230,7 +231,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} 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