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
f3af38417f
commit
e067f8b3e5
@ -14,5 +14,6 @@
|
|||||||
|
|
||||||
<export>
|
<export>
|
||||||
<build_type>ament_python</build_type>
|
<build_type>ament_python</build_type>
|
||||||
|
<gazebo_ros gazebo_model_path="${prefix}/.."/>
|
||||||
</export>
|
</export>
|
||||||
</package>
|
</package>
|
||||||
|
@ -31,14 +31,14 @@
|
|||||||
<child link="${prefix}base_link" />
|
<child link="${prefix}base_link" />
|
||||||
</joint> -->
|
</joint> -->
|
||||||
|
|
||||||
<!-- needed for replacement to find mesh dir: file://$(find bot_mini_description)/mesh/ -->
|
<!-- needed for replacement to find mesh dir: package://bot_mini_description/mesh/ -->
|
||||||
|
|
||||||
<!-- Base Link -->
|
<!-- Base Link -->
|
||||||
<link name="${prefix}base_link">
|
<link name="${prefix}base_link">
|
||||||
<visual>
|
<visual>
|
||||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="file://$(find bot_mini_description)/mesh/base_link_visual.stl"/>
|
<mesh filename="package://bot_mini_description/mesh/base_link_visual.stl"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="base_link_material">
|
<material name="base_link_material">
|
||||||
<color rgba="0.80032179626883115375 0.81301836741632160788 0.83346199892499306383 1.0"/>
|
<color rgba="0.80032179626883115375 0.81301836741632160788 0.83346199892499306383 1.0"/>
|
||||||
@ -47,7 +47,7 @@
|
|||||||
<collision>
|
<collision>
|
||||||
<origin xyz="0 0 0" rpy="0 -0 0" />
|
<origin xyz="0 0 0" rpy="0 -0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="file://$(find bot_mini_description)/mesh/base_link_collision.stl"/>
|
<mesh filename="package://bot_mini_description/mesh/base_link_collision.stl"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
<inertial>
|
<inertial>
|
||||||
@ -83,7 +83,7 @@
|
|||||||
<visual>
|
<visual>
|
||||||
<origin xyz="0 0 0" rpy="0 -0 0" />
|
<origin xyz="0 0 0" rpy="0 -0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="file://$(find bot_mini_description)/mesh/wheel_link_visual.stl"/>
|
<mesh filename="package://bot_mini_description/mesh/wheel_link_visual.stl"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="wheel_link_material">
|
<material name="wheel_link_material">
|
||||||
<color rgba="0.50196078431372548323 0.50196078431372548323 0.50196078431372548323 1.0"/>
|
<color rgba="0.50196078431372548323 0.50196078431372548323 0.50196078431372548323 1.0"/>
|
||||||
@ -92,7 +92,7 @@
|
|||||||
<collision>
|
<collision>
|
||||||
<origin xyz="0 0 0" rpy="0 -0 0" />
|
<origin xyz="0 0 0" rpy="0 -0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="file://$(find bot_mini_description)/mesh/wheel_link_collision.stl"/>
|
<mesh filename="package://bot_mini_description/mesh/wheel_link_collision.stl"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
<inertial>
|
<inertial>
|
||||||
@ -118,7 +118,7 @@
|
|||||||
<visual>
|
<visual>
|
||||||
<origin xyz="0 0 0" rpy="0 -0 0" />
|
<origin xyz="0 0 0" rpy="0 -0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="file://$(find bot_mini_description)/mesh/wheel_link_2_visual.stl"/>
|
<mesh filename="package://bot_mini_description/mesh/wheel_link_2_visual.stl"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="wheel_link_2_material">
|
<material name="wheel_link_2_material">
|
||||||
<color rgba="0.50196078431372548323 0.50196078431372548323 0.50196078431372548323 1.0"/>
|
<color rgba="0.50196078431372548323 0.50196078431372548323 0.50196078431372548323 1.0"/>
|
||||||
@ -127,7 +127,7 @@
|
|||||||
<collision>
|
<collision>
|
||||||
<origin xyz="0 0 0" rpy="0 -0 0" />
|
<origin xyz="0 0 0" rpy="0 -0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="file://$(find bot_mini_description)/mesh/wheel_link_2_collision.stl"/>
|
<mesh filename="package://bot_mini_description/mesh/wheel_link_2_collision.stl"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
<inertial>
|
<inertial>
|
||||||
@ -152,7 +152,7 @@
|
|||||||
<visual>
|
<visual>
|
||||||
<origin xyz="0 0 0" rpy="0 -0 0" />
|
<origin xyz="0 0 0" rpy="0 -0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="file://$(find bot_mini_description)/mesh/caster_link_visual.stl"/>
|
<mesh filename="package://bot_mini_description/mesh/caster_link_visual.stl"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="caster_link_material">
|
<material name="caster_link_material">
|
||||||
<color rgba="0.69513764518117548974 0.69513764518117548974 0.69513764518117548974 1.0"/>
|
<color rgba="0.69513764518117548974 0.69513764518117548974 0.69513764518117548974 1.0"/>
|
||||||
@ -161,7 +161,7 @@
|
|||||||
<collision>
|
<collision>
|
||||||
<origin xyz="0 0 0" rpy="0 -0 0" />
|
<origin xyz="0 0 0" rpy="0 -0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="file://$(find bot_mini_description)/mesh/caster_link_collision.stl"/>
|
<mesh filename="package://bot_mini_description/mesh/caster_link_collision.stl"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
<inertial>
|
<inertial>
|
||||||
@ -176,7 +176,7 @@
|
|||||||
<visual>
|
<visual>
|
||||||
<origin xyz="0 0 0" rpy="0 -0 0" />
|
<origin xyz="0 0 0" rpy="0 -0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="file://$(find bot_mini_description)/mesh/laser_link_visual.stl"/>
|
<mesh filename="package://bot_mini_description/mesh/laser_link_visual.stl"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="laser_link_material">
|
<material name="laser_link_material">
|
||||||
<color rgba="0.49803921568627451677 0.49803921568627451677 0.49803921568627451677 1.0"/>
|
<color rgba="0.49803921568627451677 0.49803921568627451677 0.49803921568627451677 1.0"/>
|
||||||
@ -185,7 +185,7 @@
|
|||||||
<collision>
|
<collision>
|
||||||
<origin xyz="0 0 0" rpy="0 -0 0" />
|
<origin xyz="0 0 0" rpy="0 -0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="file://$(find bot_mini_description)/mesh/laser_link_collision.stl"/>
|
<mesh filename="package://bot_mini_description/mesh/laser_link_collision.stl"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
<inertial>
|
<inertial>
|
||||||
@ -210,7 +210,7 @@
|
|||||||
<visual>
|
<visual>
|
||||||
<origin xyz="0 0 0" rpy="0 -0 0" />
|
<origin xyz="0 0 0" rpy="0 -0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="file://$(find bot_mini_description)/mesh/camera_link_visual.stl"/>
|
<mesh filename="package://bot_mini_description/mesh/camera_link_visual.stl"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="camera_link_material">
|
<material name="camera_link_material">
|
||||||
<color rgba="0.26274509803921569651 0.28235294117647058432 0.30196078431372547213 1.0"/>
|
<color rgba="0.26274509803921569651 0.28235294117647058432 0.30196078431372547213 1.0"/>
|
||||||
@ -219,7 +219,7 @@
|
|||||||
<collision>
|
<collision>
|
||||||
<origin xyz="0 0 0" rpy="0 -0 0" />
|
<origin xyz="0 0 0" rpy="0 -0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="file://$(find bot_mini_description)/mesh/camera_link_collision.stl"/>
|
<mesh filename="package://bot_mini_description/mesh/camera_link_collision.stl"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
<inertial>
|
<inertial>
|
||||||
|
Loading…
Reference in New Issue
Block a user