Skip to content

Commit

Permalink
[backport Gazebo7] Fixed crash when collision size is zero (#2769)
Browse files Browse the repository at this point in the history
* Fixed crash when collision size is zero

Signed-off-by: ahcorde <ahcorde@gmail.com>

* Using ignition::math::isnan

Signed-off-by: ahcorde <ahcorde@gmail.com>

* Improved error message

Signed-off-by: ahcorde <ahcorde@gmail.com>

* fixed method to get the name of the visual

Signed-off-by: ahcorde <ahcorde@gmail.com>

* Fixed else brackets

Signed-off-by: ahcorde <ahcorde@gmail.com>

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

* Added test to check collisions equal to zero

Signed-off-by: ahcorde <ahcorde@gmail.com>

* Included feedback

Signed-off-by: ahcorde <ahcorde@gmail.com>

* make linters happy

Signed-off-by: ahcorde <ahcorde@gmail.com>

* Update Visual_TEST.cc
  • Loading branch information
ahcorde committed Jul 28, 2020
1 parent a07d57f commit 9351f5c
Show file tree
Hide file tree
Showing 3 changed files with 127 additions and 3 deletions.
15 changes: 12 additions & 3 deletions gazebo/rendering/Visual.cc
Original file line number Diff line number Diff line change
Expand Up @@ -793,9 +793,18 @@ void Visual::SetScale(const math::Vector3 &_scale)

this->dataPtr->scale = _scale.Ign();

this->dataPtr->sceneNode->setScale(
Conversions::Convert(math::Vector3(this->dataPtr->scale)));

if (!ignition::math::isnan(this->dataPtr->scale.X())
&& !ignition::math::isnan(this->dataPtr->scale.Y())
&& !ignition::math::isnan(this->dataPtr->scale.Z()))
{
this->dataPtr->sceneNode->setScale(
Conversions::Convert(this->dataPtr->scale));
}
else
{
gzerr << GetName() << ": Size of the collision contains one or several zeros." <<
" Collisions may not visualize properly." << std::endl;
}
// Scale selection object in case we have one attached. Other children were
// scaled from UpdateGeomSize
for (auto child : this->dataPtr->children)
Expand Down
36 changes: 36 additions & 0 deletions gazebo/rendering/Visual_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1514,6 +1514,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>

0 comments on commit 9351f5c

Please sign in to comment.