XML world parser

This commit is contained in:
2026-02-21 17:18:30 -05:00
parent 5a60d22458
commit 8ec4bc7846
5 changed files with 387 additions and 74 deletions

View File

@@ -1,52 +1,38 @@
<?xml version="1.0" ?>
<!--
Custom UAV-UGV Search & Land World
===================================
- ArduPilot iris quadcopter (with SITL plugin + gimbal camera)
- UGV target vehicle at (10, 5) for the drone to search for and land on
- Visual navigation markers (colored squares on the ground)
- Optimized for WSL: lower physics rate, no shadows
-->
<?xml version='1.0' encoding='utf-8'?>
<sdf version="1.9">
<world name="uav_ugv_search">
<!-- Physics: 4ms step (250 Hz) for better WSL performance -->
<physics name="2ms" type="ignore">
<max_step_size>0.002</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>
<!-- Required Gazebo Harmonic system plugins -->
<plugin filename="gz-sim-physics-system"
name="gz::sim::systems::Physics">
<plugin filename="gz-sim-physics-system" name="gz::sim::systems::Physics">
</plugin>
<plugin filename="gz-sim-sensors-system"
name="gz::sim::systems::Sensors">
<plugin filename="gz-sim-sensors-system" name="gz::sim::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>
<plugin filename="gz-sim-user-commands-system"
name="gz::sim::systems::UserCommands">
<plugin filename="gz-sim-user-commands-system" name="gz::sim::systems::UserCommands">
</plugin>
<plugin filename="gz-sim-scene-broadcaster-system"
name="gz::sim::systems::SceneBroadcaster">
<plugin filename="gz-sim-scene-broadcaster-system" name="gz::sim::systems::SceneBroadcaster">
<state_hertz>25</state_hertz>
</plugin>
<plugin filename="gz-sim-imu-system"
name="gz::sim::systems::Imu">
<plugin filename="gz-sim-imu-system" name="gz::sim::systems::Imu">
</plugin>
<plugin filename="gz-sim-navsat-system"
name="gz::sim::systems::NavSat">
<plugin filename="gz-sim-navsat-system" name="gz::sim::systems::NavSat">
</plugin>
<!-- Scene: no shadows for WSL performance -->
<scene>
<ambient>1.0 1.0 1.0</ambient>
<background>0.6 0.75 0.9</background>
<sky></sky>
<sky />
<shadows>false</shadows>
</scene>
<!-- Spherical coordinates (matches ArduPilot SITL default location) -->
<spherical_coordinates>
<latitude_deg>-35.363262</latitude_deg>
<longitude_deg>149.165237</longitude_deg>
@@ -55,7 +41,7 @@
<surface_model>EARTH_WGS84</surface_model>
</spherical_coordinates>
<!-- Sun (no shadows for performance) -->
<light type="directional" name="sun">
<cast_shadows>false</cast_shadows>
<pose>0 0 10 0 0 0</pose>
@@ -70,7 +56,7 @@
<direction>-0.5 0.1 -0.9</direction>
</light>
<!-- ===================== GROUND PLANE ===================== -->
<model name="ground_plane">
<static>true</static>
<link name="link">
@@ -83,6 +69,7 @@
</geometry>
</collision>
<visual name="visual">
<pose>0 0 -0.02 0 0 0</pose>
<geometry>
<plane>
<normal>0 0 1</normal>
@@ -97,11 +84,9 @@
</link>
</model>
<!-- ===================== COORDINATE AXES ===================== -->
<model name="axes">
<static>1</static>
<link name="link">
<!-- X axis (red) = North -->
<visual name="r">
<cast_shadows>0</cast_shadows>
<pose>5 0 0.05 0 0 0</pose>
@@ -112,7 +97,6 @@
<emissive>1 0 0 0.5</emissive>
</material>
</visual>
<!-- Y axis (green) = East -->
<visual name="g">
<cast_shadows>0</cast_shadows>
<pose>0 5 0.05 0 0 0</pose>
@@ -123,7 +107,6 @@
<emissive>0 1 0 0.5</emissive>
</material>
</visual>
<!-- Z axis (blue) = Up -->
<visual name="b">
<cast_shadows>0</cast_shadows>
<pose>0 0 5.05 0 0 0</pose>
@@ -134,7 +117,6 @@
<emissive>0 0 1 0.5</emissive>
</material>
</visual>
<!-- NavSat sensor (needed for GPS/geofence) -->
<sensor name="navsat_sensor" type="navsat">
<always_on>1</always_on>
<update_rate>1</update_rate>
@@ -142,26 +124,23 @@
</link>
</model>
<!-- ===================== UAV: ArduPilot Iris ===================== -->
<!-- Starts on top of the UGV. Body top z=0.18 + iris legs 0.195 = 0.375 -->
<include>
<uri>model://iris_with_gimbal</uri>
<pose degrees="true">0.0 0.0 0.4 0 0 90</pose>
</include>
<!-- ===================== UGV: Driveable Rover ===================== -->
<!-- Dynamic 4-wheel skid-steer, drone takes off from it, then it drives -->
<include>
<uri>model://custom_ugv</uri>
<name>ugv</name>
<pose>0.0 0.0 0 0 0 0</pose>
</include>
<!-- ===================== TARGET ArUco Tag (ID 1) ===================== -->
<!-- On the ground — the UAV searches for this, then UGV drives here -->
<model name="target_tag_1">
<static>true</static>
<pose>8 -6 0.005 0 0 0</pose>
<pose>-5.0 -5.0 0.005 0 0 0</pose>
<link name="link">
<visual name="v">
<geometry><box><size>0.5 0.5 0.01</size></box></geometry>
@@ -174,10 +153,8 @@
</link>
</model>
<!-- ===================== VISUAL MARKERS ===================== -->
<!-- Ground markers for visual navigation reference -->
<!-- Origin marker (yellow circle) -->
<model name="origin_marker">
<static>true</static>
<pose>0 0 0.005 0 0 0</pose>
@@ -193,7 +170,7 @@
</link>
</model>
<!-- Waypoint marker 1 (red) at 5,0 -->
<model name="marker_red">
<static>true</static>
<pose>5 0 0.005 0 0 0</pose>
@@ -209,7 +186,7 @@
</link>
</model>
<!-- Waypoint marker 2 (green) at 10,0 -->
<model name="marker_green">
<static>true</static>
<pose>10 0 0.005 0 0 0</pose>
@@ -225,7 +202,7 @@
</link>
</model>
<!-- Waypoint marker 3 (blue) at 10,10 -->
<model name="marker_blue">
<static>true</static>
<pose>10 10 0.005 0 0 0</pose>
@@ -241,5 +218,5 @@
</link>
</model>
</world>
</sdf>
<model name="geofence_visual"><static>true</static><link name="link"><visual name="edge_0"><pose>-15.0 0.0 0.01 0 0 1.5707963267948966</pose><geometry><box><size>30.0 0.2 0.02</size></box></geometry><material><ambient>1 0 0 1</ambient><diffuse>1 0 0 1</diffuse><emissive>0.8 0 0 0.5</emissive></material></visual><visual name="edge_1"><pose>0.0 15.0 0.01 0 0 0.0</pose><geometry><box><size>30.0 0.2 0.02</size></box></geometry><material><ambient>1 0 0 1</ambient><diffuse>1 0 0 1</diffuse><emissive>0.8 0 0 0.5</emissive></material></visual><visual name="edge_2"><pose>15.0 0.0 0.01 0 0 -1.5707963267948966</pose><geometry><box><size>30.0 0.2 0.02</size></box></geometry><material><ambient>1 0 0 1</ambient><diffuse>1 0 0 1</diffuse><emissive>0.8 0 0 0.5</emissive></material></visual><visual name="edge_3"><pose>0.0 -15.0 0.01 0 0 3.141592653589793</pose><geometry><box><size>30.0 0.2 0.02</size></box></geometry><material><ambient>1 0 0 1</ambient><diffuse>1 0 0 1</diffuse><emissive>0.8 0 0 0.5</emissive></material></visual></link></model></world>
</sdf>