Skip to content

Commit

Permalink
Heightmap physics (with DART) 🏔️ (#661)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
Signed-off-by: Steve Peters <[email protected]>

Co-authored-by: Alejandro Hernández Cordero <[email protected]>
Co-authored-by: Steve Peters <[email protected]>
  • Loading branch information
3 people authored Jul 17, 2021
1 parent f2706be commit d7741f6
Show file tree
Hide file tree
Showing 7 changed files with 543 additions and 20 deletions.
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -89,6 +89,7 @@ ign_find_package (Qt5
# Find ignition-physics
ign_find_package(ignition-physics4
COMPONENTS
heightmap
mesh
sdf
REQUIRED
Expand Down
259 changes: 255 additions & 4 deletions examples/worlds/heightmap.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -3,12 +3,15 @@
Demonstrates a heightmap terrain.
At the moment, only the visuals work, but not the physics collisions, see
https://github.com/ignitionrobotics/ign-physics/issues/156.
-->
<sdf version="1.6">
<world name="heightmap">
<physics name="1ms" type="ignored">
<dart>
<!-- Heightmaps behave better with the bullet collision detector -->
<collision_detector>bullet</collision_detector>
</dart>
</physics>

<!-- 3D scene -->
<gui>
Expand All @@ -23,7 +26,111 @@
<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>-16.6 7.3 8.6 0.0 0.4 -0.45</camera_pose>
<camera_pose>-80 40 60 0.0 0.4 -0.45</camera_pose>
</plugin>

<!-- Play / pause / step -->
<plugin filename="WorldControl" name="World control">
<ignition-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>
</ignition-gui>

<play_pause>true</play_pause>
<step>true</step>
<start_paused>true</start_paused>
</plugin>

<!-- Time / RTF -->
<plugin filename="WorldStats" name="World stats">
<ignition-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>
</ignition-gui>

<sim_time>true</sim_time>
<real_time>true</real_time>
<real_time_factor>true</real_time_factor>
<iterations>true</iterations>
</plugin>

<!-- Translate / rotate -->
<plugin filename="TransformControl" name="Transform control">
<ignition-gui>
<title>Transform control</title>
<property key="resizable" type="bool">false</property>
<property key="x" type="double">0</property>
<property key="y" type="double">0</property>
<property key="width" type="double">250</property>
<property key="height" type="double">50</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
<property key="cardBackground" type="string">#666666</property>
</ignition-gui>
</plugin>

<!-- Insert simple shapes -->
<plugin filename="Shapes" name="Shapes">
<ignition-gui>
<property key="resizable" type="bool">false</property>
<property key="x" type="double">250</property>
<property key="y" type="double">0</property>
<property key="width" type="double">150</property>
<property key="height" type="double">50</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
<property key="cardBackground" type="string">#666666</property>
</ignition-gui>
</plugin>

<!-- Insert lights -->
<plugin filename="Lights" name="Lights">
<ignition-gui>
<property key="resizable" type="bool">false</property>
<property key="x" type="double">400</property>
<property key="y" type="double">0</property>
<property key="width" type="double">150</property>
<property key="height" type="double">50</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
<property key="cardBackground" type="string">#666666</property>
</ignition-gui>
</plugin>

<!-- Inspector -->
<plugin filename="ComponentInspector" name="Component inspector">
<ignition-gui>
<property type="bool" key="showTitleBar">false</property>
<property type="string" key="state">docked</property>
</ignition-gui>
</plugin>

<!-- Entity tree -->
<plugin filename="EntityTree" name="Entity tree">
<ignition-gui>
<property type="bool" key="showTitleBar">false</property>
<property type="string" key="state">docked</property>
</ignition-gui>
</plugin>

</gui>
Expand All @@ -42,6 +149,150 @@
<direction>-0.5 0.1 -0.9</direction>
</light>

<model name="sphere_red">
<pose>30 30 10 0 0 0</pose>
<link name="sphere_link">
<inertial>
<inertia>
<ixx>3</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>3</iyy>
<iyz>0</iyz>
<izz>3</izz>
</inertia>
<mass>3.0</mass>
</inertial>
<collision name="sphere_collision">
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
</collision>
<visual name="sphere_visual">
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>1 0 0 1</diffuse>
<specular>1 0 0 1</specular>
</material>
</visual>
</link>
</model>

<model name="sphere_green">
<pose>30 -30 10 0 0 0</pose>
<link name="sphere_link">
<inertial>
<inertia>
<ixx>3</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>3</iyy>
<iyz>0</iyz>
<izz>3</izz>
</inertia>
<mass>3.0</mass>
</inertial>
<collision name="sphere_collision">
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
</collision>
<visual name="sphere_visual">
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
<material>
<ambient>0 1 0 1</ambient>
<diffuse>0 1 0 1</diffuse>
<specular>0 1 0 1</specular>
</material>
</visual>
</link>
</model>

<model name="sphere_blue">
<pose>-30 30 10 0 0 0</pose>
<link name="sphere_link">
<inertial>
<inertia>
<ixx>3</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>3</iyy>
<iyz>0</iyz>
<izz>3</izz>
</inertia>
<mass>3.0</mass>
</inertial>
<collision name="sphere_collision">
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
</collision>
<visual name="sphere_visual">
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
<material>
<ambient>0 0 1 1</ambient>
<diffuse>0 0 1 1</diffuse>
<specular>0 0 1 1</specular>
</material>
</visual>
</link>
</model>

<model name="sphere_yellow">
<pose>-30 -30 20 0 0 0</pose>
<link name="sphere_link">
<inertial>
<inertia>
<ixx>3</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>3</iyy>
<iyz>0</iyz>
<izz>3</izz>
</inertia>
<mass>3.0</mass>
</inertial>
<collision name="sphere_collision">
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
</collision>
<visual name="sphere_visual">
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
<material>
<ambient>1 1 0 1</ambient>
<diffuse>1 1 0 1</diffuse>
<specular>1 1 0 1</specular>
</material>
</visual>
</link>
</model>

<include>
<uri>
https://fuel.ignitionrobotics.org/1.0/chapulina/models/Heightmap Bowl
Expand Down
12 changes: 9 additions & 3 deletions src/rendering/RenderUtil.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1893,9 +1893,15 @@ void RenderUtilPrivate::HighlightNode(const rendering::NodePtr &_node)
white->SetEmissive(1.0, 1.0, 1.0);
}

ignition::rendering::WireBoxPtr wireBox =
this->scene->CreateWireBox();
ignition::math::AxisAlignedBox aabb = vis->LocalBoundingBox();
auto aabb = vis->LocalBoundingBox();
if (aabb == math::AxisAlignedBox())
{
// Infinite bounding box, skip highlighting this node.
// This happens for Heightmaps, for example.
return;
}

auto wireBox = this->scene->CreateWireBox();
wireBox->SetBox(aabb);

// Create visual and add wire box
Expand Down
Loading

0 comments on commit d7741f6

Please sign in to comment.