Skip to content

Commit

Permalink
working on updating segmentation camera to ogre2.2
Browse files Browse the repository at this point in the history
Signed-off-by: Ashton Larkin <ashton@openrobotics.org>
  • Loading branch information
adlarkin committed Sep 16, 2021
1 parent f7b77c5 commit f81dd61
Showing 1 changed file with 77 additions and 68 deletions.
145 changes: 77 additions & 68 deletions ogre2/src/Ogre2SegmentationCamera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -42,26 +42,22 @@ namespace rendering
{
inline namespace IGNITION_RENDERING_VERSION_NAMESPACE {
/// \brief Helper class to assign unique colors to renderables
class Ogre2SegmentationMaterialSwitcher : public Ogre::RenderTargetListener
class Ogre2SegmentationMaterialSwitcher : public Ogre::Camera::Listener
{
/// \brief Constructor
/// \param[in] _scene Ogre scene to be rendered
public: explicit Ogre2SegmentationMaterialSwitcher(Ogre2ScenePtr _scene);

/// \brief Destructor
public: ~Ogre2SegmentationMaterialSwitcher() = default;
public: virtual ~Ogre2SegmentationMaterialSwitcher() = default;

/// \brief Ogre's pre render update callback
/// \param[in] _evt Ogre render target event containing information about
/// the source render target.
public: virtual void preRenderTargetUpdate(
const Ogre::RenderTargetEvent &_evt) override;
/// \brief Callback when a camera is about to be rendered
/// \param[in] _cam Ogre render camara which is about to render.
public: virtual void cameraPreRenderScene(Ogre::Camera *_cam) override;

/// \brief Ogre's post render update callback
/// \param[in] _evt Ogre render target event containing information about
/// the source render target.
public: virtual void postRenderTargetUpdate(
const Ogre::RenderTargetEvent &_evt) override;
/// \brief Callback when a camera is finished being rendered
/// \param[in] _cam Ogre camera that was rendered
public: virtual void cameraPostRenderScene(Ogre::Camera *_cam) override;

/// \brief Convert label of semantic map to a unique color for colored map and
/// add the color of the label to the taken colors if it doesn't exist
Expand Down Expand Up @@ -156,13 +152,7 @@ class ignition::rendering::Ogre2SegmentationCameraPrivate
public: std::string workspaceDefinition;

/// \brief Render Texture to store the final segmentation data
public: Ogre::RenderTexture *ogreRenderTexture {nullptr};

/// \brief Texture to create the render texture from.
public: Ogre::TexturePtr ogreTexture;

/// \brief Pixel Box to copy render texture data to a buffer
public: Ogre::PixelBox *pixelBox {nullptr};
public: Ogre::TextureGpu *ogreRenderTexture {nullptr};

/// \brief buffer to store render texture data & to be sent to listeners
public: uint8_t *buffer = nullptr;
Expand All @@ -181,7 +171,7 @@ class ignition::rendering::Ogre2SegmentationCameraPrivate
const std::string &_format)> newSegmentationFrame;

/// \brief Image / Render Texture Format
public: const Ogre::PixelFormat format = Ogre::PF_R8G8B8;
public: const Ogre::PixelFormatGpu format = Ogre::PFG_RGB8_UNORM;
};

using namespace ignition;
Expand Down Expand Up @@ -293,8 +283,8 @@ VisualPtr Ogre2SegmentationMaterialSwitcher::TopLevelModelVisual(
}

////////////////////////////////////////////////
void Ogre2SegmentationMaterialSwitcher::preRenderTargetUpdate(
const Ogre::RenderTargetEvent &/*_evt*/)
void Ogre2SegmentationMaterialSwitcher::cameraPreRenderScene(
Ogre::Camera *)
{
this->colorToLabel.clear();
this->datablockMap.clear();
Expand Down Expand Up @@ -458,8 +448,8 @@ void Ogre2SegmentationMaterialSwitcher::preRenderTargetUpdate(
}

/////////////////////////////////////////////////
void Ogre2SegmentationMaterialSwitcher::postRenderTargetUpdate(
const Ogre::RenderTargetEvent &/*_evt*/)
void Ogre2SegmentationMaterialSwitcher::cameraPostRenderScene(
Ogre::Camera *)
{
// restore item to use pbs hlms material
for (const auto &[subItem, dataBlock] : this->datablockMap)
Expand Down Expand Up @@ -540,8 +530,9 @@ void Ogre2SegmentationCamera::Destroy()
// remove thermal texture, material, compositor
if (this->dataPtr->ogreRenderTexture)
{
Ogre::TextureManager::getSingleton().remove(
this->dataPtr->ogreRenderTexture->getName());
ogreRoot->getRenderSystem()->getTextureGpuManager()->destroyTexture(
this->dataPtr->ogreRenderTexture);
this->dataPtr->ogreRenderTexture = nullptr;
}
if (this->dataPtr->ogreCompositorWorkspace)
{
Expand Down Expand Up @@ -570,10 +561,6 @@ void Ogre2SegmentationCamera::Destroy()
}
}

if (this->dataPtr->pixelBox)
delete this->dataPtr->pixelBox;
this->dataPtr->pixelBox = nullptr;

if (this->dataPtr->materialSwitcher)
delete this->dataPtr->materialSwitcher;
this->dataPtr->materialSwitcher = nullptr;
Expand All @@ -600,27 +587,28 @@ void Ogre2SegmentationCamera::CreateSegmentationTexture()
auto width = this->ImageWidth();
auto height = this->ImageHeight();

// texture
this->dataPtr->ogreTexture =
Ogre::TextureManager::getSingleton().createManual(
"SegmentationCameraTexture",
Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
Ogre::TEX_TYPE_2D, width, height, 0, this->dataPtr->format,
Ogre::TU_RENDERTARGET
);
auto engine = Ogre2RenderEngine::Instance();
auto ogreRoot = engine->OgreRoot();
Ogre::TextureGpuManager *textureMgr =
ogreRoot->getRenderSystem()->getTextureGpuManager();

// render texture
auto hardwareBuffer = this->dataPtr->ogreTexture->getBuffer();
this->dataPtr->ogreRenderTexture = hardwareBuffer->getRenderTarget();
this->dataPtr->ogreRenderTexture = textureMgr->createOrRetrieveTexture(
"SegmentationCameraTexture",
Ogre::GpuPageOutStrategy::SaveToSystemRam,
Ogre::TextureFlags::RenderToTexture,
Ogre::TextureTypes::Type2D);
this->dataPtr->ogreRenderTexture->setResolution(width, height);
this->dataPtr->ogreRenderTexture->setNumMipmaps(1u);
this->dataPtr->ogreRenderTexture->setPixelFormat(this->dataPtr->format);
this->dataPtr->ogreRenderTexture->scheduleTransitionTo(
Ogre::GpuResidency::Resident);

// switch the material to a unique color for each object
// in the pre render & get the original material again in the post render
this->dataPtr->ogreRenderTexture->addListener(
this->dataPtr->materialSwitcher);
this->ogreCamera->addListener(this->dataPtr->materialSwitcher);

// workspace
auto engine = Ogre2RenderEngine::Instance();
auto ogreRoot = engine->OgreRoot();
this->dataPtr->ogreCompositorManager = ogreRoot->getCompositorManager2();

this->dataPtr->workspaceDefinition = "SegmentationCameraWorkspace_" +
Expand Down Expand Up @@ -652,15 +640,9 @@ void Ogre2SegmentationCamera::CreateSegmentationTexture()
renderScenePass)->setVisibilityMask(IGN_VISIBILITY_ALL);

// buffer to store render texture data
auto bufferSize = Ogre::PixelUtil::getMemorySize(
width, height, 1, this->dataPtr->format);
if (this->dataPtr->buffer)
delete [] this->dataPtr->buffer;
this->dataPtr->buffer = new uint8_t[bufferSize];
if (this->dataPtr->pixelBox)
delete this->dataPtr->pixelBox;
this->dataPtr->pixelBox = new Ogre::PixelBox(width, height, 1,
this->dataPtr->format, this->dataPtr->buffer);
this->dataPtr->buffer = new uint8_t[width * height * 3 * sizeof(uint8_t)];
}

/////////////////////////////////////////////////
Expand All @@ -676,24 +658,34 @@ void Ogre2SegmentationCamera::Render()
/////////////////////////////////////////////////
void Ogre2SegmentationCamera::PostRender()
{
// copy render texture data to the pixel box & its buffer
this->dataPtr->ogreRenderTexture->copyContentsToMemory(
*this->dataPtr->pixelBox,
Ogre::RenderTarget::FB_FRONT
);

// return if no one is listening to the new frame
if (this->dataPtr->newSegmentationFrame.ConnectionCount() == 0)
return;

uint width = this->ImageWidth();
uint height = this->ImageHeight();
uint channelCount = 3;
unsigned int width = this->ImageWidth();
unsigned int height = this->ImageHeight();
unsigned int channelCount = 3;
unsigned int bytesPerChannel = PixelUtil::BytesPerChannel(PF_R8G8B8);

Ogre::Image2 image;
image.convertFromTexture(this->dataPtr->ogreRenderTexture, 0u, 0u);
Ogre::TextureBox box = image.getData(0u);

// copy data row by row. The texture box may not be a contiguous region of
// a texture
uint8_t *segmentationBuffer = static_cast<uint8_t *>(box.data);
for (unsigned int i = 0; i < height; ++i)
{
unsigned int rawDataRowIdx = i * box.bytesPerRow / bytesPerChannel;
unsigned int rowIdx = i * width * channelCount;
memcpy(&this->dataPtr->buffer[rowIdx], &segmentationBuffer[rawDataRowIdx],
width * channelCount * bytesPerChannel);
}

this->dataPtr->newSegmentationFrame(
this->dataPtr->buffer,
width, height, channelCount,
Ogre::PixelUtil::getFormatName(this->dataPtr->format)
PixelUtil::Name(PF_R8G8B8)
);
}

Expand All @@ -709,13 +701,30 @@ void Ogre2SegmentationCamera::Capture(Image &_image)
return;
}

// image buffer
void *data = _image.Data();

// pixel box to copy data from the render texture to the image buffer
Ogre::PixelBox ogrePixelBox(width, height, 1, this->dataPtr->format, data);
this->dataPtr->ogreRenderTexture->copyContentsToMemory(
ogrePixelBox, Ogre::RenderTarget::FB_FRONT);
// I'm not sure what to cast _image.Data to (void * isn't going to work here),
// so for now, this is commented out since it doesn't compile
/*
* unsigned int bytesPerChannel = PixelUtil::BytesPerChannel(_image.Format());
* unsigned int channelCount = _image.Depth();
*
* // image buffer
* void *imgData = _image.Data();
*
* // copy data from the render texture to the image buffer
* Ogre::Image2 image;
* image.convertFromTexture(this->dataPtr->ogreRenderTexture, 0u, 0u);
* Ogre::TextureBox box = image.getData(0);
* void *bufferTmp = static_cast<void *>(box.data);
* // copy data row by row. The texture box may not be a contiguous region of
* // a texture
* for (unsigned int i = 0; i < height; ++i)
* {
* unsigned int rawDataRowIdx = i * box.bytesPerRow / bytesPerChannel;
* unsigned int rowIdx = i * width * channelCount;
* memcpy(&imgData[rowIdx], &bufferTmp[rawDataRowIdx],
* width * channelCount * bytesPerChannel);
* }
*/
}

/////////////////////////////////////////////////
Expand Down

1 comment on commit f81dd61

@adlarkin
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

For context, I have branched off of the fork in #329 and have merged in the recent changes from the main branch. Part of the recent changes on main are updating from ogre2.1 to ogre2.2 (#272), so now, I am trying to update the Ogre2SegmentationCamera in #329 to use ogre2.2 instead of 2.1.

If you'd like to test the changes being made here, you can either try running the unit/integration tests added in #329 or build this in a workspace along with gazebosim/gz-sim#853 and gazebosim/gz-sensors#133, and then try running segmentation_camera.sdf from the gazebo PR. If you do decide to build a workspace with the gazebo and sensors PRs, you'll need to make the following changes to the gazebo PR in order to get it to compile:

Gazebo PR compilation fix
diff --git a/CMakeLists.txt b/CMakeLists.txt
index e44476b9..12993b00 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -121,7 +121,7 @@ ign_find_package(ignition-sensors6 REQUIRED
 
     # cameras
     camera
-    boundingbox_camera
+    #boundingbox_camera
     segmentation_camera
     depth_camera
     rgbd_camera
diff --git a/examples/worlds/segmentation_camera.sdf b/examples/worlds/segmentation_camera.sdf
index 56c9be54..b116c743 100644
--- a/examples/worlds/segmentation_camera.sdf
+++ b/examples/worlds/segmentation_camera.sdf
@@ -221,6 +221,17 @@
       </uri>
     </include>

+    <!-- adding a double pendulum in to test multi-link models --> 
+    <include>
+      <name>dblPendulum</name>
+      <pose>1 2 0 0 0 0</pose>
+      <uri>
+          https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Double pendulum with base
+      </uri>
+      <plugin filename="ignition-gazebo-label-system" name="ignition::gazebo::systems::Label">
+        <label>5</label>
+      </plugin>
+    </include>
+
     <!-- Cones, all with label 20-->
     <include>
       <name>cone1</name>
diff --git a/src/systems/sensors/CMakeLists.txt b/src/systems/sensors/CMakeLists.txt
index d9187882..e9bb8589 100644
--- a/src/systems/sensors/CMakeLists.txt
+++ b/src/systems/sensors/CMakeLists.txt
@@ -6,7 +6,7 @@ gz_add_system(sensors
     ignition-common${IGN_COMMON_VER}::ignition-common${IGN_COMMON_VER}
     ignition-rendering${IGN_RENDERING_VER}::ignition-rendering${IGN_RENDERING_VER}
     ignition-sensors${IGN_SENSORS_VER}::camera
-    ignition-sensors${IGN_SENSORS_VER}::boundingbox_camera
+    #ignition-sensors${IGN_SENSORS_VER}::boundingbox_camera
     ignition-sensors${IGN_SENSORS_VER}::segmentation_camera
     ignition-sensors${IGN_SENSORS_VER}::depth_camera
     ignition-sensors${IGN_SENSORS_VER}::gpu_lidar
diff --git a/src/systems/sensors/Sensors.cc b/src/systems/sensors/Sensors.cc
index c74dc899..a2a69b0e 100644
--- a/src/systems/sensors/Sensors.cc
+++ b/src/systems/sensors/Sensors.cc
@@ -32,13 +32,13 @@
 
 #include <ignition/rendering/Scene.hh>
 #include <ignition/sensors/CameraSensor.hh>
-#include <ignition/sensors/BoundingBoxCameraSensor.hh>
+//#include <ignition/sensors/BoundingBoxCameraSensor.hh>
 #include <ignition/sensors/DepthCameraSensor.hh>
 #include <ignition/sensors/GpuLidarSensor.hh>
 #include <ignition/sensors/RenderingSensor.hh>
 #include <ignition/sensors/RgbdCameraSensor.hh>
 #include <ignition/sensors/ThermalCameraSensor.hh>
-// #include <ignition/sensors/SegmentationCameraSensor.hh>
+#include <ignition/sensors/SegmentationCameraSensor.hh>
 #include <ignition/sensors/Manager.hh>
 
 #include "ignition/gazebo/components/Atmosphere.hh"
@@ -564,13 +564,13 @@ std::string Sensors::CreateSensor(const Entity &_entity,
   }
   else if (_sdf.Type() == sdf::SensorType::BOUNDINGBOX_CAMERA)
   {
-    sensor = this->dataPtr->sensorManager.CreateSensor<
-      sensors::BoundingBoxCameraSensor>(_sdf);
+    //sensor = this->dataPtr->sensorManager.CreateSensor<
+      //sensors::BoundingBoxCameraSensor>(_sdf);
   }
   else if (_sdf.Type() == sdf::SensorType::SEGMENTATION_CAMERA)
   {
-    // sensor = this->dataPtr->sensorManager.CreateSensor<
-    //   sensors::SegmentationCameraSensor>(_sdf);
+     sensor = this->dataPtr->sensorManager.CreateSensor<
+       sensors::SegmentationCameraSensor>(_sdf);
   }
 
   if (nullptr == sensor)

The changes I've made here compiles, but I'm having runtime issues.

First off, I have noticed that this line crashes because node->_getPasses() returns a vector of size 1, so instead of indexing at 1, it needs to be indexed at 0. So, it seems like the number of passes has changed between ogre2.1 and ogre2.2. Would it make sense that the number of passes changed between ogre2.1 and ogre2.2, or is something else wrong here?

If the index is updated to prevent the crash as mentioned above, I then see this error when I try to run segmentation_camera.sdf from the gazebo PR:

ign gazebo server: /var/lib/jenkins/workspace/ogre-2.2-debbuilder/repo/OgreMain/src/OgreTextureGpu.cpp:175: void Ogre::TextureGpu::setResolution(Ogre::uint32, Ogre::uint32, Ogre::uint32): Assertion `mResidencyStatus == GpuResidency::OnStorage || isRenderWindowSpecific()' failed.

Lastly, I also am not sure how to update Ogre2SegmentationCamera::Capture properly for ogre2.2 (see the commented out section in the diff of that method above for more details). If anyone has feedback for this, that would be greatly appreciated!

Please sign in to comment.