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
e1be35f4a4
commit
467fb49a8c
@ -12,9 +12,11 @@
|
|||||||
<xacro:property name="wheel_mass" value="0.3" /> <!-- arbitrary value for wheel mass -->
|
<xacro:property name="wheel_mass" value="0.3" /> <!-- arbitrary value for wheel mass -->
|
||||||
<xacro:property name="wheel_len" value="0.020" />
|
<xacro:property name="wheel_len" value="0.020" />
|
||||||
<xacro:property name="wheel_radius" value="0.0625" />
|
<xacro:property name="wheel_radius" value="0.0625" />
|
||||||
<xacro:property name="caster_wheel_mass" value="0.1" /> <!-- arbitrary value for caster wheel mass -->
|
<xacro:property name="caster_wheel_mass" value="0.1" /> <!-- 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}" /> <!-- Space btw top of beam and the each joint -->
|
<xacro:property name="z_offset" value="-${base_height/2}" /> <!-- Space btw top of beam and the
|
||||||
|
each joint -->
|
||||||
|
|
||||||
<!-- 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 name="${prefix}dummy">
|
||||||
@ -46,7 +48,8 @@
|
|||||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
<mass value="${base_mass}" />
|
<mass value="${base_mass}" />
|
||||||
<inertia
|
<inertia
|
||||||
ixx="${base_mass / 12.0 * (base_length*base_length + base_height*base_height)}" ixy="0.0" ixz="0.0"
|
ixx="${base_mass / 12.0 * (base_length*base_length + base_height*base_height)}" ixy="0.0"
|
||||||
|
ixz="0.0"
|
||||||
iyy="${base_mass / 12.0 * (base_height*base_height + base_width*base_width)}" iyz="0.0"
|
iyy="${base_mass / 12.0 * (base_height*base_height + base_width*base_width)}" iyz="0.0"
|
||||||
izz="${base_mass / 12.0 * (base_width*base_width + base_length*base_length)}" />
|
izz="${base_mass / 12.0 * (base_width*base_width + base_length*base_length)}" />
|
||||||
</inertial>
|
</inertial>
|
||||||
@ -60,7 +63,8 @@
|
|||||||
<dynamics damping="0.2" />
|
<dynamics damping="0.2" />
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<!-- BASE_FOOTPRINT LINK (Used for SLAM: Should be oin the ground beneath the robo like the shadow) -->
|
<!-- BASE_FOOTPRINT LINK (Used for SLAM: Should be oin the ground beneath the robo like the
|
||||||
|
shadow) -->
|
||||||
<joint name="${prefix}base_footprint_joint" type="fixed">
|
<joint name="${prefix}base_footprint_joint" type="fixed">
|
||||||
<parent link="${prefix}base_link" />
|
<parent link="${prefix}base_link" />
|
||||||
<child link="${prefix}base_footprint" />
|
<child link="${prefix}base_footprint" />
|
||||||
|
Loading…
Reference in New Issue
Block a user