Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Distortion/LensFlarePlugin: set compositor names #3007

Merged
merged 11 commits into from
May 27, 2021
11 changes: 10 additions & 1 deletion gazebo/rendering/Distortion.cc
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,9 @@ namespace gazebo
/// \brief Lens center used for distortion
public: ignition::math::Vector2d lensCenter = {0.5, 0.5};

/// \brief Compositor name to be used for distortion
public: std::string compositorName = "CameraDistortionMap/Default";

/// \brief Scale applied to distorted image.
public: ignition::math::Vector2d distortionScale = {1.0, 1.0};

Expand Down Expand Up @@ -113,6 +116,12 @@ void Distortion::Load(sdf::ElementPtr _sdf)
this->dataPtr->lensCenter = _sdf->Get<ignition::math::Vector2d>("center");

this->dataPtr->distortionCrop = this->dataPtr->k1 < 0;

const std::string compositorName = "ignition:compositor";
if (_sdf->HasElement(compositorName))
{
this->dataPtr->compositorName = _sdf->Get<std::string>(compositorName);
}
}

//////////////////////////////////////////////////
Expand Down Expand Up @@ -330,7 +339,7 @@ void Distortion::SetCamera(CameraPtr _camera)

this->dataPtr->lensDistortionInstance =
Ogre::CompositorManager::getSingleton().addCompositor(
_camera->OgreViewport(), "CameraDistortionMap/Default");
_camera->OgreViewport(), this->dataPtr->compositorName);
this->dataPtr->lensDistortionInstance->getTechnique()->getOutputTargetPass()->
getPass(0)->setMaterial(this->dataPtr->distortionMaterial);

Expand Down
25 changes: 17 additions & 8 deletions gazebo/rendering/LensFlare.cc
Original file line number Diff line number Diff line change
Expand Up @@ -349,6 +349,16 @@ namespace gazebo
public: std::shared_ptr<LensFlareCompositorListener>
lensFlareCompositorListener;

/// \brief Scale of lens flare.
public: double lensFlareScale = 1.0;

/// \brief Color of lens flare.
public: ignition::math::Vector3d lensFlareColor
= ignition::math::Vector3d(1.0, 1.0, 1.0);

/// \brief Compositor name to be used for lens flare
public: std::string compositorName = "CameraLensFlare/Default";

/// \brief Pointer to camera
public: CameraPtr camera;

Expand All @@ -369,13 +379,6 @@ namespace gazebo

/// \brief Connection for the pre render event.
public: event::ConnectionPtr preRenderConnection;

/// \brief Scale of lens flare.
public: double lensFlareScale = 1.0;

/// \brief Color of lens flare.
public: ignition::math::Vector3d lensFlareColor
= ignition::math::Vector3d(1.0, 1.0, 1.0);
};
}
}
Expand Down Expand Up @@ -423,7 +426,7 @@ void LensFlare::SetCamera(CameraPtr _camera)

this->dataPtr->lensFlareInstance =
Ogre::CompositorManager::getSingleton().addCompositor(
this->dataPtr->camera->OgreViewport(), "CameraLensFlare/Default");
this->dataPtr->camera->OgreViewport(), this->dataPtr->compositorName);
this->dataPtr->lensFlareInstance->getTechnique()->getOutputTargetPass()->
getPass(0)->setMaterial(lensFlareMaterial);

Expand Down Expand Up @@ -460,6 +463,12 @@ void LensFlare::SetColor(const ignition::math::Vector3d &_color)
}
}

//////////////////////////////////////////////////
void LensFlare::SetCompositorName(const std::string &_name)
{
this->dataPtr->compositorName = _name;
}

//////////////////////////////////////////////////
void LensFlare::Update()
{
Expand Down
5 changes: 5 additions & 0 deletions gazebo/rendering/LensFlare.hh
Original file line number Diff line number Diff line change
Expand Up @@ -123,6 +123,11 @@ namespace gazebo
/// \param[in] _color Color of lens flare
public: void SetColor(const ignition::math::Vector3d &_color);

/// \brief Set the name of the lens flare compositor to use the next
/// time SetCamera is called.
/// \param[in] _name Name of the compositor to use
public: void SetCompositorName(const std::string &_name);

/// \brief Update function to search light source
protected: void Update();

Expand Down
29 changes: 28 additions & 1 deletion media/materials/scripts/distortion.compositor
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ compositor CameraDistortionMap/Default
{
// Temporary textures
texture rt0 target_width target_height PF_A8R8G8B8

target rt0
{
// Render output from previous compositor (or original scene)
Expand All @@ -24,3 +24,30 @@ compositor CameraDistortionMap/Default
}
}
}

compositor CameraDistortionMap/PF_FLOAT32_R
{
technique
{
// Temporary textures
texture rt0 target_width target_height PF_FLOAT32_R

target rt0
{
// Render output from previous compositor (or original scene)
input previous
}
target_output
{
// Start with clear output
input none
// Draw a fullscreen quad with noise
pass render_quad
{
// Renders a fullscreen quad with a material
material Gazebo/CameraDistortionMap
input 0 rt0
}
}
}
}
27 changes: 27 additions & 0 deletions media/materials/scripts/lens_flare.compositor
Original file line number Diff line number Diff line change
Expand Up @@ -24,3 +24,30 @@ compositor CameraLensFlare/Default
}
}
}

compositor CameraLensFlare/PF_FLOAT32_R
{
technique
{
// Temporary textures
texture rt0 target_width target_height PF_FLOAT32_R

target rt0
{
// Render output from previous compositor (or original scene)
input previous
}
target_output
{
// Start with clear output
input none
// Draw a fullscreen quad
pass render_quad
{
// Renders a fullscreen quad with a material
material Gazebo/CameraLensFlare
input 0 rt0
}
}
}
}
13 changes: 13 additions & 0 deletions plugins/LensFlareSensorPlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,9 @@ namespace gazebo
/// \brief Lens flare color
public: ignition::math::Vector3d color
= ignition::math::Vector3d(1.4, 1.2, 1.0);

/// \brief Lens flare compositor name
public: std::string compositorName;
};
}

Expand Down Expand Up @@ -84,6 +87,12 @@ void LensFlareSensorPlugin::Load(sensors::SensorPtr _sensor,
this->dataPtr->color = _sdf->Get<ignition::math::Vector3d>("color");
}

const std::string compositorName = "compositor";
if (_sdf->HasElement(compositorName))
{
this->dataPtr->compositorName = _sdf->Get<std::string>(compositorName);
}

sensors::CameraSensorPtr cameraSensor =
std::dynamic_pointer_cast<sensors::CameraSensor>(_sensor);

Expand Down Expand Up @@ -140,6 +149,10 @@ void LensFlareSensorPlugin::AddLensFlare(rendering::CameraPtr _camera)

rendering::LensFlarePtr lensFlare;
lensFlare.reset(new rendering::LensFlare);
if (!this->dataPtr->compositorName.empty())
{
lensFlare->SetCompositorName(this->dataPtr->compositorName);
}
lensFlare->SetCamera(_camera);
lensFlare->SetScale(this->dataPtr->scale);
lensFlare->SetColor(this->dataPtr->color);
Expand Down
1 change: 1 addition & 0 deletions plugins/LensFlareSensorPlugin.hh
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@ namespace gazebo
/// \brief Plugin that adds lens flare effect to a camera or multicamera
/// sensor
/// The plugin has the following optional parameter:
/// <compositor> Name of the lens flare compositor to use.
/// <scale> Scale of lens flare. Must be greater than 0
/// <color> Color of lens flare.
/// \todo A potentially useful feature would be an option for constantly
Expand Down
112 changes: 112 additions & 0 deletions test/integration/camera_sensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1929,3 +1929,115 @@ TEST_F(CameraSensor, Light)
}
EXPECT_EQ(newColor, sun->DiffuseColor());
}

/////////////////////////////////////////////////
TEST_F(CameraSensor, SetCompositorNames)
{
#if not defined(__APPLE__)
Load("worlds/test/issue_3005_set_compositor_names.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;
}

const unsigned int width = 12;
const unsigned int height = 12;

for (auto camera_name : {
"camera_distortion_default", "camera_lens_flare_default"})
{
// check camera with default texture format
sensors::SensorPtr sensor = sensors::get_sensor(camera_name);
sensors::CameraSensorPtr cameraSensor =
std::dynamic_pointer_cast<sensors::CameraSensor>(sensor);

imageCount = 0;
img = new unsigned char[width * height * 3];
event::ConnectionPtr c =
cameraSensor->Camera()->ConnectNewImageFrame(
std::bind(&::OnNewCameraFrame, &imageCount, img,
std::placeholders::_1, std::placeholders::_2, std::placeholders::_3,
std::placeholders::_4, std::placeholders::_5));

// Get some images
int sleep = 0;
int maxSleep = 30;
while (imageCount < 10 && sleep < maxSleep)
{
common::Time::MSleep(50);
sleep++;
}

unsigned int rSum = 0;
unsigned int gSum = 0;
unsigned int bSum = 0;
for (unsigned int i = 0; i < height*width*3; i+=3)
{
unsigned int r = img[i];
unsigned int g = img[i+1];
unsigned int b = img[i+2];
rSum += r;
gSum += g;
bSum += b;
}

EXPECT_NE(rSum, gSum);
EXPECT_NE(rSum, bSum);
EXPECT_NE(gSum, bSum);

EXPECT_GT(rSum - bSum, 25000.0);
EXPECT_GT(rSum - gSum, 20000.0);

delete [] img;
}

for (auto camera_name : {"camera_distortion_test", "camera_lens_flare_test"})
{
// check camera with grayscale texture format
sensors::SensorPtr sensor = sensors::get_sensor(camera_name);
sensors::CameraSensorPtr cameraSensor =
std::dynamic_pointer_cast<sensors::CameraSensor>(sensor);

imageCount = 0;
img = new unsigned char[width * height * 3];
event::ConnectionPtr c =
cameraSensor->Camera()->ConnectNewImageFrame(
std::bind(&::OnNewCameraFrame, &imageCount, img,
std::placeholders::_1, std::placeholders::_2, std::placeholders::_3,
std::placeholders::_4, std::placeholders::_5));

// Get some images
int sleep = 0;
int maxSleep = 30;
while (imageCount < 10 && sleep < maxSleep)
{
common::Time::MSleep(50);
sleep++;
}

unsigned int rSum = 0;
unsigned int gSum = 0;
unsigned int bSum = 0;
for (unsigned int i = 0; i < height*width*3; i+=3)
{
unsigned int r = img[i];
unsigned int g = img[i+1];
unsigned int b = img[i+2];
rSum += r;
gSum += g;
bSum += b;
}

// For grayscale, all RGB channels should have the same value
EXPECT_EQ(rSum, gSum);
EXPECT_EQ(gSum, bSum);
EXPECT_GT(gSum, 10000u);

delete [] img;
}
#endif
}
Loading