From 280b5d6aad8f2af751f223c7956eaa2c6cdc31c5 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Wed, 22 Feb 2023 23:32:02 +0000 Subject: [PATCH] clean up rendering resources Signed-off-by: Ian Chen --- src/RenderingSensor.cc | 2 +- test/integration/boundingbox_camera.cc | 8 ++++++++ test/integration/depth_camera.cc | 12 ++++++------ test/integration/gpu_lidar_sensor.cc | 24 +++++++++++++++++++++--- test/integration/rgbd_camera.cc | 10 ++++++---- test/integration/segmentation_camera.cc | 4 ++++ test/integration/thermal_camera.cc | 16 ++++++++-------- 7 files changed, 54 insertions(+), 22 deletions(-) diff --git a/src/RenderingSensor.cc b/src/RenderingSensor.cc index ad9cc32e..e02e1232 100644 --- a/src/RenderingSensor.cc +++ b/src/RenderingSensor.cc @@ -47,7 +47,7 @@ RenderingSensor::RenderingSensor() : ////////////////////////////////////////////////// RenderingSensor::~RenderingSensor() { - if (!this->dataPtr->scene) + if (!this->dataPtr->scene || !this->dataPtr->scene->IsInitialized()) return; for (auto &s : this->dataPtr->sensors) { diff --git a/test/integration/boundingbox_camera.cc b/test/integration/boundingbox_camera.cc index badb7610..e6108fcd 100644 --- a/test/integration/boundingbox_camera.cc +++ b/test/integration/boundingbox_camera.cc @@ -344,7 +344,11 @@ void BoundingBoxCameraSensorTest::BoxesWithBuiltinSDF( g_mutex.unlock(); + // Clean up rendering ptrs + camera.reset(); + // Clean up + mgr.Remove(sensor->Id()); engine->DestroyScene(scene); rendering::unloadEngine(engine->Name()); } @@ -465,7 +469,11 @@ void BoundingBoxCameraSensorTest::Boxes3DWithBuiltinSDF( g_mutex.unlock(); + // Clean up rendering ptrs + camera.reset(); + // Clean up + mgr.Remove(sensor->Id()); engine->DestroyScene(scene); rendering::unloadEngine(engine->Name()); } diff --git a/test/integration/depth_camera.cc b/test/integration/depth_camera.cc index ba4c6ca9..4f0c217a 100644 --- a/test/integration/depth_camera.cc +++ b/test/integration/depth_camera.cc @@ -222,6 +222,7 @@ void DepthCameraSensorTest::ImagesWithBuiltinSDF( box->SetLocalRotation(0, 0, 0); box->SetLocalScale(unitBoxSize, unitBoxSize, unitBoxSize); box->SetMaterial(blue); + scene->DestroyMaterial(blue); root->AddChild(box); // do the test @@ -336,11 +337,9 @@ void DepthCameraSensorTest::ImagesWithBuiltinSDF( EXPECT_EQ(9, infoMsg.rectification_matrix().size()); // Check that for a box really close it returns -inf - root->RemoveChild(box); gz::math::Vector3d boxPositionNear( unitBoxSize * 0.5 + near_ * 0.5, 0.0, 0.0); box->SetLocalPosition(boxPositionNear); - root->AddChild(box); mgr.RunOnce(std::chrono::steady_clock::duration::zero(), true); for (int sleep = 0; @@ -372,11 +371,9 @@ void DepthCameraSensorTest::ImagesWithBuiltinSDF( g_mutex.unlock(); // Check that for a box really far it returns inf - root->RemoveChild(box); gz::math::Vector3d boxPositionFar( unitBoxSize * 0.5 + far_ * 1.5, 0.0, 0.0); box->SetLocalPosition(boxPositionFar); - root->AddChild(box); mgr.RunOnce(std::chrono::steady_clock::duration::zero(), true); for (int sleep = 0; @@ -408,11 +405,9 @@ void DepthCameraSensorTest::ImagesWithBuiltinSDF( // Check that the depth values for a box do not warp. - root->RemoveChild(box); gz::math::Vector3d boxPositionFillFrame( unitBoxSize * 0.5 + 0.2, 0.0, 0.0); box->SetLocalPosition(boxPositionFillFrame); - root->AddChild(box); mgr.RunOnce(std::chrono::steady_clock::duration::zero(), true); for (int sleep = 0; @@ -497,7 +492,12 @@ void DepthCameraSensorTest::ImagesWithBuiltinSDF( g_mutex.unlock(); g_pcMutex.unlock(); + // clean up rendering ptrs + blue.reset(); + box.reset(); + // Clean up + mgr.Remove(depthSensor->Id()); engine->DestroyScene(scene); gz::rendering::unloadEngine(engine->Name()); } diff --git a/test/integration/gpu_lidar_sensor.cc b/test/integration/gpu_lidar_sensor.cc index 4edca6d3..570a15da 100644 --- a/test/integration/gpu_lidar_sensor.cc +++ b/test/integration/gpu_lidar_sensor.cc @@ -278,6 +278,7 @@ void GpuLidarSensorTest::CreateGpuLidar(const std::string &_renderEngine) // Clean up c.reset(); + mgr.Remove(sensor->Id()); engine->DestroyScene(scene); gz::rendering::unloadEngine(engine->Name()); } @@ -416,8 +417,11 @@ void GpuLidarSensorTest::DetectBox(const std::string &_renderEngine) EXPECT_FALSE(pointMsgs.back().is_dense()); EXPECT_EQ(32u * horzSamples * vertSamples, pointMsgs.back().data().size()); + // Clean up rendering ptrs + visualBox1.reset(); + // Clean up - // + mgr.Remove(sensor->Id()); engine->DestroyScene(scene); gz::rendering::unloadEngine(engine->Name()); } @@ -573,7 +577,14 @@ void GpuLidarSensorTest::TestThreeBoxes(const std::string &_renderEngine) for (unsigned int i = 0; i < sensor1->RayCount(); ++i) EXPECT_DOUBLE_EQ(sensor2->Range(i), gz::math::INF_D); + // Clean up rendering ptrs + visualBox1.reset(); + visualBox2.reset(); + visualBox3.reset(); + // Clean up + mgr.Remove(sensor1->Id()); + mgr.Remove(sensor2->Id()); engine->DestroyScene(scene); gz::rendering::unloadEngine(engine->Name()); } @@ -693,7 +704,11 @@ void GpuLidarSensorTest::VerticalLidar(const std::string &_renderEngine) } } + // Clean up rendering ptrs + visualBox1.reset(); + // Clean up + mgr.Remove(sensor->Id()); engine->DestroyScene(scene); gz::rendering::unloadEngine(engine->Name()); } @@ -819,8 +834,12 @@ void GpuLidarSensorTest::ManualUpdate(const std::string &_renderEngine) EXPECT_DOUBLE_EQ(sensor2->Range(last), gz::math::INF_D); #endif + // Clean up rendering ptrs + visualBox1.reset(); + // Clean up - // + mgr.Remove(sensor1->Id()); + mgr.Remove(sensor2->Id()); engine->DestroyScene(scene); gz::rendering::unloadEngine(engine->Name()); } @@ -859,7 +878,6 @@ void GpuLidarSensorTest::Topic(const std::string &_renderEngine) // Create a GpuLidarSensor gz::sensors::Manager mgr; - // Default topic { const std::string topic; diff --git a/test/integration/rgbd_camera.cc b/test/integration/rgbd_camera.cc index a0e01ef6..cd319104 100644 --- a/test/integration/rgbd_camera.cc +++ b/test/integration/rgbd_camera.cc @@ -242,6 +242,7 @@ void RgbdCameraSensorTest::ImagesWithBuiltinSDF( box->SetLocalRotation(0, 0, 0); box->SetLocalScale(unitBoxSize, unitBoxSize, unitBoxSize); box->SetMaterial(blue); + scene->DestroyMaterial(blue); root->AddChild(box); // do the test @@ -529,11 +530,9 @@ void RgbdCameraSensorTest::ImagesWithBuiltinSDF( g_imgMutex.unlock(); // Check that for a box really close it returns -inf - root->RemoveChild(box); math::Vector3d boxPositionNear( unitBoxSize * 0.5 + near_ * 0.5, 0.0, 0.0); box->SetLocalPosition(boxPositionNear); - root->AddChild(box); mgr.RunOnce(std::chrono::steady_clock::duration::zero(), true); for (int sleep = 0; sleep < 300 && @@ -635,11 +634,9 @@ void RgbdCameraSensorTest::ImagesWithBuiltinSDF( g_pcMutex.unlock(); // Check that for a box really far it returns inf - root->RemoveChild(box); math::Vector3d boxPositionFar( unitBoxSize * 0.5 + far_ * 1.5, 0.0, 0.0); box->SetLocalPosition(boxPositionFar); - root->AddChild(box); mgr.RunOnce(std::chrono::steady_clock::duration::zero(), true); for (int sleep = 0; sleep < 300 && @@ -740,7 +737,12 @@ void RgbdCameraSensorTest::ImagesWithBuiltinSDF( g_imgMutex.unlock(); g_pcMutex.unlock(); + // Clean up rendering ptrs + box.reset(); + blue.reset(); + // Clean up + mgr.Remove(rgbdSensor->Id()); engine->DestroyScene(scene); rendering::unloadEngine(engine->Name()); } diff --git a/test/integration/segmentation_camera.cc b/test/integration/segmentation_camera.cc index 41771dd1..7f5cad1d 100644 --- a/test/integration/segmentation_camera.cc +++ b/test/integration/segmentation_camera.cc @@ -352,7 +352,11 @@ void SegmentationCameraSensorTest::ImagesWithBuiltinSDF( } } + // Clean up rendering ptrs + camera.reset(); + // Clean up + mgr.Remove(sensor->Id()); engine->DestroyScene(scene); ignition::rendering::unloadEngine(engine->Name()); } diff --git a/test/integration/thermal_camera.cc b/test/integration/thermal_camera.cc index a87f26d8..18eec315 100644 --- a/test/integration/thermal_camera.cc +++ b/test/integration/thermal_camera.cc @@ -282,11 +282,9 @@ void ThermalCameraSensorTest::ImagesWithBuiltinSDF( EXPECT_EQ(9, infoMsg.rectification_matrix().size()); // Check that for a box really close it returns box temperature - root->RemoveChild(box); gz::math::Vector3d boxPositionNear( unitBoxSize * 0.5 + near_ * 0.5, 0.0, 0.0); box->SetLocalPosition(boxPositionNear); - root->AddChild(box); mgr.RunOnce(std::chrono::steady_clock::duration::zero(), true); for (int sleep = 0; @@ -316,11 +314,9 @@ void ThermalCameraSensorTest::ImagesWithBuiltinSDF( g_mutex.unlock(); // Check that for a box really far it returns ambient temperature - root->RemoveChild(box); gz::math::Vector3d boxPositionFar( unitBoxSize * 0.5 + far_ * 1.5, 0.0, 0.0); box->SetLocalPosition(boxPositionFar); - root->AddChild(box); mgr.RunOnce(std::chrono::steady_clock::duration::zero(), true); for (int sleep = 0; @@ -352,7 +348,11 @@ void ThermalCameraSensorTest::ImagesWithBuiltinSDF( delete [] g_thermalBuffer; g_thermalBuffer = nullptr; + // Clean up rendering ptrs + box.reset(); + // Clean up + mgr.Remove(thermalSensor->Id()); engine->DestroyScene(scene); gz::rendering::unloadEngine(engine->Name()); } @@ -543,11 +543,9 @@ void ThermalCameraSensorTest::Images8BitWithBuiltinSDF( EXPECT_EQ(9, infoMsg.rectification_matrix().size()); // Check that for a box really close it returns box temperature - root->RemoveChild(box); gz::math::Vector3d boxPositionNear( unitBoxSize * 0.5 + near_ * 0.5, 0.0, 0.0); box->SetLocalPosition(boxPositionNear); - root->AddChild(box); mgr.RunOnce(std::chrono::steady_clock::duration::zero(), true); for (int sleep = 0; @@ -578,11 +576,9 @@ void ThermalCameraSensorTest::Images8BitWithBuiltinSDF( g_mutex.unlock(); // Check that for a box really far it returns ambient temperature - root->RemoveChild(box); ignition::math::Vector3d boxPositionFar( unitBoxSize * 0.5 + far_ * 1.5, 0.0, 0.0); box->SetLocalPosition(boxPositionFar); - root->AddChild(box); mgr.RunOnce(std::chrono::steady_clock::duration::zero(), true); for (int sleep = 0; @@ -614,7 +610,11 @@ void ThermalCameraSensorTest::Images8BitWithBuiltinSDF( delete [] g_thermalBuffer8Bit; g_thermalBuffer8Bit = nullptr; + // Clean up rendering ptrs + box.reset(); + // Clean up + mgr.Remove(thermalSensor->Id()); engine->DestroyScene(scene); gz::rendering::unloadEngine(engine->Name()); }