Skip to content

Commit

Permalink
Added ability to set backgorund image for RGB renderer
Browse files Browse the repository at this point in the history
  • Loading branch information
SamFlt committed May 24, 2024
1 parent 626ed6a commit a961249
Show file tree
Hide file tree
Showing 4 changed files with 80 additions and 20 deletions.
8 changes: 7 additions & 1 deletion modules/ar/include/visp3/ar/vpPanda3DRGBRenderer.h
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ class VISP_EXPORT vpPanda3DRGBRenderer : public vpPanda3DBaseRenderer, public vp
* \brief Default constructor. Initialize an RGB renderer with the normal rendering behavior showing speculars
*
*/
vpPanda3DRGBRenderer() : vpPanda3DBaseRenderer("RGB"), m_showSpeculars(true) { }
vpPanda3DRGBRenderer() : vpPanda3DBaseRenderer("RGB"), m_showSpeculars(true), m_display2d(nullptr), m_backgroundTexture(nullptr) { }
/**
* \brief RGB renderer constructor allowing to specify
* whether specular highlights should be rendered or
Expand All @@ -90,10 +90,13 @@ class VISP_EXPORT vpPanda3DRGBRenderer : public vpPanda3DBaseRenderer, public vp

void addNodeToScene(const NodePath &object) vp_override;

void setBackgroundImage(const vpImage<vpRGBa> &background);

GraphicsOutput *getMainOutputBuffer() vp_override { return m_colorBuffer; }

bool isShowingSpeculars() const { return m_showSpeculars; }


protected:
void setupScene() vp_override;
void setupRenderTarget() vp_override;
Expand All @@ -106,6 +109,9 @@ class VISP_EXPORT vpPanda3DRGBRenderer : public vpPanda3DBaseRenderer, public vp
static const char *COOK_TORRANCE_VERT;
static const char *COOK_TORRANCE_FRAG;

NodePath m_backgroundImage;
DisplayRegion *m_display2d;
PT(Texture) m_backgroundTexture;

};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -197,7 +197,6 @@ void vpPanda3DGeometryRenderer::getRender(vpImage<vpRGBf> &normals, vpImage<floa
rowIncrement = -rowIncrement;

for (unsigned int i = 0; i < normals.getHeight(); ++i) {
data += rowIncrement;
vpRGBf *normalRow = normals[i];
float *depthRow = depth[i];
for (unsigned int j = 0; j < normals.getWidth(); ++j) {
Expand All @@ -206,9 +205,8 @@ void vpPanda3DGeometryRenderer::getRender(vpImage<vpRGBf> &normals, vpImage<floa
normalRow[j].R = (data[j * 4 + 2]);
depthRow[j] = (data[j * 4 + 3]);
}
data += rowIncrement;
}

//#pragma omp parallel for simd
}

void vpPanda3DGeometryRenderer::getRender(vpImage<vpRGBf> &normals) const
Expand All @@ -224,13 +222,13 @@ void vpPanda3DGeometryRenderer::getRender(vpImage<vpRGBf> &normals) const
rowIncrement = -rowIncrement;

for (unsigned int i = 0; i < normals.getHeight(); ++i) {
data += rowIncrement;
vpRGBf *normalRow = normals[i];
for (unsigned int j = 0; j < normals.getWidth(); ++j) {
normalRow[j].B = (data[j * 4]);
normalRow[j].G = (data[j * 4 + 1]);
normalRow[j].R = (data[j * 4 + 2]);
}
data += rowIncrement;
}
}

Expand All @@ -247,11 +245,11 @@ void vpPanda3DGeometryRenderer::getRender(vpImage<float> &depth) const
rowIncrement = -rowIncrement;

for (unsigned int i = 0; i < depth.getHeight(); ++i) {
data += rowIncrement;
float *depthRow = depth[i];
for (unsigned int j = 0; j < depth.getWidth(); ++j) {
depthRow[j] = (data[j * 4 + 3]);
}
data += rowIncrement;
}
}

Expand Down
54 changes: 53 additions & 1 deletion modules/ar/src/panda3d-simulator/vpPanda3DRGBRenderer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,10 @@

#if defined(VISP_HAVE_PANDA3D)

#include "orthographicLens.h"
#include "cardMaker.h"
#include "texturePool.h"

const char *vpPanda3DRGBRenderer::COOK_TORRANCE_VERT = R"shader(
#version 330
Expand Down Expand Up @@ -238,6 +242,54 @@ void vpPanda3DRGBRenderer::addNodeToScene(const NodePath &object)
}


void vpPanda3DRGBRenderer::setBackgroundImage(const vpImage<vpRGBa> &background)
{

if (m_display2d == nullptr) {
CardMaker cm("card");
cm.set_frame_fullscreen_quad();

NodePath myCamera2d(new Camera("myCam2d"));
PT(OrthographicLens) lens = new OrthographicLens();
lens->set_film_size(2, 2);
lens->set_near_far(-1000, 1000);
lens->set_film_offset(0, 0);
((Camera *)myCamera2d.node())->set_lens(lens);

NodePath myRender2d("myRender2d");
myRender2d.set_depth_test(false);
myRender2d.set_depth_write(false);
myCamera2d.reparent_to(myRender2d);
m_backgroundImage = myRender2d.attach_new_node(cm.generate());

m_display2d = m_colorBuffer->make_display_region();
m_display2d->set_sort(-100);
m_display2d->set_camera(myCamera2d);
}
if (m_backgroundTexture == nullptr) {
m_backgroundTexture = new Texture();
}
m_backgroundImage.set_texture(m_backgroundTexture);
m_backgroundTexture->setup_2d_texture(background.getWidth(), background.getHeight(),
Texture::ComponentType::T_unsigned_byte,
Texture::Format::F_rgba8);
//m_backgroundTexture = TexturePool::load_texture("/home/sfelton/IMG_20230221_165330430.jpg");
unsigned char *data = (unsigned char *)m_backgroundTexture->modify_ram_image();

std::cout << m_backgroundTexture->get_x_size() << ", " << m_backgroundTexture->get_y_size() << std::endl;
for (unsigned int i = 0; i < background.getHeight(); ++i) {
const vpRGBa *srcRow = background[background.getHeight() - (i + 1)];
unsigned char *destRow = data + i * background.getWidth() * 4;
for (unsigned int j = 0; j < background.getWidth(); ++j) {
destRow[j * 4] = srcRow[j].B;
destRow[j * 4 + 1] = srcRow[j].G;
destRow[j * 4 + 2] = srcRow[j].R;
destRow[j * 4 + 3] = srcRow[j].A;
}
}

}

void vpPanda3DRGBRenderer::getRender(vpImage<vpRGBa> &I) const
{
I.resize(m_colorTexture->get_y_size(), m_colorTexture->get_x_size());
Expand All @@ -249,7 +301,6 @@ void vpPanda3DRGBRenderer::getRender(vpImage<vpRGBa> &I) const
rowIncrement = -rowIncrement;

for (unsigned int i = 0; i < I.getHeight(); ++i) {
data += rowIncrement;
vpRGBa *colorRow = I[i];
for (unsigned int j = 0; j < I.getWidth(); ++j) {
// BGRA order in panda3d
Expand All @@ -258,6 +309,7 @@ void vpPanda3DRGBRenderer::getRender(vpImage<vpRGBa> &I) const
colorRow[j].R = data[j * 4 + 2];
colorRow[j].A = data[j * 4 + 3];
}
data += rowIncrement;
}


Expand Down
30 changes: 17 additions & 13 deletions tutorial/ar/tutorial-panda3d-renderer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@
#include <visp3/gui/vpDisplayGTK.h>

#include <visp3/io/vpParseArgv.h>
#include <visp3/io/vpImageIo.h>

#include <visp3/ar/vpPanda3DRGBRenderer.h>
#include <visp3/ar/vpPanda3DGeometryRenderer.h>
Expand Down Expand Up @@ -120,10 +121,14 @@ int main(int argc, const char **argv)
bool showLightContrib = false;
bool showCanny = false;
char *modelPathCstr = nullptr;
char *backgroundPathCstr = nullptr;

vpParseArgv::vpArgvInfo argTable[] =
{
{"-model", vpParseArgv::ARGV_STRING, (char *) nullptr, (char *)&modelPathCstr,
"Path to the model to load."},
{"-background", vpParseArgv::ARGV_STRING, (char *) nullptr, (char *)&backgroundPathCstr,
"Path to the background image to load for the rgb renderer."},
{"-step", vpParseArgv::ARGV_CONSTANT_BOOL, (char *) nullptr, (char *)&stepByStep,
"Show frames step by step."},
{"-specular", vpParseArgv::ARGV_CONSTANT_BOOL, (char *) nullptr, (char *)&showLightContrib,
Expand Down Expand Up @@ -151,6 +156,10 @@ int main(int argc, const char **argv)
else {
modelPath = "data/suzanne.bam";
}
std::string backgroundPath;
if (backgroundPathCstr) {
backgroundPath = backgroundPathCstr;
}
vpPanda3DRenderParameters renderParams(vpCameraParameters(300, 300, 160, 120), 240, 320, 0.01, 10.0);
vpPanda3DRendererSet renderer(renderParams);
renderer.setRenderParameters(renderParams);
Expand Down Expand Up @@ -212,11 +221,17 @@ int main(int argc, const char **argv)
renderer.addLight(dlight);

rgbRenderer->printStructure();
if (!backgroundPath.empty()) {
vpImage<vpRGBa> background;
vpImageIo::read(background, backgroundPath);
rgbRenderer->setBackgroundImage(background);
}


std::cout << "Setting camera pose" << std::endl;
renderer.setCameraPose(vpHomogeneousMatrix(0.0, 0.0, -0.3, 0.0, 0.0, 0.0));

unsigned h = renderParams.getImageHeight(), w = renderParams.getImageWidth();

std::cout << "Creating display and data images" << std::endl;
vpImage<vpRGBf> normalsImage;
vpImage<vpRGBf> cameraNormalsImage;
vpImage<vpRGBf> cannyRawData;
Expand Down Expand Up @@ -281,7 +296,6 @@ int main(int argc, const char **argv)
}

const double beforeConvert = vpTime::measureTimeMs();

displayNormals(normalsImage, normalDisplayImage);
displayNormals(cameraNormalsImage, cameraNormalDisplayImage);
displayDepth(depthImage, depthDisplayImage, nearV, farV);
Expand Down Expand Up @@ -316,16 +330,6 @@ int main(int argc, const char **argv)
}
}
}
// if (firstFrame) {
// renderParams.setImageResolution(h * 0.5, w * 0.5);
// vpCameraParameters orig = renderParams.getCameraIntrinsics();
// vpCameraParameters newCam(orig.get_px() * 0.5, orig.get_py() * 0.5, orig.get_u0() * 0.5, orig.get_v0() * 0.5);
// renderParams.setCameraIntrinsics(newCam);
// std::cout << h << std::endl;
// //dDepth.setDownScalingFactor(0.5);
// renderer.setRenderParameters(renderParams);
// }
// firstFrame = false;
const double afterAll = vpTime::measureTimeMs();
const double delta = (afterAll - beforeRender) / 1000.0;
const vpHomogeneousMatrix wTo = renderer.getNodePose(objectName);
Expand Down

0 comments on commit a961249

Please sign in to comment.