107 lines
2.8 KiB
XML
107 lines
2.8 KiB
XML
<?xml version="1.0" ?>
|
|
<sdf version="1.6">
|
|
<world name="iris_runway">
|
|
<physics type="ode">
|
|
<ode>
|
|
<solver>
|
|
<type>quick</type>
|
|
<iters>100</iters>
|
|
<sor>1.0</sor>
|
|
</solver>
|
|
<constraints>
|
|
<cfm>0.0</cfm>
|
|
<erp>0.9</erp>
|
|
<contact_max_correcting_vel>0.1</contact_max_correcting_vel>
|
|
<contact_surface_layer>0.0</contact_surface_layer>
|
|
</constraints>
|
|
</ode>
|
|
<max_step_size>0.001</max_step_size>
|
|
<real_time_factor>1.0</real_time_factor>
|
|
<real_time_update_rate>1000</real_time_update_rate>
|
|
</physics>
|
|
|
|
<include>
|
|
<uri>model://sun</uri>
|
|
</include>
|
|
|
|
<include>
|
|
<uri>model://ground_plane</uri>
|
|
</include>
|
|
|
|
<!-- ArduPilot Iris Quadcopter -->
|
|
<model name="iris">
|
|
<include>
|
|
<uri>model://iris_with_ardupilot</uri>
|
|
</include>
|
|
</model>
|
|
|
|
<!-- Visual Navigation Markers -->
|
|
<model name="marker_red">
|
|
<static>true</static>
|
|
<pose>10 0 0.01 0 0 0</pose>
|
|
<link name="link">
|
|
<visual name="visual">
|
|
<geometry><box><size>1 1 0.02</size></box></geometry>
|
|
<material>
|
|
<ambient>1 0 0 1</ambient>
|
|
<diffuse>1 0 0 1</diffuse>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
</model>
|
|
|
|
<model name="marker_green">
|
|
<static>true</static>
|
|
<pose>10 10 0.01 0 0 0</pose>
|
|
<link name="link">
|
|
<visual name="visual">
|
|
<geometry><box><size>1 1 0.02</size></box></geometry>
|
|
<material>
|
|
<ambient>0 1 0 1</ambient>
|
|
<diffuse>0 1 0 1</diffuse>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
</model>
|
|
|
|
<model name="marker_blue">
|
|
<static>true</static>
|
|
<pose>0 10 0.01 0 0 0</pose>
|
|
<link name="link">
|
|
<visual name="visual">
|
|
<geometry><box><size>1 1 0.02</size></box></geometry>
|
|
<material>
|
|
<ambient>0 0 1 1</ambient>
|
|
<diffuse>0 0 1 1</diffuse>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
</model>
|
|
|
|
<model name="origin_marker">
|
|
<static>true</static>
|
|
<pose>0 0 0.01 0 0 0</pose>
|
|
<link name="link">
|
|
<visual name="visual">
|
|
<geometry>
|
|
<cylinder><radius>0.5</radius><length>0.02</length></cylinder>
|
|
</geometry>
|
|
<material>
|
|
<ambient>1 1 0 1</ambient>
|
|
<diffuse>1 1 0 1</diffuse>
|
|
</material>
|
|
</visual>
|
|
</link>
|
|
</model>
|
|
|
|
<!-- Spherical coordinates for GPS geofencing -->
|
|
<spherical_coordinates>
|
|
<surface_model>EARTH_WGS84</surface_model>
|
|
<latitude_deg>-35.363262</latitude_deg>
|
|
<longitude_deg>149.165237</longitude_deg>
|
|
<elevation>584</elevation>
|
|
<heading_deg>0</heading_deg>
|
|
</spherical_coordinates>
|
|
</world>
|
|
</sdf>
|