UGV Camera and World Gen Boxes
This commit is contained in:
7
models/box_large/model.config
Normal file
7
models/box_large/model.config
Normal file
@@ -0,0 +1,7 @@
|
||||
<?xml version="1.0"?>
|
||||
<model>
|
||||
<name>Large Cardboard Box</name>
|
||||
<version>1.0</version>
|
||||
<sdf version="1.9">model.sdf</sdf>
|
||||
<description>Large cardboard box obstacle (~3ft cube)</description>
|
||||
</model>
|
||||
19
models/box_large/model.sdf
Normal file
19
models/box_large/model.sdf
Normal file
@@ -0,0 +1,19 @@
|
||||
<?xml version="1.0" ?>
|
||||
<sdf version="1.9">
|
||||
<model name="box_large">
|
||||
<static>true</static>
|
||||
<link name="link">
|
||||
<collision name="collision">
|
||||
<geometry><box><size>0.8 0.6 0.7</size></box></geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry><box><size>0.8 0.6 0.7</size></box></geometry>
|
||||
<material>
|
||||
<ambient>0.58 0.40 0.24 1</ambient>
|
||||
<diffuse>0.58 0.40 0.24 1</diffuse>
|
||||
<specular>0.1 0.1 0.1 1</specular>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
</sdf>
|
||||
7
models/box_medium/model.config
Normal file
7
models/box_medium/model.config
Normal file
@@ -0,0 +1,7 @@
|
||||
<?xml version="1.0"?>
|
||||
<model>
|
||||
<name>Medium Cardboard Box</name>
|
||||
<version>1.0</version>
|
||||
<sdf version="1.9">model.sdf</sdf>
|
||||
<description>Medium cardboard box obstacle (~2ft cube)</description>
|
||||
</model>
|
||||
19
models/box_medium/model.sdf
Normal file
19
models/box_medium/model.sdf
Normal file
@@ -0,0 +1,19 @@
|
||||
<?xml version="1.0" ?>
|
||||
<sdf version="1.9">
|
||||
<model name="box_medium">
|
||||
<static>true</static>
|
||||
<link name="link">
|
||||
<collision name="collision">
|
||||
<geometry><box><size>0.5 0.5 0.5</size></box></geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry><box><size>0.5 0.5 0.5</size></box></geometry>
|
||||
<material>
|
||||
<ambient>0.65 0.45 0.28 1</ambient>
|
||||
<diffuse>0.65 0.45 0.28 1</diffuse>
|
||||
<specular>0.1 0.1 0.1 1</specular>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
</sdf>
|
||||
7
models/box_small/model.config
Normal file
7
models/box_small/model.config
Normal file
@@ -0,0 +1,7 @@
|
||||
<?xml version="1.0"?>
|
||||
<model>
|
||||
<name>Small Cardboard Box</name>
|
||||
<version>1.0</version>
|
||||
<sdf version="1.9">model.sdf</sdf>
|
||||
<description>Small cardboard box obstacle (~1ft cube)</description>
|
||||
</model>
|
||||
19
models/box_small/model.sdf
Normal file
19
models/box_small/model.sdf
Normal file
@@ -0,0 +1,19 @@
|
||||
<?xml version="1.0" ?>
|
||||
<sdf version="1.9">
|
||||
<model name="box_small">
|
||||
<static>true</static>
|
||||
<link name="link">
|
||||
<collision name="collision">
|
||||
<geometry><box><size>0.3 0.3 0.3</size></box></geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry><box><size>0.3 0.3 0.3</size></box></geometry>
|
||||
<material>
|
||||
<ambient>0.72 0.53 0.34 1</ambient>
|
||||
<diffuse>0.72 0.53 0.34 1</diffuse>
|
||||
<specular>0.1 0.1 0.1 1</specular>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
</sdf>
|
||||
@@ -115,11 +115,53 @@
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<!-- Forward-facing camera for obstacle detection -->
|
||||
<link name="front_camera_link">
|
||||
<pose>0.42 0 0.22 0 0 0</pose>
|
||||
<inertial>
|
||||
<mass>0.05</mass>
|
||||
<inertia>
|
||||
<ixx>0.00001</ixx><ixy>0</ixy><ixz>0</ixz>
|
||||
<iyy>0.00001</iyy><iyz>0</iyz><izz>0.00001</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<visual name="camera_visual">
|
||||
<geometry><box><size>0.03 0.03 0.03</size></box></geometry>
|
||||
<material>
|
||||
<ambient>0.1 0.1 0.1 1</ambient>
|
||||
<diffuse>0.1 0.1 0.1 1</diffuse>
|
||||
</material>
|
||||
</visual>
|
||||
<sensor name="front_camera" type="camera">
|
||||
<always_on>1</always_on>
|
||||
<update_rate>10</update_rate>
|
||||
<visualize>1</visualize>
|
||||
<topic>/ugv/camera/forward</topic>
|
||||
<camera>
|
||||
<horizontal_fov>1.3962634</horizontal_fov>
|
||||
<image>
|
||||
<width>640</width>
|
||||
<height>480</height>
|
||||
<format>R8G8B8</format>
|
||||
</image>
|
||||
<clip>
|
||||
<near>0.1</near>
|
||||
<far>50</far>
|
||||
</clip>
|
||||
</camera>
|
||||
</sensor>
|
||||
</link>
|
||||
|
||||
<joint name="aruco_joint" type="fixed">
|
||||
<parent>base_link</parent>
|
||||
<child>aruco_tag</child>
|
||||
</joint>
|
||||
|
||||
<joint name="front_camera_joint" type="fixed">
|
||||
<parent>base_link</parent>
|
||||
<child>front_camera_link</child>
|
||||
</joint>
|
||||
|
||||
<joint name="front_left_wheel_joint" type="revolute">
|
||||
<parent>base_link</parent>
|
||||
<child>front_left_wheel</child>
|
||||
|
||||
7
models/traffic_cone/model.config
Normal file
7
models/traffic_cone/model.config
Normal file
@@ -0,0 +1,7 @@
|
||||
<?xml version="1.0"?>
|
||||
<model>
|
||||
<name>Traffic Cone</name>
|
||||
<version>1.0</version>
|
||||
<sdf version="1.9">model.sdf</sdf>
|
||||
<description>Standard traffic cone obstacle</description>
|
||||
</model>
|
||||
128
models/traffic_cone/model.sdf
Normal file
128
models/traffic_cone/model.sdf
Normal file
@@ -0,0 +1,128 @@
|
||||
<?xml version="1.0" ?>
|
||||
<sdf version="1.9">
|
||||
<model name="traffic_cone">
|
||||
<static>true</static>
|
||||
<link name="link">
|
||||
|
||||
<!-- Rubber base plate -->
|
||||
<collision name="base_collision">
|
||||
<pose>0 0 0.015 0 0 0</pose>
|
||||
<geometry><box><size>0.38 0.38 0.03</size></box></geometry>
|
||||
</collision>
|
||||
<visual name="base_visual">
|
||||
<pose>0 0 0.015 0 0 0</pose>
|
||||
<geometry><box><size>0.38 0.38 0.03</size></box></geometry>
|
||||
<material>
|
||||
<ambient>0.08 0.08 0.08 1</ambient>
|
||||
<diffuse>0.10 0.10 0.10 1</diffuse>
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
<!-- Cone body: tapered segments (bottom to top) -->
|
||||
<!-- Segment 1 (bottom) — widest -->
|
||||
<visual name="seg_1">
|
||||
<pose>0 0 0.065 0 0 0</pose>
|
||||
<geometry><cylinder><radius>0.135</radius><length>0.07</length></cylinder></geometry>
|
||||
<material>
|
||||
<ambient>1.0 0.35 0.0 1</ambient>
|
||||
<diffuse>1.0 0.40 0.05 1</diffuse>
|
||||
<emissive>0.25 0.08 0.0 0.2</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
<!-- Segment 2 -->
|
||||
<visual name="seg_2">
|
||||
<pose>0 0 0.125 0 0 0</pose>
|
||||
<geometry><cylinder><radius>0.120</radius><length>0.05</length></cylinder></geometry>
|
||||
<material>
|
||||
<ambient>1.0 0.35 0.0 1</ambient>
|
||||
<diffuse>1.0 0.40 0.05 1</diffuse>
|
||||
<emissive>0.25 0.08 0.0 0.2</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
<!-- Lower reflective stripe -->
|
||||
<visual name="stripe_lower">
|
||||
<pose>0 0 0.168 0 0 0</pose>
|
||||
<geometry><cylinder><radius>0.108</radius><length>0.036</length></cylinder></geometry>
|
||||
<material>
|
||||
<ambient>0.95 0.95 0.95 1</ambient>
|
||||
<diffuse>1.0 1.0 1.0 1</diffuse>
|
||||
<emissive>0.6 0.6 0.6 0.5</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
<!-- Segment 3 (between stripes) -->
|
||||
<visual name="seg_3">
|
||||
<pose>0 0 0.210 0 0 0</pose>
|
||||
<geometry><cylinder><radius>0.095</radius><length>0.05</length></cylinder></geometry>
|
||||
<material>
|
||||
<ambient>1.0 0.35 0.0 1</ambient>
|
||||
<diffuse>1.0 0.40 0.05 1</diffuse>
|
||||
<emissive>0.25 0.08 0.0 0.2</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
<!-- Upper reflective stripe -->
|
||||
<visual name="stripe_upper">
|
||||
<pose>0 0 0.253 0 0 0</pose>
|
||||
<geometry><cylinder><radius>0.080</radius><length>0.036</length></cylinder></geometry>
|
||||
<material>
|
||||
<ambient>0.95 0.95 0.95 1</ambient>
|
||||
<diffuse>1.0 1.0 1.0 1</diffuse>
|
||||
<emissive>0.6 0.6 0.6 0.5</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
<!-- Segment 4 -->
|
||||
<visual name="seg_4">
|
||||
<pose>0 0 0.295 0 0 0</pose>
|
||||
<geometry><cylinder><radius>0.065</radius><length>0.05</length></cylinder></geometry>
|
||||
<material>
|
||||
<ambient>1.0 0.35 0.0 1</ambient>
|
||||
<diffuse>1.0 0.40 0.05 1</diffuse>
|
||||
<emissive>0.25 0.08 0.0 0.2</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
<!-- Segment 5 -->
|
||||
<visual name="seg_5">
|
||||
<pose>0 0 0.340 0 0 0</pose>
|
||||
<geometry><cylinder><radius>0.048</radius><length>0.04</length></cylinder></geometry>
|
||||
<material>
|
||||
<ambient>1.0 0.35 0.0 1</ambient>
|
||||
<diffuse>1.0 0.40 0.05 1</diffuse>
|
||||
<emissive>0.25 0.08 0.0 0.2</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
<!-- Segment 6 (top) — narrowest -->
|
||||
<visual name="seg_6">
|
||||
<pose>0 0 0.375 0 0 0</pose>
|
||||
<geometry><cylinder><radius>0.032</radius><length>0.03</length></cylinder></geometry>
|
||||
<material>
|
||||
<ambient>1.0 0.35 0.0 1</ambient>
|
||||
<diffuse>1.0 0.40 0.05 1</diffuse>
|
||||
<emissive>0.25 0.08 0.0 0.2</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
<!-- Tip cap -->
|
||||
<visual name="tip">
|
||||
<pose>0 0 0.395 0 0 0</pose>
|
||||
<geometry><cylinder><radius>0.020</radius><length>0.01</length></cylinder></geometry>
|
||||
<material>
|
||||
<ambient>1.0 0.40 0.05 1</ambient>
|
||||
<diffuse>1.0 0.45 0.10 1</diffuse>
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
<!-- Collision: simplified bounding shape for the whole cone -->
|
||||
<collision name="cone_collision">
|
||||
<pose>0 0 0.22 0 0 0</pose>
|
||||
<geometry><cylinder><radius>0.13</radius><length>0.40</length></cylinder></geometry>
|
||||
</collision>
|
||||
|
||||
</link>
|
||||
</model>
|
||||
</sdf>
|
||||
Reference in New Issue
Block a user