Skip to content

Commit a961249

Browse files
committed
Added ability to set backgorund image for RGB renderer
1 parent 626ed6a commit a961249

File tree

4 files changed

+80
-20
lines changed

4 files changed

+80
-20
lines changed

modules/ar/include/visp3/ar/vpPanda3DRGBRenderer.h

+7-1
Original file line numberDiff line numberDiff line change
@@ -68,7 +68,7 @@ class VISP_EXPORT vpPanda3DRGBRenderer : public vpPanda3DBaseRenderer, public vp
6868
* \brief Default constructor. Initialize an RGB renderer with the normal rendering behavior showing speculars
6969
*
7070
*/
71-
vpPanda3DRGBRenderer() : vpPanda3DBaseRenderer("RGB"), m_showSpeculars(true) { }
71+
vpPanda3DRGBRenderer() : vpPanda3DBaseRenderer("RGB"), m_showSpeculars(true), m_display2d(nullptr), m_backgroundTexture(nullptr) { }
7272
/**
7373
* \brief RGB renderer constructor allowing to specify
7474
* whether specular highlights should be rendered or
@@ -90,10 +90,13 @@ class VISP_EXPORT vpPanda3DRGBRenderer : public vpPanda3DBaseRenderer, public vp
9090

9191
void addNodeToScene(const NodePath &object) vp_override;
9292

93+
void setBackgroundImage(const vpImage<vpRGBa> &background);
94+
9395
GraphicsOutput *getMainOutputBuffer() vp_override { return m_colorBuffer; }
9496

9597
bool isShowingSpeculars() const { return m_showSpeculars; }
9698

99+
97100
protected:
98101
void setupScene() vp_override;
99102
void setupRenderTarget() vp_override;
@@ -106,6 +109,9 @@ class VISP_EXPORT vpPanda3DRGBRenderer : public vpPanda3DBaseRenderer, public vp
106109
static const char *COOK_TORRANCE_VERT;
107110
static const char *COOK_TORRANCE_FRAG;
108111

112+
NodePath m_backgroundImage;
113+
DisplayRegion *m_display2d;
114+
PT(Texture) m_backgroundTexture;
109115

110116
};
111117

modules/ar/src/panda3d-simulator/vpPanda3DGeometryRenderer.cpp

+3-5
Original file line numberDiff line numberDiff line change
@@ -197,7 +197,6 @@ void vpPanda3DGeometryRenderer::getRender(vpImage<vpRGBf> &normals, vpImage<floa
197197
rowIncrement = -rowIncrement;
198198

199199
for (unsigned int i = 0; i < normals.getHeight(); ++i) {
200-
data += rowIncrement;
201200
vpRGBf *normalRow = normals[i];
202201
float *depthRow = depth[i];
203202
for (unsigned int j = 0; j < normals.getWidth(); ++j) {
@@ -206,9 +205,8 @@ void vpPanda3DGeometryRenderer::getRender(vpImage<vpRGBf> &normals, vpImage<floa
206205
normalRow[j].R = (data[j * 4 + 2]);
207206
depthRow[j] = (data[j * 4 + 3]);
208207
}
208+
data += rowIncrement;
209209
}
210-
211-
//#pragma omp parallel for simd
212210
}
213211

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

226224
for (unsigned int i = 0; i < normals.getHeight(); ++i) {
227-
data += rowIncrement;
228225
vpRGBf *normalRow = normals[i];
229226
for (unsigned int j = 0; j < normals.getWidth(); ++j) {
230227
normalRow[j].B = (data[j * 4]);
231228
normalRow[j].G = (data[j * 4 + 1]);
232229
normalRow[j].R = (data[j * 4 + 2]);
233230
}
231+
data += rowIncrement;
234232
}
235233
}
236234

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

249247
for (unsigned int i = 0; i < depth.getHeight(); ++i) {
250-
data += rowIncrement;
251248
float *depthRow = depth[i];
252249
for (unsigned int j = 0; j < depth.getWidth(); ++j) {
253250
depthRow[j] = (data[j * 4 + 3]);
254251
}
252+
data += rowIncrement;
255253
}
256254
}
257255

modules/ar/src/panda3d-simulator/vpPanda3DRGBRenderer.cpp

+53-1
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,10 @@
3333

3434
#if defined(VISP_HAVE_PANDA3D)
3535

36+
#include "orthographicLens.h"
37+
#include "cardMaker.h"
38+
#include "texturePool.h"
39+
3640
const char *vpPanda3DRGBRenderer::COOK_TORRANCE_VERT = R"shader(
3741
#version 330
3842
@@ -238,6 +242,54 @@ void vpPanda3DRGBRenderer::addNodeToScene(const NodePath &object)
238242
}
239243

240244

245+
void vpPanda3DRGBRenderer::setBackgroundImage(const vpImage<vpRGBa> &background)
246+
{
247+
248+
if (m_display2d == nullptr) {
249+
CardMaker cm("card");
250+
cm.set_frame_fullscreen_quad();
251+
252+
NodePath myCamera2d(new Camera("myCam2d"));
253+
PT(OrthographicLens) lens = new OrthographicLens();
254+
lens->set_film_size(2, 2);
255+
lens->set_near_far(-1000, 1000);
256+
lens->set_film_offset(0, 0);
257+
((Camera *)myCamera2d.node())->set_lens(lens);
258+
259+
NodePath myRender2d("myRender2d");
260+
myRender2d.set_depth_test(false);
261+
myRender2d.set_depth_write(false);
262+
myCamera2d.reparent_to(myRender2d);
263+
m_backgroundImage = myRender2d.attach_new_node(cm.generate());
264+
265+
m_display2d = m_colorBuffer->make_display_region();
266+
m_display2d->set_sort(-100);
267+
m_display2d->set_camera(myCamera2d);
268+
}
269+
if (m_backgroundTexture == nullptr) {
270+
m_backgroundTexture = new Texture();
271+
}
272+
m_backgroundImage.set_texture(m_backgroundTexture);
273+
m_backgroundTexture->setup_2d_texture(background.getWidth(), background.getHeight(),
274+
Texture::ComponentType::T_unsigned_byte,
275+
Texture::Format::F_rgba8);
276+
//m_backgroundTexture = TexturePool::load_texture("/home/sfelton/IMG_20230221_165330430.jpg");
277+
unsigned char *data = (unsigned char *)m_backgroundTexture->modify_ram_image();
278+
279+
std::cout << m_backgroundTexture->get_x_size() << ", " << m_backgroundTexture->get_y_size() << std::endl;
280+
for (unsigned int i = 0; i < background.getHeight(); ++i) {
281+
const vpRGBa *srcRow = background[background.getHeight() - (i + 1)];
282+
unsigned char *destRow = data + i * background.getWidth() * 4;
283+
for (unsigned int j = 0; j < background.getWidth(); ++j) {
284+
destRow[j * 4] = srcRow[j].B;
285+
destRow[j * 4 + 1] = srcRow[j].G;
286+
destRow[j * 4 + 2] = srcRow[j].R;
287+
destRow[j * 4 + 3] = srcRow[j].A;
288+
}
289+
}
290+
291+
}
292+
241293
void vpPanda3DRGBRenderer::getRender(vpImage<vpRGBa> &I) const
242294
{
243295
I.resize(m_colorTexture->get_y_size(), m_colorTexture->get_x_size());
@@ -249,7 +301,6 @@ void vpPanda3DRGBRenderer::getRender(vpImage<vpRGBa> &I) const
249301
rowIncrement = -rowIncrement;
250302

251303
for (unsigned int i = 0; i < I.getHeight(); ++i) {
252-
data += rowIncrement;
253304
vpRGBa *colorRow = I[i];
254305
for (unsigned int j = 0; j < I.getWidth(); ++j) {
255306
// BGRA order in panda3d
@@ -258,6 +309,7 @@ void vpPanda3DRGBRenderer::getRender(vpImage<vpRGBa> &I) const
258309
colorRow[j].R = data[j * 4 + 2];
259310
colorRow[j].A = data[j * 4 + 3];
260311
}
312+
data += rowIncrement;
261313
}
262314

263315

tutorial/ar/tutorial-panda3d-renderer.cpp

+17-13
Original file line numberDiff line numberDiff line change
@@ -46,6 +46,7 @@
4646
#include <visp3/gui/vpDisplayGTK.h>
4747

4848
#include <visp3/io/vpParseArgv.h>
49+
#include <visp3/io/vpImageIo.h>
4950

5051
#include <visp3/ar/vpPanda3DRGBRenderer.h>
5152
#include <visp3/ar/vpPanda3DGeometryRenderer.h>
@@ -120,10 +121,14 @@ int main(int argc, const char **argv)
120121
bool showLightContrib = false;
121122
bool showCanny = false;
122123
char *modelPathCstr = nullptr;
124+
char *backgroundPathCstr = nullptr;
125+
123126
vpParseArgv::vpArgvInfo argTable[] =
124127
{
125128
{"-model", vpParseArgv::ARGV_STRING, (char *) nullptr, (char *)&modelPathCstr,
126129
"Path to the model to load."},
130+
{"-background", vpParseArgv::ARGV_STRING, (char *) nullptr, (char *)&backgroundPathCstr,
131+
"Path to the background image to load for the rgb renderer."},
127132
{"-step", vpParseArgv::ARGV_CONSTANT_BOOL, (char *) nullptr, (char *)&stepByStep,
128133
"Show frames step by step."},
129134
{"-specular", vpParseArgv::ARGV_CONSTANT_BOOL, (char *) nullptr, (char *)&showLightContrib,
@@ -151,6 +156,10 @@ int main(int argc, const char **argv)
151156
else {
152157
modelPath = "data/suzanne.bam";
153158
}
159+
std::string backgroundPath;
160+
if (backgroundPathCstr) {
161+
backgroundPath = backgroundPathCstr;
162+
}
154163
vpPanda3DRenderParameters renderParams(vpCameraParameters(300, 300, 160, 120), 240, 320, 0.01, 10.0);
155164
vpPanda3DRendererSet renderer(renderParams);
156165
renderer.setRenderParameters(renderParams);
@@ -212,11 +221,17 @@ int main(int argc, const char **argv)
212221
renderer.addLight(dlight);
213222

214223
rgbRenderer->printStructure();
224+
if (!backgroundPath.empty()) {
225+
vpImage<vpRGBa> background;
226+
vpImageIo::read(background, backgroundPath);
227+
rgbRenderer->setBackgroundImage(background);
228+
}
229+
230+
215231
std::cout << "Setting camera pose" << std::endl;
216232
renderer.setCameraPose(vpHomogeneousMatrix(0.0, 0.0, -0.3, 0.0, 0.0, 0.0));
217-
218233
unsigned h = renderParams.getImageHeight(), w = renderParams.getImageWidth();
219-
234+
std::cout << "Creating display and data images" << std::endl;
220235
vpImage<vpRGBf> normalsImage;
221236
vpImage<vpRGBf> cameraNormalsImage;
222237
vpImage<vpRGBf> cannyRawData;
@@ -281,7 +296,6 @@ int main(int argc, const char **argv)
281296
}
282297

283298
const double beforeConvert = vpTime::measureTimeMs();
284-
285299
displayNormals(normalsImage, normalDisplayImage);
286300
displayNormals(cameraNormalsImage, cameraNormalDisplayImage);
287301
displayDepth(depthImage, depthDisplayImage, nearV, farV);
@@ -316,16 +330,6 @@ int main(int argc, const char **argv)
316330
}
317331
}
318332
}
319-
// if (firstFrame) {
320-
// renderParams.setImageResolution(h * 0.5, w * 0.5);
321-
// vpCameraParameters orig = renderParams.getCameraIntrinsics();
322-
// vpCameraParameters newCam(orig.get_px() * 0.5, orig.get_py() * 0.5, orig.get_u0() * 0.5, orig.get_v0() * 0.5);
323-
// renderParams.setCameraIntrinsics(newCam);
324-
// std::cout << h << std::endl;
325-
// //dDepth.setDownScalingFactor(0.5);
326-
// renderer.setRenderParameters(renderParams);
327-
// }
328-
// firstFrame = false;
329333
const double afterAll = vpTime::measureTimeMs();
330334
const double delta = (afterAll - beforeRender) / 1000.0;
331335
const vpHomogeneousMatrix wTo = renderer.getNodePose(objectName);

0 commit comments

Comments
 (0)