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

Commit

Permalink
Added a test case for wideangle camera lensflare
Browse files Browse the repository at this point in the history
Signed-off-by: Aditya <aditya050995@gmail.com>
  • Loading branch information
adityapande-1995 committed Dec 28, 2022
1 parent a545ff7 commit 3db8327
Show file tree
Hide file tree
Showing 2 changed files with 229 additions and 0 deletions.
101 changes: 101 additions & 0 deletions test/integration/camera_sensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1411,6 +1411,107 @@ TEST_F(CameraSensor, LensFlare)
delete[] img3;
}

/////////////////////////////////////////////////
TEST_F(CameraSensor, LensFlareWideAngleCamera)
{
Load("worlds/lensflare_wideangle_cam.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;
}

// Get the lens flare wide angle camera model.
std::string modelNameLensFlare = "wide_angle_camera_lensflare";
std::string cameraNameLensFlare = "camera_sensor_lensflare";

physics::WorldPtr world = physics::get_world();
ASSERT_TRUE(world != nullptr);
physics::ModelPtr model = world->ModelByName(modelNameLensFlare);
ASSERT_TRUE(model != nullptr);

sensors::SensorPtr sensorLensFlare =
sensors::get_sensor(cameraNameLensFlare);
sensors::CameraSensorPtr camSensorLensFlare =
std::dynamic_pointer_cast<sensors::CameraSensor>(sensorLensFlare);
ASSERT_TRUE(camSensorLensFlare != nullptr);

// Get the wide angle camera without the lens flare.
std::string modelNameWithoutLensFlare = "wide_angle_camera_lensflare";
std::string cameraNameWithoutLensFlare = "camera_sensor_without_lensflare";

model = world->ModelByName(modelNameWithoutLensFlare);
ASSERT_TRUE(model != nullptr);

sensors::SensorPtr sensorWithoutLensFlare =
sensors::get_sensor(cameraNameWithoutLensFlare);
sensors::CameraSensorPtr camSensorWithoutLensFlare =
std::dynamic_pointer_cast<sensors::CameraSensor>(sensorWithoutLensFlare);
ASSERT_TRUE(camSensorWithoutLensFlare != nullptr);

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

// Collect images from the 2 cameras.
imageCount = 0;
imageCount2 = 0;
img = new unsigned char[width * height * 3];
img2 = new unsigned char[width * height * 3];
event::ConnectionPtr c =
camSensorLensFlare->Camera()->ConnectNewImageFrame(
std::bind(&::OnNewCameraFrame, &imageCount, img,
std::placeholders::_1, std::placeholders::_2, std::placeholders::_3,
std::placeholders::_4, std::placeholders::_5));
event::ConnectionPtr c2 =
camSensorWithoutLensFlare->Camera()->ConnectNewImageFrame(
std::bind(&::OnNewCameraFrame, &imageCount2, img2,
std::placeholders::_1, std::placeholders::_2, std::placeholders::_3,
std::placeholders::_4, std::placeholders::_5));

// Get some images.
int sleep = 0;
while ((imageCount < 10 || imageCount2 < 10)
&& sleep++ < 1000)
{
common::Time::MSleep(10);
}

EXPECT_GE(imageCount, 10);
EXPECT_GE(imageCount2, 10);

c.reset();
c2.reset();

// Compare colors.
unsigned int colorSum = 0;
unsigned int colorSum2 = 0;
for (unsigned int y = 0; y < height; ++y)
{
for (unsigned int x = 0; x < width*3; x+=3)
{
unsigned int r = img[(y*width*3) + x];
unsigned int g = img[(y*width*3) + x + 1];
unsigned int b = img[(y*width*3) + x + 2];
colorSum += r + g + b;
unsigned int r2 = img2[(y*width*3) + x];
unsigned int g2 = img2[(y*width*3) + x + 1];
unsigned int b2 = img2[(y*width*3) + x + 2];
colorSum2 += r2 + g2 + b2;
}
}

// Camera with lens flare should be brighter than camera without it.
EXPECT_GT(colorSum, colorSum2) <<
"colorSum: " << colorSum << ", " <<
"colorSum2: " << colorSum2;

delete[] img;
delete[] img2;
}

/////////////////////////////////////////////////
TEST_F(CameraSensor, 16bit)
{
Expand Down
128 changes: 128 additions & 0 deletions worlds/lensflare_wideangle_cam.world
Original file line number Diff line number Diff line change
@@ -0,0 +1,128 @@
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="default">

<!-- Light Source -->
<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 0 0.0 0.0 0.0</pose>
<diffuse>1.0 1.0 1.0 1.0</diffuse>
<specular>0.2 0.2 0.2 1</specular>
<direction>-1.0 0.0 -0.2</direction>
</light>

<!-- A ground plane -->
<include>
<uri>model://ground_plane</uri>
</include>

<model name="heightmap">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<heightmap>
<uri>file://media/materials/textures/heightmap_bowl.png</uri>
<size>129 129 10</size>
<pos>0 0 0</pos>
</heightmap>
</geometry>
</collision>
<visual name="visual_abcedf">
<geometry>
<heightmap>
<use_terrain_paging>false</use_terrain_paging>
<texture>
<diffuse>file://media/materials/textures/dirt_diffusespecular.png</diffuse>
<normal>file://media/materials/textures/flat_normal.png</normal>
<size>1</size>
</texture>
<texture>
<diffuse>file://media/materials/textures/grass_diffusespecular.png</diffuse>
<normal>file://media/materials/textures/flat_normal.png</normal>
<size>1</size>
</texture>
<texture>
<diffuse>file://media/materials/textures/fungus_diffusespecular.png</diffuse>
<normal>file://media/materials/textures/flat_normal.png</normal>
<size>1</size>
</texture>
<blend>
<min_height>2</min_height>
<fade_dist>5</fade_dist>
</blend>
<blend>
<min_height>4</min_height>
<fade_dist>5</fade_dist>
</blend>
<uri>file://media/materials/textures/heightmap_bowl.png</uri>
<size>129 129 10</size>
<pos>0 0 0</pos>
</heightmap>
</geometry>
</visual>
</link>
</model>

<!-- wide-angle camera model with lens flare plugin -->
<model name="wide_angle_camera_lensflare">
<static>true</static>
<pose>0 2 5.2 0 0 0</pose>
<link name="link">
<visual name="visual">
<geometry>
<box>
<size>0.1 0.1 0.1</size>
</box>
</geometry>
</visual>
<sensor name="camera_sensor_lensflare" type="wideanglecamera">
<camera>
<horizontal_fov>1.047</horizontal_fov>
<image>
<width>320</width>
<height>240</height>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<lens>
<type>gnomonical</type>
<scale_to_hfov>true</scale_to_hfov>
<cutoff_angle>1.5707</cutoff_angle>
<env_texture_size>512</env_texture_size>
</lens>
</camera>
<always_on>1</always_on>
<update_rate>25</update_rate>
<visualize>true</visualize>
<plugin name="lensflare" filename="libLensFlareSensorPlugin.so"/>
</sensor>
<sensor name="camera_sensor_without_lensflare" type="wideanglecamera">
<camera>
<horizontal_fov>1.047</horizontal_fov>
<image>
<width>320</width>
<height>240</height>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<lens>
<type>gnomonical</type>
<scale_to_hfov>true</scale_to_hfov>
<cutoff_angle>1.5707</cutoff_angle>
<env_texture_size>512</env_texture_size>
</lens>
</camera>
<always_on>1</always_on>
<update_rate>25</update_rate>
<visualize>true</visualize>
</sensor>
</link>
</model>

</world>
</sdf>

0 comments on commit 3db8327

Please sign in to comment.