Visual Servoing Platform  version 3.6.1 under development (2025-03-06)
vpPanda3DPostProcessFilter.cpp
1 /*
2  * ViSP, open source Visual Servoing Platform software.
3  * Copyright (C) 2005 - 2024 by Inria. All rights reserved.
4  *
5  * This software is free software; you can redistribute it and/or modify
6  * it under the terms of the GNU General Public License as published by
7  * the Free Software Foundation; either version 2 of the License, or
8  * (at your option) any later version.
9  * See the file LICENSE.txt at the root directory of this source
10  * distribution for additional information about the GNU GPL.
11  *
12  * For using ViSP with software that can not be combined with the GNU
13  * GPL, please contact Inria about acquiring a ViSP Professional
14  * Edition License.
15  *
16  * See https://visp.inria.fr for more information.
17  *
18  * This software was developed at:
19  * Inria Rennes - Bretagne Atlantique
20  * Campus Universitaire de Beaulieu
21  * 35042 Rennes Cedex
22  * France
23  *
24  * If you have questions regarding the use of this file, please contact
25  * Inria at visp@inria.fr
26  *
27  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29  */
30 
31 #include <visp3/ar/vpPanda3DPostProcessFilter.h>
32 
33 #if defined(VISP_HAVE_PANDA3D)
34 
35 #include "lightRampAttrib.h"
36 #include "graphicsOutput.h"
37 #include "windowFramework.h"
38 #include "graphicsEngine.h"
39 
40 BEGIN_VISP_NAMESPACE
42 "#version 330\n"
43 "in vec4 p3d_Vertex;\n"
44 "uniform mat4 p3d_ModelViewProjectionMatrix;\n"
45 "in vec2 p3d_MultiTexCoord0;\n"
46 "out vec2 texcoords;\n"
47 
48 "void main()\n"
49 "{\n"
50 " gl_Position = p3d_ModelViewProjectionMatrix * p3d_Vertex;\n"
51 " texcoords = p3d_MultiTexCoord0;\n"
52 "}\n";
53 
55 {
56  CardMaker cm("cm");
57  cm.set_frame_fullscreen_quad();
58  m_renderRoot = NodePath(cm.generate()); // Render root is a 2D rectangle
59  m_renderRoot.set_depth_test(false);
60  m_renderRoot.set_depth_write(false);
61  GraphicsOutput *buffer = m_inputRenderer->getMainOutputBuffer();
62  if (buffer == nullptr) {
64  "Cannot add a postprocess filter to a renderer that does not define getMainOutputBuffer()");
65  }
66  m_shader = Shader::make(Shader::ShaderLanguage::SL_GLSL,
69  m_renderRoot.set_shader(m_shader);
70  m_renderRoot.set_shader_input("dp", LVector2f(1.0 / buffer->get_texture()->get_x_size(), 1.0 / buffer->get_texture()->get_y_size()));
71  m_renderRoot.set_texture(buffer->get_texture());
72  m_renderRoot.set_attrib(LightRampAttrib::make_identity());
73 }
74 
76 {
77  m_cameraPath = m_window->make_camera();
78  m_camera = (Camera *)m_cameraPath.node();
79  PT(OrthographicLens) lens = new OrthographicLens();
80  lens->set_film_size(2, 2);
81  lens->set_film_offset(0, 0);
82  lens->set_near_far(-1000, 1000);
83  m_camera->set_lens(lens);
84  m_cameraPath = m_renderRoot.attach_new_node(m_camera);
85  m_camera->set_scene(m_renderRoot);
86 }
87 
89 {
90 
91  if (m_window == nullptr) {
92  throw vpException(vpException::fatalError, "Cannot setup render target when window is null");
93  }
94  FrameBufferProperties fbp = getBufferProperties();
95  WindowProperties win_prop;
97 
98  // Don't open a window - force it to be an offscreen buffer.
99  int flags = GraphicsPipe::BF_refuse_window | GraphicsPipe::BF_resizeable;
100  GraphicsOutput *windowOutput = m_window->get_graphics_output();
101  GraphicsEngine *engine = windowOutput->get_engine();
102  GraphicsStateGuardian *gsg = windowOutput->get_gsg();
103  GraphicsPipe *pipe = windowOutput->get_pipe();
104  static int id = 0;
105  m_buffer = engine->make_output(pipe, m_name + std::to_string(id), m_renderOrder,
106  fbp, win_prop, flags,
107  gsg, windowOutput);
108 
109  ++id;
110  if (m_buffer == nullptr) {
111  throw vpException(vpException::fatalError, "Could not create buffer");
112  }
113  m_buffers.push_back(m_buffer);
114  //m_buffer->set_inverted(true);
115  m_texture = new Texture();
116  fbp.setup_color_texture(m_texture);
117  m_buffer->add_render_texture(m_texture, m_isOutput ? GraphicsOutput::RenderTextureMode::RTM_copy_texture : GraphicsOutput::RenderTextureMode::RTM_bind_or_copy);
118  m_buffer->set_clear_color(LColor(0.f));
119  m_buffer->set_clear_color_active(true);
120  DisplayRegion *region = m_buffer->make_display_region();
121  if (region == nullptr) {
122  throw vpException(vpException::fatalError, "Could not create display region");
123  }
124  region->set_camera(m_cameraPath);
125  region->set_clear_color(LColor(0.f));
126 }
127 
129 {
130  unsigned int previousH = m_renderParameters.getImageHeight(), previousW = m_renderParameters.getImageWidth();
131  bool resize = previousH != params.getImageHeight() || previousW != params.getImageWidth();
132 
133  m_renderParameters = params;
134  if (m_window != nullptr) {
135  GraphicsOutput *buffer = m_inputRenderer->getMainOutputBuffer();
136  m_renderRoot.set_shader_input("dp", LVector2f(1.0 / buffer->get_texture()->get_x_size(), 1.0 / buffer->get_texture()->get_y_size()));
137  }
138  if (resize) {
139  for (GraphicsOutput *buffer: m_buffers) {
140  //buffer->get_type().is_derived_from()
141  GraphicsBuffer *buf = dynamic_cast<GraphicsBuffer *>(buffer);
142  if (buf == nullptr) {
143  throw vpException(vpException::fatalError, "Panda3D: could not cast to GraphicsBuffer when rendering.");
144  }
145  else {
147  }
148  }
149  }
150 }
151 
153 {
154  if (!m_isOutput) {
155  throw vpException(vpException::fatalError, "Tried to fetch output of a postprocessing filter that was configured as an intermediate output");
156  }
157 
159  const unsigned numComponents = m_texture->get_num_components();
160  int rowIncrement = I.getWidth() * numComponents; // we ask for only 8 bits image, but we may get an rgb image
161  unsigned char *data = (unsigned char *)(&(m_texture->get_ram_image().front()));
162  // Panda3D stores data upside down
163  data += rowIncrement * (I.getHeight() - 1);
164  rowIncrement = -rowIncrement;
165 
166  for (unsigned int i = 0; i < I.getHeight(); ++i) {
167  unsigned char *colorRow = I[i];
168  for (unsigned int j = 0; j < I.getWidth(); ++j) {
169  colorRow[j] = data[j * numComponents];
170  }
171  data += rowIncrement;
172  }
173 }
174 
176 {
177  if (!m_isOutput) {
178  throw vpException(vpException::fatalError, "Tried to fetch output of a postprocessing filter that was configured as an intermediate output");
179  }
180 
182  const unsigned numComponents = m_texture->get_num_components();
183  int rowIncrement = I.getWidth() * numComponents; // we ask for only 8 bits image, but we may get an rgb image
184  float *data = (float *)(&(m_texture->get_ram_image().front()));
185  // Panda3D stores data upside down
186  data += rowIncrement * (I.getHeight() - 1);
187  rowIncrement = -rowIncrement;
188 
189  for (unsigned int i = 0; i < I.getHeight(); ++i) {
190  vpRGBf *colorRow = I[i];
191  for (unsigned int j = 0; j < I.getWidth(); ++j) {
192  colorRow[j].B = data[j * numComponents];
193  colorRow[j].G = data[j * numComponents + 1];
194  colorRow[j].R = data[j * numComponents + 2];
195  }
196  data += rowIncrement;
197  }
198 }
199 
200 END_VISP_NAMESPACE
201 
202 #elif !defined(VISP_BUILD_SHARED_LIBS)
203 // Work around to avoid warning: libvisp_ar.a(vpPanda3DPostProcessFilter.cpp.o) has no symbols
204 void dummy_vpPanda3DPostProcessFilter() { };
205 
206 #endif
error that can be emitted by ViSP classes.
Definition: vpException.h:60
@ fatalError
Fatal error.
Definition: vpException.h:72
unsigned int getWidth() const
Definition: vpImage.h:242
void resize(unsigned int h, unsigned int w)
resize the image : Image initialization
Definition: vpImage.h:544
unsigned int getHeight() const
Definition: vpImage.h:181
NodePath m_renderRoot
Rendering parameters.
PointerTo< Camera > m_camera
Node containing all the objects and the camera for this renderer.
std::string m_name
Inverse of VISP_T_PANDA.
std::vector< PointerTo< GraphicsOutput > > m_buffers
NodePath of the camera.
PointerTo< WindowFramework > m_window
Rendering priority for this renderer and its buffers. A lower value will be rendered first....
int m_renderOrder
name of the renderer
vpPanda3DRenderParameters m_renderParameters
Pointer to owning window, which can create buffers etc. It is not necessarily visible.
std::string m_fragmentShader
Whether this filter is an output to be used and should be copied to ram.
virtual FrameBufferProperties getBufferProperties() const =0
static const std::string FILTER_VERTEX_SHADER
void getRenderBasic(vpImage< unsigned char > &I) const
std::shared_ptr< vpPanda3DBaseRenderer > m_inputRenderer
PointerTo< GraphicsOutput > m_buffer
virtual void setupScene() VP_OVERRIDE
Initialize the scene for this specific renderer.
void setRenderParameters(const vpPanda3DRenderParameters &params) VP_OVERRIDE
Set new rendering parameters. If the scene has already been initialized, the renderer camera is updat...
void setupRenderTarget() VP_OVERRIDE
Initialize buffers and other objects that are required to save the render.
void setupCamera() VP_OVERRIDE
Initialize camera. Should be called when the scene root of this render has already been created.
Rendering parameters for a panda3D simulation.
Definition: vpRGBf.h:64
float B
Blue component.
Definition: vpRGBf.h:157
float G
Green component.
Definition: vpRGBf.h:156
float R
Red component.
Definition: vpRGBf.h:155