mirror of
https://github.com/bjoernellens1/bot_mini_description.git
synced 2024-11-22 07:13:48 +00:00
update
This commit is contained in:
parent
0cc7afdd6a
commit
9ba911389f
@ -19,7 +19,8 @@
|
|||||||
<!-- arbitrary value for caster wheel mass -->
|
<!-- arbitrary value for caster wheel mass -->
|
||||||
<xacro:property name="caster_wheel_radius" value="0.04" />
|
<xacro:property name="caster_wheel_radius" value="0.04" />
|
||||||
<xacro:property name="z_offset" value="-${base_height/2}" />
|
<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?
|
<!-- dummy link - used for ros2 control so it stops complaining?
|
||||||
<link name="${prefix}dummy_link">
|
<link name="${prefix}dummy_link">
|
||||||
@ -50,7 +51,7 @@
|
|||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
<inertial>
|
<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" />
|
<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" />
|
<inertia ixx="0.090166990291185383777" ixy="4.7429179749238352248e-18" ixz="1.4209310488728267579e-18" iyy="0.055481261106946747064" iyz="-0.01112159061226025876" izz="0.13051099377067149065" />
|
||||||
</inertial>
|
</inertial>
|
||||||
@ -69,7 +70,7 @@
|
|||||||
<!-- right wheel joint -->
|
<!-- right wheel joint -->
|
||||||
<!-- fixed wheel joint for testing, type was continuous -->
|
<!-- fixed wheel joint for testing, type was continuous -->
|
||||||
<joint name="${prefix}right_wheel_joint" type="continuous">
|
<joint name="${prefix}right_wheel_joint" type="continuous">
|
||||||
<origin xyz="$(base_length/2) -0.125 ${z_offset}" rpy="0 0 0" />
|
<origin xyz="0 -0.125 ${z_offset}" rpy="0 0 0" />
|
||||||
<parent link="${prefix}base_link" />
|
<parent link="${prefix}base_link" />
|
||||||
<child link="${prefix}right_wheel" />
|
<child link="${prefix}right_wheel" />
|
||||||
<axis xyz="0 0 -1"/>
|
<axis xyz="0 0 -1"/>
|
||||||
@ -104,7 +105,7 @@
|
|||||||
<!-- fixed wheel joint for testing, type was continuous -->
|
<!-- fixed wheel joint for testing, type was continuous -->
|
||||||
<!-- left wheel joint -->
|
<!-- left wheel joint -->
|
||||||
<joint name="${prefix}left_wheel_joint" type="continuous">
|
<joint name="${prefix}left_wheel_joint" type="continuous">
|
||||||
<origin xyz="${(base_length/2)} 0.125 ${z_offset}" rpy="0 0 0" />
|
<origin xyz="0 0.125 ${z_offset}" rpy="0 0 0" />
|
||||||
<parent link="${prefix}base_link" />
|
<parent link="${prefix}base_link" />
|
||||||
<child link="${prefix}left_wheel" />
|
<child link="${prefix}left_wheel" />
|
||||||
<axis xyz="0 0 -1" />
|
<axis xyz="0 0 -1" />
|
||||||
@ -138,7 +139,7 @@
|
|||||||
|
|
||||||
<!-- caster wheel joint -->
|
<!-- caster wheel joint -->
|
||||||
<joint name="${prefix}caster_wheel_joint" type="fixed">
|
<joint name="${prefix}caster_wheel_joint" type="fixed">
|
||||||
<origin xyz="-${(base_length/2)} 0 -0.02" rpy="0 0 ${PI}" />
|
<origin xyz="-${base_length / 2 + base_offset} 0 -0.02" rpy="0 0 ${PI}" />
|
||||||
<parent link="${prefix}base_link" />
|
<parent link="${prefix}base_link" />
|
||||||
<child link="${prefix}caster_wheel" />
|
<child link="${prefix}caster_wheel" />
|
||||||
<axis xyz="0 0 1"/>
|
<axis xyz="0 0 1"/>
|
||||||
@ -196,7 +197,7 @@
|
|||||||
|
|
||||||
<!-- laser_joint -->
|
<!-- laser_joint -->
|
||||||
<joint name="${prefix}laser_joint" type="fixed">
|
<joint name="${prefix}laser_joint" type="fixed">
|
||||||
<origin xyz="${(base_length/2)-0.035} 0 0" rpy="0 0 0"/>
|
<origin xyz="${base_length /2 -0.035 - base_offset} 0 0" rpy="0 0 0"/>
|
||||||
<parent link="${prefix}base_link" />
|
<parent link="${prefix}base_link" />
|
||||||
<child link="${prefix}laser_link" />
|
<child link="${prefix}laser_link" />
|
||||||
<axis xyz="0 0 1"/>
|
<axis xyz="0 0 1"/>
|
||||||
@ -231,7 +232,7 @@
|
|||||||
|
|
||||||
<!-- Camera Joint -->
|
<!-- Camera Joint -->
|
||||||
<joint name="${prefix}camera_joint" type="fixed">
|
<joint name="${prefix}camera_joint" type="fixed">
|
||||||
<origin xyz="${base_length/2} 0 0" rpy="0 0 ${PI}" />
|
<origin xyz="${base_length / 2 - base_offset} 0 0" rpy="0 0 ${PI}" />
|
||||||
<parent link="${prefix}base_link" />
|
<parent link="${prefix}base_link" />
|
||||||
<child link="${prefix}camera_link" />
|
<child link="${prefix}camera_link" />
|
||||||
<axis xyz="0 0 1"/>
|
<axis xyz="0 0 1"/>
|
||||||
|
Loading…
Reference in New Issue
Block a user