Skip to content

Commit

Permalink
Use custom simulation time variants for Ogre (#584)
Browse files Browse the repository at this point in the history
* Use custom simulation time variants for Ogre

This fixes Particle FXs not respecting simulation time
Fixes #556

Signed-off-by: Matias N. Goldberg <[email protected]>
  • Loading branch information
darksylinc authored Apr 4, 2022
1 parent 195317e commit 3b0426e
Show file tree
Hide file tree
Showing 8 changed files with 198 additions and 5 deletions.
6 changes: 6 additions & 0 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,12 @@ release will remove the deprecated code.
1. **depth_camera_fs.glsl** and **depth_camera_final_fs.glsl**
+ Far clipping changed from clipping by depth to clipping by range, i.e. distance to point, so that the data generated will never exceed the specified max range of the camera.
1. `Scene::SetTime` is often unset. Ignition's `Ogre2` now defaults to 60hz otherwise rendering won't advance forward.
+ Mostly affects Particles.
+ Also may affect gaussian postprocessing and other filters dependant on time.
+ Previous behavior was using real time instead of simulation time, which is wrong.
+ See https://github.com/ignitionrobotics/ign-rendering/issues/556 for details.
## Ignition Rendering 4.0 to 4.1
## ABI break
Expand Down
4 changes: 4 additions & 0 deletions ogre2/include/ignition/rendering/ogre2/Ogre2Scene.hh
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,10 @@ namespace ignition
// Documentation inherited.
public: virtual VisualPtr RootVisual() const override;

// Documentation inherited.
public: virtual void SetTime(
const std::chrono::steady_clock::duration &_time) override;

// Documentation inherited.
public: virtual math::Color AmbientLight() const override;

Expand Down
107 changes: 103 additions & 4 deletions ogre2/src/Ogre2Scene.cc
Original file line number Diff line number Diff line change
Expand Up @@ -86,6 +86,29 @@ class ignition::rendering::Ogre2ScenePrivate
/// is incorrect
public: bool frameUpdateStarted = false;

#if IGNITION_RENDERING_MAJOR_VERSION <= 6
/// \brief HACK: SetTime was not doing anything; but it is needed for
/// particle FXs to simulate forward.
///
/// To avoid breaking apps that were already calling SetTime() or
/// were never calling it, apps that call SetTime( -1 ) will tell
/// ign-rendering6 to start honouring simulation time.
///
/// Otherwise the old behavior is used; which uses real time for particle
/// FXs instead of simulation time.
///
/// See https://github.com/ignitionrobotics/ign-rendering/issues/556
/// See https://github.com/ignitionrobotics/ign-rendering/pull/584
///
/// TODO(anyone): Remove any code using hackIgnoringSimTime for
/// ign-rendering7 as we can safely default to simulation time
/// without worrying about breaking existing apps.
public: bool hackIgnoringSimTime = true;
#endif

/// \brief Total time elapsed in simulation since last rendering frame
public: std::chrono::steady_clock::duration lastRenderSimTime{0};

/// \brief Keeps track how many passes we've done so far and
/// compares it to cameraPassCountPerGpuFlush
public: uint32_t currNumCameraPasses = 0u;
Expand Down Expand Up @@ -128,6 +151,23 @@ VisualPtr Ogre2Scene::RootVisual() const
return this->rootVisual;
}

//////////////////////////////////////////////////
void Ogre2Scene::SetTime(const std::chrono::steady_clock::duration &_time)
{
#if IGNITION_RENDERING_MAJOR_VERSION <= 6
if (std::chrono::duration_cast<std::chrono::nanoseconds>(_time).count() == -1)
{
this->dataPtr->hackIgnoringSimTime = false;
}
else // NOLINT
#endif
{
this->time = _time;
if (_time < this->dataPtr->lastRenderSimTime)
this->dataPtr->lastRenderSimTime = _time;
}
}

//////////////////////////////////////////////////
math::Color Ogre2Scene::AmbientLight() const
{
Expand Down Expand Up @@ -190,7 +230,26 @@ void Ogre2Scene::PreRender()
if (!this->LegacyAutoGpuFlush())
{
auto engine = Ogre2RenderEngine::Instance();
engine->OgreRoot()->_fireFrameStarted();
const auto currTime = this->Time();
Ogre::FrameEvent evt;
evt.timeSinceLastEvent = 0; // Not used by Ogre so we don't care
evt.timeSinceLastFrame = static_cast<Ogre::Real>(
static_cast<double>(std::chrono::duration_cast<std::chrono::nanoseconds>(
currTime - this->dataPtr->lastRenderSimTime)
.count()) /
1000000000.0);
#if IGNITION_RENDERING_MAJOR_VERSION <= 6
if (!this->dataPtr->hackIgnoringSimTime)
{
engine->OgreRoot()->_fireFrameStarted(evt);
}
else
{
engine->OgreRoot()->_fireFrameStarted();
}
#else
engine->OgreRoot()->_fireFrameStarted(evt);
#endif

this->ogreSceneManager->updateSceneGraph();
}
Expand Down Expand Up @@ -269,7 +328,27 @@ void Ogre2Scene::StartRendering(Ogre::Camera *_camera)
if (this->LegacyAutoGpuFlush())
{
auto engine = Ogre2RenderEngine::Instance();
engine->OgreRoot()->_fireFrameStarted();

const auto currTime = this->Time();
Ogre::FrameEvent evt;
evt.timeSinceLastEvent = 0; // Not used by Ogre so we don't care
evt.timeSinceLastFrame = static_cast<Ogre::Real>(
static_cast<double>(std::chrono::duration_cast<std::chrono::nanoseconds>(
currTime - this->dataPtr->lastRenderSimTime)
.count()) /
1000000000.0);
#if IGNITION_RENDERING_MAJOR_VERSION <= 6
if (!this->dataPtr->hackIgnoringSimTime)
{
engine->OgreRoot()->_fireFrameStarted(evt);
}
else
{
engine->OgreRoot()->_fireFrameStarted();
}
#else
engine->OgreRoot()->_fireFrameStarted(evt);
#endif

this->ogreSceneManager->updateSceneGraph();
}
Expand Down Expand Up @@ -332,7 +411,27 @@ void Ogre2Scene::EndFrame()
auto engine = Ogre2RenderEngine::Instance();
auto ogreRoot = engine->OgreRoot();

ogreRoot->_fireFrameRenderingQueued();
const auto currTime = this->Time();
Ogre::FrameEvent evt;
evt.timeSinceLastEvent = 0; // Not used by Ogre so we don't care
evt.timeSinceLastFrame = static_cast<Ogre::Real>(
static_cast<double>(std::chrono::duration_cast<std::chrono::nanoseconds>(
currTime - this->dataPtr->lastRenderSimTime)
.count()) /
1000000000.0);
#if IGNITION_RENDERING_MAJOR_VERSION <= 6
if (!this->dataPtr->hackIgnoringSimTime)
{
ogreRoot->_fireFrameRenderingQueued(evt);
}
else
{
ogreRoot->_fireFrameRenderingQueued();
}
#else
ogreRoot->_fireFrameRenderingQueued(evt);
#endif
this->dataPtr->lastRenderSimTime = currTime;

auto itor = ogreRoot->getSceneManagerIterator();
while (itor.hasMoreElements())
Expand All @@ -341,7 +440,7 @@ void Ogre2Scene::EndFrame()
sceneManager->clearFrameData();
}

ogreRoot->_fireFrameEnded();
ogreRoot->_fireFrameEnded(evt);
}

//////////////////////////////////////////////////
Expand Down
9 changes: 9 additions & 0 deletions src/Scene_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -675,6 +675,15 @@ void SceneTest::Time(const std::string &_renderEngine)
std::chrono::steady_clock::duration duration =
std::chrono::steady_clock::duration::zero();

#if IGNITION_RENDERING_MAJOR_VERSION <= 6
// -1 is a hack and is the only value supposed to
// be ignored by ign-rendering6.
//
// We must call it and EXPECT_EQ(duration, scene->Time());
// should still be pass in ign-rendering6.
scene->SetTime(std::chrono::nanoseconds(-1));
#endif

EXPECT_EQ(duration, scene->Time());

duration = std::chrono::seconds(23);
Expand Down
8 changes: 7 additions & 1 deletion src/base/BaseScene.cc
Original file line number Diff line number Diff line change
Expand Up @@ -141,7 +141,13 @@ std::chrono::steady_clock::duration BaseScene::Time() const
//////////////////////////////////////////////////
void BaseScene::SetTime(const std::chrono::steady_clock::duration &_time)
{
this->time = _time;
#if IGNITION_RENDERING_MAJOR_VERSION <= 6
// TODO(anyone): Remove me in ign-rendering7
if (std::chrono::duration_cast<std::chrono::nanoseconds>(_time).count() != -1)
#endif
{
this->time = _time;
}
}

//////////////////////////////////////////////////
Expand Down
18 changes: 18 additions & 0 deletions test/integration/camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -79,6 +79,11 @@ void CameraTest::Track(const std::string &_renderEngine)
ScenePtr scene = engine->CreateScene("scene");
ASSERT_TRUE(scene != nullptr);

#if IGNITION_RENDERING_MAJOR_VERSION <= 6
// HACK: Tell ign-rendering6 to listen to SetTime calls
scene->SetTime(std::chrono::nanoseconds(-1));
#endif

VisualPtr root = scene->RootVisual();

CameraPtr camera = scene->CreateCamera();
Expand Down Expand Up @@ -106,6 +111,7 @@ void CameraTest::Track(const std::string &_renderEngine)

// render a frame
camera->Update();
scene->SetTime(scene->Time() + std::chrono::milliseconds(16));

EXPECT_EQ(initPos, camera->WorldPosition());
EXPECT_NE(initRot, camera->WorldRotation());
Expand All @@ -126,6 +132,7 @@ void CameraTest::Track(const std::string &_renderEngine)

// render a frame
camera->Update();
scene->SetTime(scene->Time() + std::chrono::milliseconds(16));

// verify camera orientation when tracking target with offset
// in world frame
Expand All @@ -144,6 +151,7 @@ void CameraTest::Track(const std::string &_renderEngine)

// render a frame
camera->Update();
scene->SetTime(scene->Time() + std::chrono::milliseconds(16));
// verify camera orientation when tracking target with offset
// in local frame
// camera should be looking down and to the right
Expand All @@ -160,6 +168,7 @@ void CameraTest::Track(const std::string &_renderEngine)

// render a frame
camera->Update();
scene->SetTime(scene->Time() + std::chrono::milliseconds(16));

// reset camera pose
camera->SetWorldPosition(initPos);
Expand All @@ -175,6 +184,7 @@ void CameraTest::Track(const std::string &_renderEngine)

// render a frame
camera->Update();
scene->SetTime(scene->Time() + std::chrono::milliseconds(16));

// verify camera rotaion has pitch component
// but not as large as before without p gain
Expand Down Expand Up @@ -247,6 +257,7 @@ void CameraTest::VisualAt(const std::string &_renderEngine)
for (auto i = 0; i < 30; ++i)
{
camera->Update();
scene->SetTime(scene->Time() + std::chrono::milliseconds(16));
}

EXPECT_EQ(800u, camera->ImageWidth());
Expand Down Expand Up @@ -298,6 +309,7 @@ void CameraTest::VisualAt(const std::string &_renderEngine)
for (auto i = 0; i < 30; ++i)
{
camera->Update();
scene->SetTime(scene->Time() + std::chrono::milliseconds(16));
}

// test that VisualAt still works after resize
Expand Down Expand Up @@ -359,6 +371,7 @@ void CameraTest::Follow(const std::string &_renderEngine)

// render a frame
camera->Update();
scene->SetTime(scene->Time() + std::chrono::milliseconds(16));

// verify camera is at same location as visual because
// no offset is given
Expand All @@ -373,6 +386,7 @@ void CameraTest::Follow(const std::string &_renderEngine)

// render a frame
camera->Update();
scene->SetTime(scene->Time() + std::chrono::milliseconds(16));

// verify camera pose when following target with offset
// in world frame
Expand All @@ -389,6 +403,7 @@ void CameraTest::Follow(const std::string &_renderEngine)

// render a frame
camera->Update();
scene->SetTime(scene->Time() + std::chrono::milliseconds(16));

// verify camera pose when following target with offset
// in local frame
Expand All @@ -405,6 +420,7 @@ void CameraTest::Follow(const std::string &_renderEngine)

// render a frame
camera->Update();
scene->SetTime(scene->Time() + std::chrono::milliseconds(16));

// reset camera pose
camera->SetWorldPosition(initPos);
Expand All @@ -420,6 +436,7 @@ void CameraTest::Follow(const std::string &_renderEngine)

// render a frame
camera->Update();
scene->SetTime(scene->Time() + std::chrono::milliseconds(16));

// verify camera position has changed but
// but not as close to the target as before without p gain
Expand Down Expand Up @@ -740,6 +757,7 @@ void CameraTest::ShaderSelection(const std::string &_renderEngine)
thermalCamera->Update();
if (segmentationCamera)
segmentationCamera->Update();
scene->SetTime(scene->Time() + std::chrono::milliseconds(16));
}

// capture a frame
Expand Down
17 changes: 17 additions & 0 deletions test/integration/depth_camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -100,6 +100,11 @@ void DepthCameraTest::DepthCameraBoxes(
// red background
scene->SetBackgroundColor(1.0, 0.0, 0.0);

#if IGNITION_RENDERING_MAJOR_VERSION <= 6
// HACK: Tell ign-rendering6 to listen to SetTime calls
scene->SetTime(std::chrono::nanoseconds(-1));
#endif

// Create an scene with a box in it
scene->SetAmbientLight(1.0, 1.0, 1.0);
ignition::rendering::VisualPtr root = scene->RootVisual();
Expand Down Expand Up @@ -172,6 +177,7 @@ void DepthCameraTest::DepthCameraBoxes(
g_depthCounter = 0u;
g_pointCloudCounter = 0u;
depthCamera->Update();
scene->SetTime(scene->Time() + std::chrono::milliseconds(16));
EXPECT_EQ(1u, g_depthCounter);
EXPECT_EQ(1u, g_pointCloudCounter);

Expand Down Expand Up @@ -302,6 +308,7 @@ void DepthCameraTest::DepthCameraBoxes(
g_depthCounter = 0u;
g_pointCloudCounter = 0u;
depthCamera->Update();
scene->SetTime(scene->Time() + std::chrono::milliseconds(16));
EXPECT_EQ(1u, g_depthCounter);
EXPECT_EQ(1u, g_pointCloudCounter);

Expand Down Expand Up @@ -358,6 +365,7 @@ void DepthCameraTest::DepthCameraBoxes(
g_depthCounter = 0u;
g_pointCloudCounter = 0u;
depthCamera->Update();
scene->SetTime(scene->Time() + std::chrono::milliseconds(16));
EXPECT_EQ(1u, g_depthCounter);
EXPECT_EQ(1u, g_pointCloudCounter);

Expand Down Expand Up @@ -416,6 +424,7 @@ void DepthCameraTest::DepthCameraBoxes(
g_depthCounter = 0u;
g_pointCloudCounter = 0u;
depthCamera->Update();
scene->SetTime(scene->Time() + std::chrono::milliseconds(16));
EXPECT_EQ(1u, g_depthCounter);
EXPECT_EQ(1u, g_pointCloudCounter);

Expand Down Expand Up @@ -511,6 +520,11 @@ void DepthCameraTest::DepthCameraParticles(
// red background
scene->SetBackgroundColor(1.0, 0.0, 0.0);

#if IGNITION_RENDERING_MAJOR_VERSION <= 6
// HACK: Tell ign-rendering6 to listen to SetTime calls
scene->SetTime(std::chrono::nanoseconds(-1));
#endif

// Create an scene with a box in it
scene->SetAmbientLight(1.0, 1.0, 1.0);
ignition::rendering::VisualPtr root = scene->RootVisual();
Expand Down Expand Up @@ -583,6 +597,7 @@ void DepthCameraTest::DepthCameraParticles(
g_depthCounter = 0u;
g_pointCloudCounter = 0u;
depthCamera->Update();
scene->SetTime(scene->Time() + std::chrono::milliseconds(16));
EXPECT_EQ(1u, g_depthCounter);
EXPECT_EQ(1u, g_pointCloudCounter);

Expand Down Expand Up @@ -636,6 +651,7 @@ void DepthCameraTest::DepthCameraParticles(
for (unsigned int i = 0; i < 100; ++i)
{
depthCamera->Update();
scene->SetTime(scene->Time() + std::chrono::milliseconds(16));
}
EXPECT_EQ(100u, g_depthCounter);
EXPECT_EQ(100u, g_pointCloudCounter);
Expand Down Expand Up @@ -705,6 +721,7 @@ void DepthCameraTest::DepthCameraParticles(
for (unsigned int i = 0; i < 100; ++i)
{
depthCamera->Update();
scene->SetTime(scene->Time() + std::chrono::milliseconds(16));
}
EXPECT_EQ(100u, g_depthCounter);
EXPECT_EQ(100u, g_pointCloudCounter);
Expand Down
Loading

0 comments on commit 3b0426e

Please sign in to comment.