Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
sdf_parsing/build/
4 changes: 4 additions & 0 deletions models/moving_platform/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
<?xml version="1.0" encoding="UTF-8"?>
<model>
<sdf version="1.9">model.sdf</sdf>
</model>
48 changes: 48 additions & 0 deletions models/moving_platform/model.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
<?xml version="1.0" encoding="UTF-8"?>
<sdf version="1.9">
<model name="flat_platform">
<link name="platform_link">
<visual name="platform_visual">
<geometry>
<box>
<size>5 5 0.1</size>
</box>
</geometry>
<material>
<ambient>0.3 0.3 0.3 1</ambient>
<diffuse>0.3 0.3 0.3 1</diffuse>
<specular>0.1 0.1 0.1 1</specular>
</material>
</visual>
<collision name="platform_collision">
<geometry>
<box>
<size>5 5 0.1</size>
</box>
</geometry>
</collision>
<pose>0 0 2 0 0 0</pose>
<inertial>
<mass>10000</mass>
<inertia>
<ixx>10000</ixx>
<iyy>10000</iyy>
<izz>10000</izz>
</inertia>
</inertial>
<sensor name="navsat_sensor" type="navsat">
<always_on>1</always_on>
<update_rate>30</update_rate>
</sensor>
Comment on lines +33 to +36
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

the navsat sensor is not needed. See my comments in PX4/PX4-Autopilot#24471

</link>
<!-- plugin for sending direct velocity commands -->
<plugin
filename="gz-sim-velocity-control-system"
name="gz::sim::systems::VelocityControl">
</plugin>
<plugin
filename="libMovingPlatformController.so"
name="custom::MovingPlatformController">
</plugin>
</model>
</sdf>
97 changes: 97 additions & 0 deletions worlds/moving_platform.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,97 @@
<?xml version="1.0" encoding="UTF-8"?>
<sdf version="1.9">
<world name="moving_platform">
<physics type="ode">
<max_step_size>0.004</max_step_size>
<real_time_factor>1.0</real_time_factor>
<real_time_update_rate>250</real_time_update_rate>
</physics>
<gravity>0 0 -9.8</gravity>
<magnetic_field>6e-06 2.3e-05 -4.2e-05</magnetic_field>
<atmosphere type="adiabatic"/>
<scene>
<grid>false</grid>
<ambient>0.4 0.4 0.4 1</ambient>
<background>0.7 0.7 0.7 1</background>
<shadows>true</shadows>
</scene>
<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>1 1</size>
</plane>
</geometry>
<surface>
<friction>
<ode/>
</friction>
<bounce/>
<contact/>
</surface>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>500 500</size>
</plane>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
<pose>0 0 0 0 -0 0</pose>
<inertial>
<pose>0 0 0 0 -0 0</pose>
<mass>1</mass>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
</inertial>
<enable_wind>false</enable_wind>
</link>
<pose>0 0 0 0 -0 0</pose>
<self_collide>false</self_collide>
</model>
<include>
<uri>model://moving_platform</uri>
</include>
<light name="sunUTC" type="directional">
<pose>0 0 500 0 -0 0</pose>
<cast_shadows>true</cast_shadows>
<intensity>1</intensity>
<direction>0.001 0.625 -0.78</direction>
<diffuse>0.904 0.904 0.904 1</diffuse>
<specular>0.271 0.271 0.271 1</specular>
<attenuation>
<range>2000</range>
<linear>0</linear>
<constant>1</constant>
<quadratic>0</quadratic>
</attenuation>
<spot>
<inner_angle>0</inner_angle>
<outer_angle>0</outer_angle>
<falloff>0</falloff>
</spot>
</light>
<spherical_coordinates>
<surface_model>EARTH_WGS84</surface_model>
<world_frame_orientation>ENU</world_frame_orientation>
<latitude_deg>47.397971057728974</latitude_deg>
<longitude_deg> 8.546163739800146</longitude_deg>
<elevation>0</elevation>
</spherical_coordinates>
</world>
</sdf>