Skip to content

Commit

Permalink
Maritime tutorials 💧 - Part 3 of 4 (#2259)
Browse files Browse the repository at this point in the history
* Lander and lrauv tutorials.

Signed-off-by: Carlos Agüero <[email protected]>
Co-authored-by: Alejandro Hernández Cordero <[email protected]>
Co-authored-by: crvogt <[email protected]>
Co-authored-by: Ian Chen <[email protected]>
  • Loading branch information
4 people authored Dec 22, 2023
1 parent ae0070f commit beada29
Show file tree
Hide file tree
Showing 25 changed files with 90,810 additions and 122 deletions.
4 changes: 4 additions & 0 deletions src/systems/lift_drag/LiftDrag.cc
Original file line number Diff line number Diff line change
Expand Up @@ -280,7 +280,9 @@ void LiftDragPrivate::Update(EntityComponentManager &_ecm)
}

if (!worldLinVel || !worldAngVel || !worldPose)
{
return;
}

const auto &pose = worldPose->Data();
const auto cpWorld = pose.Rot().RotateVector(this->cp);
Expand All @@ -292,7 +294,9 @@ void LiftDragPrivate::Update(EntityComponentManager &_ecm)
}

if (vel.Length() <= 0.01)
{
return;
}

const auto velI = vel.Normalized();

Expand Down
3 changes: 2 additions & 1 deletion tutorials.md.in
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,6 @@ Gazebo @GZ_DESIGNATION_CAP@ library and how to use the library effectively.
* \subpage battery "Battery": Keep track of battery charge on robot models.
* \subpage particle_emitter "Particle emitter": Using particle emitters in simulation
* \subpage spherical_coordinates "Spherical coordinates": Working with latitude and longitude
* \subpage underwater_vehicles "Underwater Vehicles": Understand how to simulate underwater vehicles.
* \subpage logicalaudiosensor "Logical Audio Sensor": Using the LogicalAudioSensor system to mimic logical audio emission and detection in simulation.
* \subpage auto_inertia_calculation "Automatic Inertia Calculation": Automatically compute inertia values(mass, mass matrix, center of mass) for SDFormat links.

Expand Down Expand Up @@ -95,6 +94,8 @@ to increase the visual fidelity of your model.
for your model.
* \subpage adding_system_plugins "Adding system plugins:" How to add plugins to
your model to provide extra capabilities to it.
* \subpage lander "Create a lander vehicle:" How to create a lander robot.
* \subpage underwater_vehicles "Create an underwater vehicle:" How to create an underwater robot.

## License

Expand Down
297 changes: 297 additions & 0 deletions tutorials/files/lander/buoyant_lander.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,297 @@
<?xml version="1.0" ?>
<sdf version="1.7">
<world name="buoyant_lander">

<scene>
<ambient>0.0 1.0 1.0</ambient>
<grid>false</grid>
</scene>

<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>1 1 1 1</diffuse>
<specular>0.5 0.5 0.5 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>

<plugin
filename="gz-sim-physics-system"
name="gz::sim::systems::Physics">
</plugin>

<plugin
filename="gz-sim-buoyancy-system"
name="gz::sim::systems::Buoyancy">
<graded_buoyancy>
<default_density>1025</default_density>
<density_change>
<above_depth>0.5</above_depth>
<density>1.125</density>
</density_change>
</graded_buoyancy>
</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-sensors-system"
name="gz::sim::systems::Sensors">
</plugin>

<gui fullscreen="0">
<!-- 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>
<!-- looking at robot -->
<camera_pose>0 6 6 0 0.5 -1.57</camera_pose>
<!-- looking at all science data for 2003080103_mb_l3_las.csv -->
<!--camera_pose>-50000 -30000 250000 0 1.1 1.58</camera_pose-->
<camera_clip>
<!-- ortho view needs low near clip -->
<!-- but a very low near clip messes orbit's far clip ?! -->
<near>0.1</near>
<!-- See 3000 km away -->
<far>3000000</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>
<anchors target="3D View">
<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="InteractiveViewControl" name="Interactive view control">
<gz-gui>
<anchors target="3D View">
<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="CameraTracking" name="Camera Tracking">
<gz-gui>
<anchors target="3D View">
<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="MarkerManager" name="Marker manager">
<gz-gui>
<anchors target="3D View">
<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>
<warn_on_action_failure>false</warn_on_action_failure>
</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>
<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="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>
<!-- World control -->
<plugin filename="WorldControl" name="World control">
<gz-gui>
<title>World control</title>
<property type="bool" key="showTitleBar">false</property>
<property type="bool" key="resizable">false</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>true</play_pause>
<step>true</step>
<start_paused>true</start_paused>
</plugin>
<!-- World statistics -->
<plugin filename="WorldStats" name="World stats">
<gz-gui>
<title>World stats</title>
<property type="bool" key="showTitleBar">false</property>
<property type="bool" key="resizable">false</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>true</sim_time>
<real_time>true</real_time>
<real_time_factor>true</real_time_factor>
<iterations>true</iterations>
</plugin>
<plugin filename="Plot3D" name="Plot 3D">
<gz-gui>
<title>Plot lander 3D path</title>
<property type="string" key="state">docked_collapsed</property>
</gz-gui>
<entity_name>lander</entity_name>
<color>0 0 1</color>
<maximum_points>10000</maximum_points>
<minimum_distance>0.5</minimum_distance>
</plugin>
<plugin filename="ComponentInspector" name="Component Inspector">
<gz-gui>
<title>Inspector</title>
<property type="string" key="state">docked_collapsed</property>
</gz-gui>
</plugin>
</gui>

<!-- This invisible plane helps with orbiting the camera, especially at large scales -->
<model name="horizontal_plane">
<static>true</static>
<link name="link">
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<!-- 300 km x 300 km -->
<size>300000 300000</size>
</plane>
</geometry>
<transparency>1.0</transparency>
</visual>
</link>
</model>

<!-- Physics parameters -->
<physics name="1ms" type="dart">
<max_step_size>0.02</max_step_size>
<real_time_factor>1</real_time_factor>
</physics>

<!-- Model to load -->
<include>
<pose degrees="true">0 0 -3 0 0 0</pose>
<uri>my_lander</uri>
</include>

<!-- Ground plane -->
<model name="ground_plane">
<static>true</static>
<pose>0 0 -10 0 0 0</pose>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</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>
</link>
</model>

</world>
</sdf>
Binary file added tutorials/files/lander/gui_transform_control.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading

0 comments on commit beada29

Please sign in to comment.