Skip to content

Commit

Permalink
Add SITL viewer model
Browse files Browse the repository at this point in the history
Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
  • Loading branch information
Ryanf55 committed Apr 20, 2024
1 parent 89f9797 commit f093a33
Show file tree
Hide file tree
Showing 4 changed files with 225 additions and 0 deletions.
24 changes: 24 additions & 0 deletions ardupilot_gz_description/models/iris_sitl_viewer/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
<?xml version="1.0"?>

<model>
<name>Iris SITL Viewer</name>
<version>1.0</version>
<sdf version="1.9">model.sdf</sdf>

<author>
<name>Ryan Friedman</name>
<email>ryanfriedman5410+github@gmail.com</email>
</author>

<maintainer email="ryanfriedman5410+github@gmail.com">Ryan Friedman</maintainer>

<description>
View-only Iris copter for showing ArduPilot SITL FDM state in Gazebo.
</description>
<depend>
<model>
<uri>model://iris_sitl_viewer</uri>
<version>1.0</version>
</model>
</depend>
</model>
83 changes: 83 additions & 0 deletions ardupilot_gz_description/models/iris_sitl_viewer/model.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,83 @@
<?xml version='1.0'?>
<sdf version="1.9">

<model name="iris_sitl_viewer">
<include merge="true">
<uri>model://iris_with_standoffs</uri>
</include>

<link name="base_scan">
<pose>0 0 0.075077 0 0 0</pose>
<inertial>
<mass>0.1</mass>
<inertia>
<ixx>0.000166667</ixx>
<iyy>0.000166667</iyy>
<izz>0.000166667</izz>
</inertia>
</inertial>

<collision name="collision">
<geometry>
<box>
<size>0.05 0.05 0.05</size>
</box>
</geometry>
</collision>

<visual name="visual">
<geometry>
<box>
<size>0.05 0.05 0.05</size>
</box>
</geometry>
</visual>

<sensor name='gpu_lidar' type='gpu_lidar'>
<gz_frame_id>base_scan</gz_frame_id>
<pose>0 0 0 0 0 0</pose>
<topic>lidar</topic>
<update_rate>10</update_rate>
<lidar>
<scan>
<horizontal>
<samples>640</samples>
<resolution>1</resolution>
<min_angle>-3.14159265</min_angle>
<max_angle>3.14159265</max_angle>
</horizontal>
<vertical>
<samples>1</samples>
<resolution>1</resolution>
<min_angle>0.0</min_angle>
<max_angle>0.0</max_angle>
</vertical>
</scan>
<range>
<min>0.08</min>
<max>10.0</max>
<resolution>0.01</resolution>
</range>
</lidar>
<visualize>true</visualize>
</sensor>
</link>

<joint name="lidar_joint" type="revolute">
<parent>base_link</parent>
<child>base_scan</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>0</lower>
<upper>0</upper>
</limit>
<dynamics>
<damping>1</damping>
</dynamics>
</axis>
</joint>

</model>

</sdf>
1 change: 1 addition & 0 deletions ardupilot_gz_gazebo/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
<depend>gz-common5</depend>
<depend>gz-cmake3</depend>
<depend>gz-plugin2</depend>
<depend>ardupilot_gz_description</depend>

<!-- Garden (default) -->
<depend condition="$GZ_VERSION == garden">gz-sim7</depend>
Expand Down
117 changes: 117 additions & 0 deletions ardupilot_gz_gazebo/worlds/iris_viewer.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,117 @@
<?xml version="1.0" ?>
<sdf version="1.9">
<world name="map">
<physics name="1ms" type="ignore">
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>

<plugin filename="gz-sim-physics-system"
name="gz::sim::systems::Physics">
</plugin>
<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>
<plugin filename="gz-sim-scene-broadcaster-system"
name="gz::sim::systems::SceneBroadcaster">
</plugin>
<plugin filename="gz-sim-air-pressure-system"
name="gz::sim::systems::AirPressure">
</plugin>
<plugin filename="gz-sim-air-speed-system"
name="gz::sim::systems::AirSpeed">
</plugin>
<plugin filename="gz-sim-altimeter-system"
name="gz::sim::systems::Altimeter">
</plugin>
<plugin filename="gz-sim-imu-system"
name="gz::sim::systems::Imu">
</plugin>
<plugin filename="gz-sim-magnetometer-system"
name="gz::sim::systems::Magnetometer">
</plugin>
<plugin filename="gz-sim-navsat-system"
name="gz::sim::systems::NavSat">
</plugin>

<scene>
<ambient>1.0 1.0 1.0</ambient>
<background>0.8 0.8 0.8</background>
<sky></sky>
</scene>

<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
</light>

<spherical_coordinates>
<latitude_deg>-35.3632621</latitude_deg>
<longitude_deg>149.1652374</longitude_deg>
<elevation>584</elevation>
<heading_deg>0</heading_deg>
<surface_model>EARTH_WGS84</surface_model>
</spherical_coordinates>

<!-- <include>
<uri>model://runway</uri>
<pose degrees="true">-29 545 0 0 0 363</pose>
</include> -->

<!-- <include>
<uri>model://iris_sitl_viewer</uri>
<name>iris</name>
<pose degrees="true">0 0 0.195 0 0 90</pose>
</include> -->

<model name="NavSat">
<pose>0 0 0.05 0 0.0 0</pose>
<!-- <static>true</static> -->
<link name="link">
<inertial>
<mass>0.1</mass>
<inertia>
<ixx>0.000166667</ixx>
<iyy>0.000166667</iyy>
<izz>0.000166667</izz>
</inertia>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.1 0.5 0.1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.1 0.1 0.2</size>
</box>
</geometry>
</visual>

<sensor name="navsat" type="navsat">
<always_on>1</always_on>
<update_rate>1</update_rate>
<topic>navsat</topic>
</sensor>
</link>
</model>

</world>
</sdf>

0 comments on commit f093a33

Please sign in to comment.