Skip to content

Commit

Permalink
remove plugins from sdf
Browse files Browse the repository at this point in the history
  • Loading branch information
mbjd committed Mar 7, 2025
1 parent 93587c1 commit 73cb2ec
Showing 1 changed file with 1 addition and 157 deletions.
158 changes: 1 addition & 157 deletions worlds/moving_platform.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -6,155 +6,6 @@
<real_time_factor>1.0</real_time_factor>
<real_time_update_rate>250</real_time_update_rate>
</physics>
<plugin name="gz::sim::systems::Physics" filename="gz-sim-physics-system"/>
<plugin name="gz::sim::systems::UserCommands" filename="gz-sim-user-commands-system"/>
<plugin name="gz::sim::systems::SceneBroadcaster" filename="gz-sim-scene-broadcaster-system"/>
<plugin name="gz::sim::systems::Contact" filename="gz-sim-contact-system"/>
<plugin name="gz::sim::systems::Imu" filename="gz-sim-imu-system"/>
<plugin name="gz::sim::systems::AirPressure" filename="gz-sim-air-pressure-system"/>
<plugin name="gz::sim::systems::AirSpeed" filename="gz-sim-air-speed-system"/>
<plugin name="gz::sim::systems::ApplyLinkWrench" filename="gz-sim-apply-link-wrench-system"/>
<plugin name="gz::sim::systems::NavSat" filename="gz-sim-navsat-system"/>
<plugin name="gz::sim::systems::Sensors" filename="gz-sim-sensors-system">
<render_engine>ogre2</render_engine>
</plugin>
<gui fullscreen="false">
<!-- 3D scene -->
<plugin filename="MinimalScene" name="3D View">
<gz-gui>
<title>3D View</title>
<property type="bool" key="showTitleBar">false</property>
<property type="string" key="state">docked</property>
</gz-gui>
<engine>ogre2</engine>
<scene>scene</scene>
<ambient_light>0.4 0.4 0.4</ambient_light>
<background_color>0.8 0.8 0.8</background_color>
<camera_pose>-6 0 6 0 0.5 0</camera_pose>
<camera_clip>
<near>0.25</near>
<far>25000</far>
</camera_clip>
</plugin>
<!-- Plugins that add functionality to the scene -->
<plugin filename="EntityContextMenuPlugin" name="Entity context menu">
<gz-gui>
<property key="state" type="string">floating</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="GzSceneManager" name="Scene Manager">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="InteractiveViewControl" name="Interactive view control">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="CameraTracking" name="Camera Tracking">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="MarkerManager" name="Marker manager">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="SelectEntities" name="Select Entities">
<gz-gui>
<anchors target="Select entities">
<line own="right" target="right"/>
<line own="top" target="top"/>
</anchors>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="VisualizationCapabilities" name="Visualization Capabilities">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="Spawn" name="Spawn Entities">
<gz-gui>
<anchors target="Select entities">
<line own="right" target="right"/>
<line own="top" target="top"/>
</anchors>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin name="World control" filename="WorldControl">
<gz-gui>
<title>World control</title>
<property type="bool" key="showTitleBar">0</property>
<property type="bool" key="resizable">0</property>
<property type="double" key="height">72</property>
<property type="double" key="width">121</property>
<property type="double" key="z">1</property>
<property type="string" key="state">floating</property>
<anchors target="3D View">
<line own="left" target="left"/>
<line own="bottom" target="bottom"/>
</anchors>
</gz-gui>
<play_pause>1</play_pause>
<step>1</step>
<start_paused>1</start_paused>
</plugin>
<plugin name="World stats" filename="WorldStats">
<gz-gui>
<title>World stats</title>
<property type="bool" key="showTitleBar">0</property>
<property type="bool" key="resizable">0</property>
<property type="double" key="height">110</property>
<property type="double" key="width">290</property>
<property type="double" key="z">1</property>
<property type="string" key="state">floating</property>
<anchors target="3D View">
<line own="right" target="right"/>
<line own="bottom" target="bottom"/>
</anchors>
</gz-gui>
<sim_time>1</sim_time>
<real_time>1</real_time>
<real_time_factor>1</real_time_factor>
<iterations>1</iterations>
</plugin>
<plugin name="Entity tree" filename="EntityTree"/>
</gui>
<gravity>0 0 -9.8</gravity>
<magnetic_field>6e-06 2.3e-05 -4.2e-05</magnetic_field>
<atmosphere type="adiabatic"/>
Expand Down Expand Up @@ -186,7 +37,7 @@
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
<size>500 500</size>
</plane>
</geometry>
<material>
Expand Down Expand Up @@ -248,13 +99,6 @@
<update_rate>30</update_rate>
</sensor>
</link>
<!-- plugin for sending direct velocity commands -->
<plugin
filename="gz-sim-velocity-control-system"
name="gz::sim::systems::VelocityControl">
<link_name>platform_link</link_name>
</plugin>
<plugin name="custom::MovingPlatformController" filename="libMovingPlatformController.so" />
</model>
<light name="sunUTC" type="directional">
<pose>0 0 500 0 -0 0</pose>
Expand Down

0 comments on commit 73cb2ec

Please sign in to comment.