Skip to content
This repository has been archived by the owner on Feb 3, 2025. It is now read-only.

[Gazebo 9] Added test to check collisions equal to zero #2788

Merged
merged 4 commits into from
Jul 23, 2020
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
36 changes: 36 additions & 0 deletions gazebo/rendering/Visual_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1588,6 +1588,42 @@ TEST_F(Visual_TEST, ConvertVisualType)
rendering::Visual::ConvertVisualType(msgs::Visual::PHYSICS));
}

TEST_F(Visual_TEST, CollisionZero)
{
// This test checks that there isn't a segmentation fault when inserting
// zero collision geometries.
// Load a world containing 3 simple shapes with collision geometry equals
// to zero.
Load("worlds/collision_zero.world");

// Get the scene
gazebo::rendering::ScenePtr scene = gazebo::rendering::get_scene();
ASSERT_NE(scene, nullptr);

// Wait until all models are inserted
int sleep = 0;
int maxSleep = 10;
rendering::VisualPtr box, sphere, cylinder;
while ((!box || !sphere || !cylinder) && sleep < maxSleep)
{
event::Events::preRender();
event::Events::render();
event::Events::postRender();

box = scene->GetVisual("box");
cylinder = scene->GetVisual("cylinder");
sphere = scene->GetVisual("sphere");
common::Time::MSleep(1000);
sleep++;
}
scene->ShowCollisions(true);
// box
ASSERT_NE(box, nullptr);
// cylinder
ASSERT_NE(cylinder, nullptr);
// sphere
ASSERT_NE(sphere, nullptr);
}
/////////////////////////////////////////////////
TEST_F(Visual_TEST, Scale)
{
Expand Down
79 changes: 79 additions & 0 deletions worlds/collision_zero.world
Original file line number Diff line number Diff line change
@@ -0,0 +1,79 @@
<?xml version="1.0" ?>
<sdf version="1.5">
<world name="default">
<include>
<uri>model://ground_plane</uri>
</include>
<include>
<uri>model://sun</uri>
</include>
<model name="box">
<pose>0 0 0.5 0 0 0</pose>
<link name="link">
<collision name="collision">
<geometry>
<box>
<size>0 0 0</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
<material>
<script>Gazebo/WoodPallet</script>
</material>
</visual>
</link>
</model>
<model name="sphere">
<pose>0 1.5 0.5 0 0 0</pose>
<link name="link">
<collision name="collision">
<geometry>
<sphere>
<radius>0</radius>
</sphere>
</geometry>
</collision>
<visual name="visual">
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
<material>
<script>Gazebo/WoodPallet</script>
</material>
</visual>
</link>
</model>
<model name="cylinder">
<pose>0 -1.5 0.5 0 1.5707 0</pose>
<link name="link">
<collision name="collision">
<geometry>
<cylinder>
<radius>0</radius>
<length>0</length>
</cylinder>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder>
<radius>0.5</radius>
<length>1.0</length>
</cylinder>
</geometry>
<material>
<script>Gazebo/WoodPallet</script>
</material>
</visual>
</link>
</model>
</world>
</sdf>