diff --git a/examples/worlds/global_illumination.sdf b/examples/worlds/global_illumination.sdf
new file mode 100644
index 0000000000..1c2f0b0bac
--- /dev/null
+++ b/examples/worlds/global_illumination.sdf
@@ -0,0 +1,328 @@
+
+
+
+
+
+
+
+
+ ogre2
+
+ true
+ 16 16 16
+ 1 1 1
+ 6
+ true
+ true
+ 1.0
+ false
+ none
+
+
+
+
+
+
+
+
+
+ 0.1 0.1 0.1
+ 0 0 0
+
+
+
+
+
+
+ Cornell box GI demo
+ true
+ docked
+
+ ogre2
+ -12 0 4 0 0 0
+
+
+
+ camera
+
+
+
+
+
+
+ false
+ 5
+ 5
+ floating
+ false
+
+
+
+
+
+ false
+ 5
+ 5
+ floating
+ false
+
+
+
+
+
+ false
+ 0
+ 50
+ 250
+ 50
+ docked
+ true
+ #777777
+
+
+
+
+ false
+ 5
+ 5
+ floating
+ false
+
+
+
+
+
+
+ 0 0 7.5 0 0 0
+ 1 1 1 1
+ 0.0 0.0 0.0 0
+
+ 50
+ 0
+ 0
+ 0.02
+
+ true
+ false
+ 1.0
+
+
+
+
+ 0 5 4 0 0 0
+ true
+
+
+
+
+ 10 1 10
+
+
+
+
+
+
+ 10 1 10
+
+
+
+ 1 0 0 1
+ 1 0 0 1
+ 1 0 0 1
+
+
+
+
+
+
+ 0 -5 4 0 0 0
+ true
+
+
+
+
+ 10 1 10
+
+
+
+
+
+
+ 10 1 10
+
+
+
+ 0 1 0 1
+ 0 1 0 1
+ 0 1 0 1
+
+
+
+
+
+
+ 0 0 -0.5 0 0 0
+ true
+
+
+
+
+ 10 10 1
+
+
+
+
+
+
+ 10 10 1
+
+
+
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+
+
+
+
+
+
+ 0 0 8.5 0 0 0
+ true
+
+
+
+
+ 10 10 1
+
+
+
+
+
+
+ 10 10 1
+
+
+
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+
+
+
+
+
+
+ 4.5 0 4 0 0 0
+ true
+
+
+
+
+ 1 10 10
+
+
+
+
+
+
+ 1 10 10
+
+
+
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+
+
+
+
+
+
+
+ -1.5 0 0 0 0 0
+
+
+
+
+ https://fuel.gazebosim.org/1.0/openrobotics/models/pump/1/files/meshes/pump.dae
+ 3 3 3
+
+
+
+
+
+
+
+ https://fuel.gazebosim.org/1.0/openrobotics/models/pump/1/files/meshes/pump.dae
+ 3 3 3
+
+
+
+ 1.0 1.0 1.0
+ 1.0 1.0 1.0
+
+
+ https://fuel.gazebosim.org/1.0/openrobotics/models/pump/1/files/materials/textures/pump_albedo.png
+ https://fuel.gazebosim.org/1.0/openrobotics/models/pump/1/files/materials/textures/pump_roughness.png
+ https://fuel.gazebosim.org/1.0/openrobotics/models/pump/1/files/materials/textures/pump_metallic.png
+ https://fuel.gazebosim.org/1.0/openrobotics/models/pump/1/files/materials/textures/pump_normal.png
+
+
+
+
+
+
+
+
+
+ -15 0 4 0 0.0 0
+ true
+
+ 0.05 0.05 0.05 0 0 0
+
+
+
+ 0.1 0.1 0.1
+
+
+
+
+
+
+ 0.1 0.1 0.1
+
+
+
+
+
+ 1.047
+
+ 2560
+ 1920
+
+
+ 0.1
+ 100
+
+
+ 1
+ 30
+ true
+ camera
+
+
+
+
+
diff --git a/src/systems/sensors/Sensors.cc b/src/systems/sensors/Sensors.cc
index 601a4b3c9d..defd28c3cf 100644
--- a/src/systems/sensors/Sensors.cc
+++ b/src/systems/sensors/Sensors.cc
@@ -64,11 +64,71 @@
#include "gz/sim/rendering/Events.hh"
#include "gz/sim/rendering/RenderUtil.hh"
+#include "gz/rendering/GlobalIlluminationVct.hh"
using namespace gz;
using namespace sim;
using namespace systems;
+/// \brief GI parameters holding default data
+struct GiDefaultData
+{
+ /// \brief See rendering::GlobalIlluminationVct::SetResolution
+ math::Vector3d resolution{16, 16, 16};
+
+ /// \brief See rendering::GlobalIlluminationVct::SetOctantCount
+ math::Vector3d octantCount{1, 1, 1};
+
+ /// \brief See rendering::GlobalIlluminationVct::SetBounceCount
+ uint32_t bounceCount = 6;
+
+ /// \brief See rendering::GlobalIlluminationVct::SetHighQuality
+ bool highQuality = true;
+
+ /// \brief See rendering::GlobalIlluminationVct::SetAnisotropic
+ bool anisotropic = true;
+
+ /// \brief See rendering::GlobalIlluminationVct::SetThinWallCounter
+ float thinWallCounter = 1.0f;
+
+ /// \brief See rendering::GlobalIlluminationVct::SetConserveMemory
+ bool conserveMemory = false;
+
+ /// \brief See rendering::GlobalIlluminationVct::DebugVisualizationMode
+ uint32_t debugVisMode = rendering::GlobalIlluminationVct::DVM_None;
+};
+
+/// \brief GI VCT flag and parameters
+struct GiVctParameters
+{
+ /// \brief VCT enabled flag
+ bool enabled = false;
+
+ /// \brief See rendering::GlobalIlluminationVct::SetResolution
+ uint32_t resolution[3];
+
+ /// \brief See rendering::GlobalIlluminationVct::SetOctantCount
+ uint32_t octantCount[3];
+
+ /// \brief See rendering::GlobalIlluminationVct::SetBounceCount
+ uint32_t bounceCount;
+
+ /// \brief See rendering::GlobalIlluminationVct::SetHighQuality
+ bool highQuality;
+
+ /// \brief See rendering::GlobalIlluminationVct::SetAnisotropic
+ bool anisotropic;
+
+ /// \brief See rendering::GlobalIlluminationVct::SetThinWallCounter
+ float thinWallCounter;
+
+ /// \brief See rendering::GlobalIlluminationVct::SetConserveMemory
+ bool conserveMemory;
+
+ /// \brief See rendering::GlobalIlluminationVct::DebugVisualizationMode
+ uint32_t debugVisMode;
+};
+
// Private data class.
class gz::sim::systems::SensorsPrivate
{
@@ -89,6 +149,18 @@ class gz::sim::systems::SensorsPrivate
/// generate sensor data
public: rendering::ScenePtr scene;
+ /// \brief Pointer to GlobalIlluminationVct
+ public: rendering::GlobalIlluminationVctPtr giVct;
+
+ /// \brief GI VCT parameters passed to giVct
+ public: GiVctParameters giVctParameters;
+
+ /// \brief Default GI data
+ public: GiDefaultData giDefaultData;
+
+ /// \brief GI built flag
+ public: bool giBuilt = false;
+
/// \brief Temperature used by thermal camera. Defaults to temperature at
/// sea level
public: double ambientTemperature = 288.15;
@@ -288,6 +360,28 @@ void SensorsPrivate::WaitForInit()
#endif
this->scene = this->renderUtil.Scene();
this->scene->SetCameraPassCountPerGpuFlush(6u);
+
+ if (this->giVctParameters.enabled)
+ {
+ this->giVct = this->scene->CreateGlobalIlluminationVct();
+ this->giVct->SetParticipatingVisuals(
+ rendering::GlobalIlluminationBase::DYNAMIC_VISUALS |
+ rendering::GlobalIlluminationBase::STATIC_VISUALS);
+
+ this->giVct->SetResolution(this->giVctParameters.resolution);
+ this->giVct->SetOctantCount(this->giVctParameters.octantCount);
+ this->giVct->SetBounceCount(this->giVctParameters.bounceCount);
+ this->giVct->SetAnisotropic(this->giVctParameters.anisotropic);
+ this->giVct->SetHighQuality(this->giVctParameters.highQuality);
+ this->giVct->SetConserveMemory(this->giVctParameters.conserveMemory);
+ this->giVct->SetThinWallCounter(this->giVctParameters.thinWallCounter);
+
+ this->giVct->SetDebugVisualization(
+ rendering::GlobalIlluminationVct::DVM_None);
+
+ this->scene->SetActiveGlobalIllumination(this->giVct);
+ }
+
this->initialized = true;
}
@@ -359,6 +453,19 @@ void SensorsPrivate::RunOnce()
// We only need to do this once per frame It is important to call
// sensors::RenderingSensor::SetManualSceneUpdate and set it to true
// so we don't waste cycles doing one scene graph update per sensor
+
+ if (!this->giBuilt)
+ {
+ if (this->giVctParameters.enabled)
+ {
+ this->giVct->Build();
+ this->giVct->SetDebugVisualization(static_cast<
+ rendering::GlobalIlluminationVct::DebugVisualizationMode>
+ (this->giVctParameters.debugVisMode));
+ this->giBuilt = true;
+ }
+ }
+
this->scene->PreRender();
}
@@ -438,6 +545,7 @@ void SensorsPrivate::RenderThread()
for (const auto id : this->sensorIds)
this->sensorManager.Remove(id);
+ this->giVct.reset();
this->scene.reset();
this->renderUtil.Destroy();
gzdbg << "SensorsPrivate::RenderThread stopped" << std::endl;
@@ -521,6 +629,65 @@ Sensors::~Sensors()
this->dataPtr->Stop();
}
+/// \brief Helper to convert math::Vector3d to uint32_t array
+/// \param[in] _valueToSet Array values to set
+/// \param[in] _vecValues Vector values to convert
+static void convertVector3dToUInt32Array(uint32_t _valueToSet[3],
+ const math::Vector3d &_vecValues)
+{
+ _valueToSet[0] = static_cast(_vecValues[0]);
+ _valueToSet[1] = static_cast(_vecValues[1]);
+ _valueToSet[2] = static_cast(_vecValues[2]);
+}
+
+/// \brief Helper to parse math::Vector3d as uint32_t array
+/// \param[in] _parentElem Parent element to look through
+/// \param[in] _childName Child element name to look for
+/// \param[in] _valueToSet Array values to set
+/// \param[in] _defaultValue Default vector values to use
+static void parseVector3dAsUInt32Array(sdf::ElementConstPtr _parentElem,
+ const char *_childName, uint32_t _valueToSet[3],
+ const math::Vector3d &_defaultValue)
+{
+ math::Vector3d parsedValues = (_parentElem == nullptr) ? _defaultValue :
+ _parentElem->Get(_childName, _defaultValue).first;
+
+ convertVector3dToUInt32Array(_valueToSet, parsedValues);
+}
+
+/// \brief Helper to set debug visualization mode (DVM)
+/// \param[in] _text String text to parse
+/// \param[in] _modeToSet DVM to set
+/// \param[in] _defaultMode Default DVM to use
+static void SetDebugVisMode(const std::string &_text,
+ uint32_t &_modeToSet, uint32_t _defaultMode)
+{
+ if (_text == "albedo")
+ {
+ _modeToSet = rendering::GlobalIlluminationVct::DVM_Albedo;
+ }
+ else if (_text == "normal")
+ {
+ _modeToSet = rendering::GlobalIlluminationVct::DVM_Normal;
+ }
+ else if (_text == "emissive")
+ {
+ _modeToSet = rendering::GlobalIlluminationVct::DVM_Emissive;
+ }
+ else if (_text == "lighting")
+ {
+ _modeToSet = rendering::GlobalIlluminationVct::DVM_Lighting;
+ }
+ else if (_text == "none")
+ {
+ _modeToSet = rendering::GlobalIlluminationVct::DVM_None;
+ }
+ else
+ {
+ _modeToSet = _defaultMode;
+ }
+}
+
//////////////////////////////////////////////////
void Sensors::Configure(const Entity &/*_id*/,
const std::shared_ptr &_sdf,
@@ -549,6 +716,89 @@ void Sensors::Configure(const Entity &/*_id*/,
if (_sdf->HasElement("ambient_light"))
this->dataPtr->ambientLight = _sdf->Get("ambient_light");
+ // Get the global illumination technique and its parameters, if specified
+ if (_sdf->HasElement("global_illumination"))
+ {
+ if (engineName != "ogre2")
+ {
+ gzerr << "Global illumination is only supported by the ogre2 "
+ << "render engine" << std::endl;
+ }
+ else
+ {
+ auto giElem = _sdf->FindElement("global_illumination");
+ std::string giType = giElem->GetAttribute("type")->GetAsString();
+ if (giType == "vct")
+ {
+ this->dataPtr->giVctParameters.enabled = giElem->Get(
+ "enabled", this->dataPtr->giVctParameters.enabled).first;
+
+ // Use helper functions to parse the inputted set of values
+ // as a uint32_t array
+ if (giElem->HasElement("resolution"))
+ {
+ parseVector3dAsUInt32Array(giElem, "resolution",
+ this->dataPtr->giVctParameters.resolution,
+ this->dataPtr->giDefaultData.resolution);
+ }
+ else
+ {
+ convertVector3dToUInt32Array(
+ this->dataPtr->giVctParameters.resolution,
+ this->dataPtr->giDefaultData.resolution);
+ }
+
+ if (giElem->HasElement("octant_count"))
+ {
+ parseVector3dAsUInt32Array(giElem, "octant_count",
+ this->dataPtr->giVctParameters.octantCount,
+ this->dataPtr->giDefaultData.octantCount);
+ }
+ else
+ {
+ convertVector3dToUInt32Array(
+ this->dataPtr->giVctParameters.octantCount,
+ this->dataPtr->giDefaultData.octantCount);
+ }
+
+ this->dataPtr->giVctParameters.bounceCount =
+ giElem->Get("bounce_count",
+ this->dataPtr->giVctParameters.bounceCount).first;
+ this->dataPtr->giVctParameters.highQuality =
+ giElem->Get("high_quality",
+ this->dataPtr->giVctParameters.highQuality).first;
+ this->dataPtr->giVctParameters.anisotropic =
+ giElem->Get("anisotropic",
+ this->dataPtr->giVctParameters.anisotropic).first;
+ this->dataPtr->giVctParameters.thinWallCounter =
+ giElem->Get("thin_wall_counter",
+ this->dataPtr->giVctParameters.thinWallCounter).first;
+ this->dataPtr->giVctParameters.conserveMemory =
+ giElem->Get("conserve_memory",
+ this->dataPtr->giVctParameters.conserveMemory).first;
+
+ if (giElem->HasElement("debug_vis_mode"))
+ {
+ const std::string text = giElem->Get(
+ "debug_vis_mode", "none").first;
+ SetDebugVisMode(text, this->dataPtr->giVctParameters.debugVisMode,
+ this->dataPtr->giDefaultData.debugVisMode);
+ }
+ }
+ else if (giType == "civct")
+ {
+ // todo: add CIVCT here. should also check if apiBackend is vulkan
+ // can use SetDebugVisMode when parsing DVM
+ gzerr << "GI CI VCT is not supported" << std::endl;
+ }
+ else
+ {
+ gzerr << "GI method type [" << giType << "] is not supported."
+ << std::endl;
+ }
+ }
+ }
+
this->dataPtr->renderUtil.SetEngineName(engineName);
#ifdef __APPLE__
if (apiBackend.empty())
diff --git a/test/integration/CMakeLists.txt b/test/integration/CMakeLists.txt
index da422d2a89..fe614d8666 100644
--- a/test/integration/CMakeLists.txt
+++ b/test/integration/CMakeLists.txt
@@ -108,6 +108,7 @@ set(tests_needing_display
dvl_system.cc
dvl_system_bottom_tracking.cc
dvl_system_water_mass_tracking.cc
+ camera_sensor_global_illumination.cc
gpu_lidar.cc
markers.cc
mesh_uri.cc
diff --git a/test/integration/camera_sensor_global_illumination.cc b/test/integration/camera_sensor_global_illumination.cc
new file mode 100644
index 0000000000..5a7e94677e
--- /dev/null
+++ b/test/integration/camera_sensor_global_illumination.cc
@@ -0,0 +1,170 @@
+/*
+ * Copyright (C) 2024 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
+
+#include
+
+#include
+
+#include
+#include
+
+#include "gz/sim/Server.hh"
+#include "gz/sim/SystemLoader.hh"
+#include "gz/sim/Util.hh"
+#include "test_config.hh"
+
+#include "../helpers/EnvTestFixture.hh"
+
+using namespace gz;
+using namespace std::chrono_literals;
+
+std::mutex mutex;
+int cbValue = 0;
+int giEnabled = false;
+
+//////////////////////////////////////////////////
+/// Note: This test is almost identical to the test in
+/// camera_sensor_scene_background.cc, and the `cameraCb` could have been
+/// reused, but loading the world twice in a single processes causes errors with
+/// Ogre.
+class CameraSensorGlobalIlluminationTest :
+ public InternalFixture>
+{
+};
+
+/////////////////////////////////////////////////
+void cameraCb(const msgs::Image & _msg)
+{
+ ASSERT_EQ(msgs::PixelFormatType::RGB_INT8,
+ _msg.pixel_format_type());
+
+ for (unsigned int y = 0; y < _msg.height(); ++y)
+ {
+ for (unsigned int x = 0; x < _msg.width(); ++x)
+ {
+ unsigned char r = _msg.data()[y * _msg.step() + x*3];
+ unsigned char g = _msg.data()[y * _msg.step() + x*3+1];
+ unsigned char b = _msg.data()[y * _msg.step() + x*3+2];
+
+ if (!giEnabled)
+ {
+ ASSERT_LT(static_cast(r), 2);
+ ASSERT_LT(static_cast(g), 2);
+ ASSERT_LT(static_cast(b), 2);
+ }
+ else
+ {
+ ASSERT_GT(static_cast(r), 50);
+ ASSERT_LT(static_cast(g), 25);
+ ASSERT_LT(static_cast(g), 25);
+ }
+ }
+ }
+ std::lock_guard lock(mutex);
+ if (!giEnabled)
+ cbValue = 1;
+ else
+ cbValue = 2;
+}
+
+/////////////////////////////////////////////////
+// Check that sensor reads a very dark value when GI is not enabled
+TEST_F(CameraSensorGlobalIlluminationTest,
+ GlobalIlluminationNotEnabled)
+{
+ const auto sdfFile = common::joinPaths(std::string(PROJECT_SOURCE_PATH),
+ "test", "worlds", "camera_sensor_gi_enabled_false.sdf");
+ // Start server
+ sim::ServerConfig serverConfig;
+ serverConfig.SetSdfFile(sdfFile);
+
+ sim::Server server(serverConfig);
+ EXPECT_FALSE(server.Running());
+ EXPECT_FALSE(*server.Running(0));
+
+ // subscribe to the camera topic
+ transport::Node node;
+ cbValue = 0;
+ giEnabled = false;
+ node.Subscribe("/camera", &cameraCb);
+
+ // Run server and verify that we are receiving a message
+ // from the depth camera
+ server.Run(true, 100, false);
+
+ int i = 0;
+ while (i < 100 && cbValue == 0)
+ {
+ std::this_thread::sleep_for(std::chrono::milliseconds(100));
+ i++;
+ }
+
+ std::lock_guard lock(mutex);
+ EXPECT_EQ(cbValue, 1);
+}
+
+/////////////////////////////////////////////////
+// Check that sensor reads less dark value when GI is enabled
+TEST_F(CameraSensorGlobalIlluminationTest,
+ GZ_UTILS_TEST_DISABLED_ON_MAC(GlobalIlluminationEnabled))
+{
+ // \todo(anyone) test fails on github action but pass on other
+ // ubuntu jenkins CI. Need to investigate further.
+ // Github action sets the MESA_GL_VERSION_OVERRIDE variable
+ // so check for this variable and disable test if it is set.
+#ifdef __linux__
+ std::string value;
+ bool result = common::env("MESA_GL_VERSION_OVERRIDE", value, true);
+ if (result && value == "3.3")
+ {
+ GTEST_SKIP() << "Test is run on machine with software rendering or mesa "
+ << "driver. Skipping test. " << std::endl;
+ }
+#endif
+
+ const auto sdfFile = common::joinPaths(std::string(PROJECT_SOURCE_PATH),
+ "test", "worlds", "camera_sensor_gi_enabled_true.sdf");
+ // Start server
+ sim::ServerConfig serverConfig;
+ serverConfig.SetSdfFile(sdfFile);
+
+ sim::Server server(serverConfig);
+ EXPECT_FALSE(server.Running());
+ EXPECT_FALSE(*server.Running(0));
+
+ // subscribe to the camera topic
+ transport::Node node;
+ cbValue = 0;
+ giEnabled = true;
+ node.Subscribe("/camera", &cameraCb);
+
+ // Run server and verify that we are receiving a message
+ // from the depth camera
+ server.Run(true, 100, false);
+
+ int i = 0;
+ while (i < 100 && cbValue == 0)
+ {
+ std::this_thread::sleep_for(std::chrono::milliseconds(100));
+ i++;
+ }
+
+ std::lock_guard lock(mutex);
+ EXPECT_EQ(cbValue, 2);
+}
diff --git a/test/worlds/camera_sensor_gi_enabled_false.sdf b/test/worlds/camera_sensor_gi_enabled_false.sdf
new file mode 100644
index 0000000000..b8700cf1f9
--- /dev/null
+++ b/test/worlds/camera_sensor_gi_enabled_false.sdf
@@ -0,0 +1,251 @@
+
+
+
+
+
+
+ ogre2
+
+
+ false
+ 16 16 16
+ 1 1 1
+ 6
+ true
+ true
+ 1.0
+ true
+ none
+
+
+
+
+
+
+ 0 0 0
+ 0.1 0.1 0.1
+
+
+
+
+ 0 -0.5 2.5 0 0 0
+ 1 1 1 1
+ 0 0 0 0
+
+ 50
+ 0
+ 0
+ 0.02
+
+ true
+ true
+ 1.0
+
+
+
+
+ 0 5 4 0 0 0
+ true
+
+
+
+
+ 10 1 10
+
+
+
+
+
+
+ 10 1 10
+
+
+
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+
+
+
+
+
+
+ 0 -5 4 0 0 0
+ true
+
+
+
+
+ 10 1 10
+
+
+
+
+
+
+ 10 1 10
+
+
+
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+
+
+
+
+
+
+ 0 0 -0.5 0 0 0
+ true
+
+
+
+
+ 10 10 1
+
+
+
+
+
+
+ 10 10 1
+
+
+
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+
+
+
+
+
+
+ 0 0 8.5 0 0 0
+ true
+
+
+
+
+ 10 10 1
+
+
+
+
+
+
+ 10 10 1
+
+
+
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+
+
+
+
+
+
+ 4.5 0 4 0 0 0
+ true
+
+
+
+
+ 1 10 10
+
+
+
+
+
+
+ 1 10 10
+
+
+
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+
+
+
+
+
+
+
+ 0 -0.5 0.5 0 0 0
+
+
+
+
+ 1 1 1
+
+
+
+
+
+
+
+ 1 1 1
+
+
+
+ 1 0 0 1
+ 1 0 0 1
+ 1 1 1 1
+
+
+
+
+
+
+
+ true
+ 0 0.5 0.5 0 0 -1.57
+
+
+
+
+ 0.1 0.1 0.1
+
+
+
+
+
+
+ 0.1 0.1 0.1
+
+
+
+ 0 0 1 1
+ 0 0 1 1
+ 1 1 1 1
+
+
+
+
+ 1.047
+
+ 320
+ 240
+
+
+ 0.1
+ 100
+
+
+ 30
+ camera
+
+
+
+
+
diff --git a/test/worlds/camera_sensor_gi_enabled_true.sdf b/test/worlds/camera_sensor_gi_enabled_true.sdf
new file mode 100644
index 0000000000..067466da8f
--- /dev/null
+++ b/test/worlds/camera_sensor_gi_enabled_true.sdf
@@ -0,0 +1,251 @@
+
+
+
+
+
+
+ ogre2
+
+
+ true
+ 16 16 16
+ 1 1 1
+ 6
+ true
+ true
+ 1.0
+ true
+ none
+
+
+
+
+
+
+ 0 0 0
+ 0.1 0.1 0.1
+
+
+
+
+ 0 -0.5 2.5 0 0 0
+ 1 1 1 1
+ 0 0 0 0
+
+ 50
+ 0
+ 0
+ 0.02
+
+ true
+ true
+ 1.0
+
+
+
+
+ 0 5 4 0 0 0
+ true
+
+
+
+
+ 10 1 10
+
+
+
+
+
+
+ 10 1 10
+
+
+
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+
+
+
+
+
+
+ 0 -5 4 0 0 0
+ true
+
+
+
+
+ 10 1 10
+
+
+
+
+
+
+ 10 1 10
+
+
+
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+
+
+
+
+
+
+ 0 0 -0.5 0 0 0
+ true
+
+
+
+
+ 10 10 1
+
+
+
+
+
+
+ 10 10 1
+
+
+
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+
+
+
+
+
+
+ 0 0 8.5 0 0 0
+ true
+
+
+
+
+ 10 10 1
+
+
+
+
+
+
+ 10 10 1
+
+
+
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+
+
+
+
+
+
+ 4.5 0 4 0 0 0
+ true
+
+
+
+
+ 1 10 10
+
+
+
+
+
+
+ 1 10 10
+
+
+
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+
+
+
+
+
+
+
+ 0 -0.5 0.5 0 0 0
+
+
+
+
+ 1 1 1
+
+
+
+
+
+
+
+ 1 1 1
+
+
+
+ 1 0 0 1
+ 1 0 0 1
+ 1 1 1 1
+
+
+
+
+
+
+
+ true
+ 0 0.5 0.5 0 0 -1.57
+
+
+
+
+ 0.1 0.1 0.1
+
+
+
+
+
+
+ 0.1 0.1 0.1
+
+
+
+ 0 0 1 1
+ 0 0 1 1
+ 1 1 1 1
+
+
+
+
+ 1.047
+
+ 320
+ 240
+
+
+ 0.1
+ 100
+
+
+ 30
+ camera
+
+
+
+
+
diff --git a/tutorials.md.in b/tutorials.md.in
index b75967e1ad..b3d734544e 100644
--- a/tutorials.md.in
+++ b/tutorials.md.in
@@ -24,6 +24,7 @@ Gazebo @GZ_DESIGNATION_CAP@ library and how to use the library effectively.
* \subpage headless_rendering "Headless rendering": Access the GPU on a remote machine to produce sensor data without an X server.
* \subpage apply_force_torque "Apply Force and Torque": Applying forces and/or torques to models during simulation through the GUI.
* \subpage mouse_drag "Mouse Drag": Move models by dragging them in the scene using forces and torques.
+* \subpage global_illumination "Global illumination": Enable global illumination for the GUI and for the sensor view.
### Migration from Gazebo classic
diff --git a/tutorials/files/global_illumination/global_illumination.gif b/tutorials/files/global_illumination/global_illumination.gif
new file mode 100644
index 0000000000..fbc1435e28
Binary files /dev/null and b/tutorials/files/global_illumination/global_illumination.gif differ
diff --git a/tutorials/files/global_illumination/gui_demo_default.png b/tutorials/files/global_illumination/gui_demo_default.png
new file mode 100644
index 0000000000..516d32dea6
Binary files /dev/null and b/tutorials/files/global_illumination/gui_demo_default.png differ
diff --git a/tutorials/files/global_illumination/gui_demo_with_vct.png b/tutorials/files/global_illumination/gui_demo_with_vct.png
new file mode 100644
index 0000000000..823d23b3dc
Binary files /dev/null and b/tutorials/files/global_illumination/gui_demo_with_vct.png differ
diff --git a/tutorials/global_illumination.md b/tutorials/global_illumination.md
new file mode 100644
index 0000000000..13ff5bc3a7
--- /dev/null
+++ b/tutorials/global_illumination.md
@@ -0,0 +1,419 @@
+\page global_illumination Global Illumination
+
+This tutorial showcases how to enable real-time global illumination in Gazebo.
+
+
+ \image html files/global_illumination/global_illumination.gif width=60%
+
+
+## About global illumination
+
+Global illumination (GI) techniques account for illumination from indirect light reflections. When GI is enabled, objects not only receive direct light from light sources, but also from indirect light bouncing off of other surfaces, ensuring nice reflections and a more natural appearance.
+
+Gazebo supports two GI methods through the Ogre2 rendering engine, Voxel Cone Tracing (VCT) and Cascaded Image Voxel Cone Tracing (CI VCT).
+
+### Voxel Cone Tracing
+
+A scene rendered with VCT is reliable and good quality, and thus is the best choice for most scenes.
+
+VCT parameters include:
+* **Resolution**
+* **Octant count**
+* **Bounce count**
+* **High quality**
+* **Anisotropic**
+* **Thin wall counter**
+* **Conserve memory**
+* **Debug visualization mode**
+
+### Cascaded Image Voxel Cone Tracing
+
+Compared to VCT, a scene rendered with CI VCT is slightly lower quality, but the scene can be re-voxelized every frame, so it’s much faster when dealing with very large scenes. However, it is more memory-intensive than VCT.
+
+CI VCT parameters include:
+* **Bounce count**
+* **High quality**
+* **Anisotropic**
+* **Debug visualization mode**
+* **Cascade**
+ * **Resolution**
+ * **Octant count**
+ * **Thin wall counter**
+ * **Area half size**
+
+## Enabling global illumination in Gazebo
+
+During simulation, the GUI and the camera sensor view are two different scenes. The GUI scene is rendered on the frontend client process, and the camera sensor scene is rendered on the backend server process. Thus, GI can be enabled on either or both of these processes.
+
+> **Note:** GI solutions require hardware that uses OpenGL4.
+> **Note:** CI VCT must be run with Vulkan as the render engine API backend.
+
+### How to enable global illumination for the GUI
+
+GI can be enabled for the GUI through a GUI plugin. Both VCT and CI VCT are supported for the GUI.
+
+#### Example usage for VCT
+
+1) Open the [global_illumination.sdf](
+https://github.com/gazebosim/gz-sim/tree/gz-sim8/examples/worlds/global_illumination.sdf) world with
+
+```bash
+gz sim global_illumination.sdf
+```
+
+ \image html files/global_illumination/gui_demo_default.png width=60%
+
+
+
+2) From the plugin dropdown, select the Global Illumination Vct plugin.
+
+3) On the card, check the `Enabled` button to enable GI and change the parameter values as desired.
+
+
+ \image html files/global_illumination/gui_demo_with_vct.png width=60%
+