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

Commit

Permalink
Added tests for shadow_caster_render_back_faces param
Browse files Browse the repository at this point in the history
Signed-off-by: William Lew <WilliamMilesLew@gmail.com>
  • Loading branch information
WilliamLewww committed Oct 13, 2021
1 parent abe295e commit 349b235
Show file tree
Hide file tree
Showing 5 changed files with 325 additions and 1 deletion.
1 change: 1 addition & 0 deletions test/integration/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -99,6 +99,7 @@ set(tests
sensor.cc
sdf_frame_semantics.cc
server_fixture.cc
shadow_caster_render_back_faces.cc
sim_events.cc
speed.cc
speed_thread_islands.cc
Expand Down
175 changes: 175 additions & 0 deletions test/integration/shadow_caster_render_back_faces.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,175 @@
/*
* Copyright (C) 2021 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

#include "gazebo/test/ServerFixture.hh"
#include "gazebo/sensors/sensors.hh"

using namespace gazebo;
class ShadowCasterRenderBackFacesTest : public ServerFixture
{
/// \brief Test rendering back faces
public: void ShadowCasterBackFaces();

/// \brief Test rendering without back face
public: void ShadowCasterNoBackFaces();

/// \brief Counter for the numbder of image messages received.
public: unsigned int imageCount = 0u;

/// \brief Depth data buffer.
public: unsigned char* imageBuffer = nullptr;

/// \brief Camera image callback
/// \param[in] _msg Message with image data containing raw image values.
public: void OnImage(ConstImageStampedPtr &_msg);
};

/////////////////////////////////////////////////
void ShadowCasterRenderBackFacesTest::OnImage(ConstImageStampedPtr &_msg)
{
unsigned int imageSamples = _msg->image().width() *_msg->image().height() * 3;
memcpy(this->imageBuffer, _msg->image().data().c_str(), imageSamples);
this->imageCount++;
}

/////////////////////////////////////////////////
// \brief The shadow caster will render back faces; The plane in the world will
/// cast a shadow
void ShadowCasterRenderBackFacesTest::ShadowCasterBackFaces()
{
this->Load("worlds/shadow_caster_back_faces.world");

// Make sure the render engine is available.
if (rendering::RenderEngine::Instance()->GetRenderPathType() ==
rendering::RenderEngine::NONE)
{
gzerr << "No rendering engine, unable to run camera test\n";
return;
}

sensors::CameraSensorPtr sensor =
std::dynamic_pointer_cast<sensors::CameraSensor>(
sensors::get_sensor("camera_normal"));
EXPECT_TRUE(sensor != nullptr);
EXPECT_TRUE(sensor->IsActive());

unsigned int width = 320;
unsigned int height = 240;

this->imageCount = 0;
this->imageBuffer = new unsigned char[width * height*3];

transport::NodePtr node(new transport::Node());
node->Init();

std::string topic = sensor->Topic();
EXPECT_TRUE(!topic.empty());

transport::SubscriberPtr sub = node->Subscribe(topic,
&ShadowCasterRenderBackFacesTest::OnImage, this);

// wait for a few images
int i = 0;
while (this->imageCount < 10 && i < 300)
{
common::Time::MSleep(10);
i++;
}
EXPECT_LT(i, 300);

for (unsigned int x = 0; x < 320 * 240; x += 600) {
EXPECT_GT(50, this->imageBuffer[3 * x]);
EXPECT_GT(50, this->imageBuffer[3 * x + 1]);
EXPECT_GT(50, this->imageBuffer[3 * x + 2]);
}

delete this->imageBuffer;
}

/////////////////////////////////////////////////
TEST_F(ShadowCasterRenderBackFacesTest, ShadowCasterBackFaces)
{
ShadowCasterBackFaces();
}

/////////////////////////////////////////////////
// \brief The shadow caster will not render back faces; The plane in the world
/// will not cast a shadow
void ShadowCasterRenderBackFacesTest::ShadowCasterNoBackFaces()
{
this->Load("worlds/shadow_caster_no_back_faces.world");

// Make sure the render engine is available.
if (rendering::RenderEngine::Instance()->GetRenderPathType() ==
rendering::RenderEngine::NONE)
{
gzerr << "No rendering engine, unable to run camera test\n";
return;
}

sensors::CameraSensorPtr sensor =
std::dynamic_pointer_cast<sensors::CameraSensor>(
sensors::get_sensor("camera_normal"));
EXPECT_TRUE(sensor != nullptr);
EXPECT_TRUE(sensor->IsActive());

unsigned int width = 320;
unsigned int height = 240;

this->imageCount = 0;
this->imageBuffer = new unsigned char[width * height*3];

transport::NodePtr node(new transport::Node());
node->Init();

std::string topic = sensor->Topic();
EXPECT_TRUE(!topic.empty());

transport::SubscriberPtr sub = node->Subscribe(topic,
&ShadowCasterRenderBackFacesTest::OnImage, this);

// wait for a few images
int i = 0;
while (this->imageCount < 10 && i < 300)
{
common::Time::MSleep(10);
i++;
}
EXPECT_LT(i, 300);

for (unsigned int x = 0; x < 320 * 240; x += 600) {
EXPECT_LT(50, this->imageBuffer[3 * x]);
EXPECT_LT(50, this->imageBuffer[3 * x + 1]);
EXPECT_LT(50, this->imageBuffer[3 * x + 2]);
}

delete this->imageBuffer;
}

/////////////////////////////////////////////////
TEST_F(ShadowCasterRenderBackFacesTest, ShadowCasterNoBackFaces)
{
ShadowCasterNoBackFaces();
}

/////////////////////////////////////////////////
int main(int argc, char **argv)
{
::testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}

2 changes: 1 addition & 1 deletion test/worlds/custom_shadow_caster.world
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@
<image>
<width>320</width>
<height>240</height>
<format>R8G8B8</format>\
<format>R8G8B8</format>
</image>
<clip>
<near>0.1</near>
Expand Down
74 changes: 74 additions & 0 deletions test/worlds/shadow_caster_back_faces.world
Original file line number Diff line number Diff line change
@@ -0,0 +1,74 @@
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="default">

<light name='sun' type='directional'>
<cast_shadows>1</cast_shadows>
<pose>0 0 0 0 0 0</pose>
<diffuse>1.0 1.0 1.0 1</diffuse>
<specular>1.0 1.0 1.0 1</specular>
<direction>1 0 -0.2</direction>
</light>

<include>
<uri>model://ground_plane</uri>
</include>

<scene>
<ignition:shadow_caster_render_back_faces>true</ignition:shadow_caster_render_back_faces>
<background>0.0 0.0 0.0 1</background>
</scene>

<model name='camera_normal'>
<static>1</static>
<pose>5 0.0 0.25 0 1.5 0</pose>
<link name='link'>
<visual name='visual'>
<geometry>
<box>
<size>0.1 0.1 0.1</size>
</box>
</geometry>
</visual>
<sensor name='camera_normal' type='camera'>
<camera>
<horizontal_fov>1.047</horizontal_fov>
<image>
<width>320</width>
<height>240</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
</camera>
<always_on>1</always_on>
<update_rate>10</update_rate>
</sensor>
</link>
</model>

<model name="box">
<static>true</static>
<pose>0 0 1.0 0 2.0 0</pose>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<size>1 1 1</size>
</plane>
</geometry>
</collision>
<visual name="visual">
<geometry>
<plane>
<size>1 1 1</size>
</plane>
</geometry>
</visual>
</link>
</model>

</world>
</sdf>
74 changes: 74 additions & 0 deletions test/worlds/shadow_caster_no_back_faces.world
Original file line number Diff line number Diff line change
@@ -0,0 +1,74 @@
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="default">

<light name='sun' type='directional'>
<cast_shadows>1</cast_shadows>
<pose>0 0 0 0 0 0</pose>
<diffuse>1.0 1.0 1.0 1</diffuse>
<specular>1.0 1.0 1.0 1</specular>
<direction>1 0 -0.2</direction>
</light>

<include>
<uri>model://ground_plane</uri>
</include>

<scene>
<ignition:shadow_caster_render_back_faces>false</ignition:shadow_caster_render_back_faces>
<background>0.0 0.0 0.0 1</background>
</scene>

<model name='camera_normal'>
<static>1</static>
<pose>5 0.0 0.25 0 1.5 0</pose>
<link name='link'>
<visual name='visual'>
<geometry>
<box>
<size>0.1 0.1 0.1</size>
</box>
</geometry>
</visual>
<sensor name='camera_normal' type='camera'>
<camera>
<horizontal_fov>1.047</horizontal_fov>
<image>
<width>320</width>
<height>240</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
</camera>
<always_on>1</always_on>
<update_rate>10</update_rate>
</sensor>
</link>
</model>

<model name="box">
<static>true</static>
<pose>0 0 1.0 0 2.0 0</pose>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<size>1 1 1</size>
</plane>
</geometry>
</collision>
<visual name="visual">
<geometry>
<plane>
<size>1 1 1</size>
</plane>
</geometry>
</visual>
</link>
</model>

</world>
</sdf>

0 comments on commit 349b235

Please sign in to comment.