Skip to content

Commit

Permalink
Support for basic filters on output textures
Browse files Browse the repository at this point in the history
  • Loading branch information
SamFlt committed Apr 29, 2024
1 parent 0cb2f04 commit ebfbdc8
Show file tree
Hide file tree
Showing 12 changed files with 331 additions and 13 deletions.
2 changes: 1 addition & 1 deletion modules/ar/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -195,7 +195,7 @@ if(USE_PANDA3D)
set(PANDA3D_MODULE_SOURCES
vpPanda3DBaseRenderer.cpp vpPanda3DGeometryRenderer.cpp
vpPanda3DRGBRenderer.cpp vpPanda3DRenderParameters.cpp
vpPanda3DRendererSet.cpp
vpPanda3DRendererSet.cpp vpPanda3DPostProcessFilter.cpp vpPanda3DCommonFilters.cpp
)
foreach(panda_src_name ${PANDA3D_MODULE_SOURCES})
vp_set_source_file_compile_flag(src/panda3d-simulator/${panda_src_name} ${PANDA3D_CXX_FLAGS})
Expand Down
25 changes: 22 additions & 3 deletions modules/ar/include/visp3/ar/vpPanda3DBaseRenderer.h
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ class VISP_EXPORT vpPanda3DBaseRenderer
{
public:
vpPanda3DBaseRenderer(const std::string &rendererName)
: m_name(rendererName), m_framework(nullptr), m_window(nullptr), m_camera(nullptr)
: m_name(rendererName), m_renderOrder(-100), m_framework(nullptr), m_window(nullptr), m_camera(nullptr)
{
setVerticalSyncEnabled(false);
}
Expand Down Expand Up @@ -121,12 +121,28 @@ class VISP_EXPORT vpPanda3DBaseRenderer
}
}

// If renderer is already initialize, modify camera properties
// If renderer is already initialized, modify camera properties
if (m_camera != nullptr) {
m_renderParameters.setupPandaCamera(m_camera);
}
}

/**
* @brief Returns true if this renderer process 3D data and its scene root can be interacted with.
*
* This value could be false, if for instance it is redefined in a subclass that performs postprocessing on a texture.
*/
virtual bool isRendering3DScene() const { return true; }

/**
* @brief Get the rendering order of this renderer.
* If a renderer A has a lower order value than B, it will be rendered before B.
* This is useful, if for instance, B is a postprocessing filter that depends on the result of B.
*
* @return int
*/
int getRenderOrder() const { return m_renderOrder; }

/**
* @brief Set the camera's pose.
* The pose is specified using the ViSP convention (Y-down right handed).
Expand Down Expand Up @@ -232,6 +248,8 @@ class VISP_EXPORT vpPanda3DBaseRenderer

void printStructure();

virtual GraphicsOutput *getMainOutputBuffer() { return nullptr; }

protected:

/**
Expand All @@ -254,13 +272,14 @@ class VISP_EXPORT vpPanda3DBaseRenderer
*/
virtual void setupRenderTarget() { }


const static vpHomogeneousMatrix VISP_T_PANDA; //! Homogeneous transformation matrix to convert from the Panda coordinate system (right-handed Z-up) to the ViSP coordinate system (right-handed Y-Down)
const static vpHomogeneousMatrix PANDA_T_VISP; //! Inverse of VISP_T_PANDA



protected:
const std::string m_name; //! name of the renderer
int m_renderOrder; //! Rendering priority for this renderer and its buffers. A lower value will be rendered first. Should be used when calling make_output in setupRenderTarget()
std::shared_ptr<PandaFramework> m_framework; //! Pointer to the active panda framework
PT(WindowFramework) m_window; //! Pointer to owning window, which can create buffers etc. It is not necessarily visible.
vpPanda3DRenderParameters m_renderParameters; //! Rendering parameters
Expand Down
24 changes: 24 additions & 0 deletions modules/ar/include/visp3/ar/vpPanda3DCommonFilters.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
#ifndef vpPanda3DCommonFilters_h
#define vpPanda3DCommonFilters_h

#include <visp3/core/vpConfig.h>

#if defined(VISP_HAVE_PANDA3D)

#include <visp3/ar/vpPanda3DPostProcessFilter.h>

class vpPanda3DRGBRenderer;

class VISP_EXPORT vpPanda3DLuminanceFilter : public vpPanda3DPostProcessFilter
{
public:
vpPanda3DLuminanceFilter(const std::string &name, std::shared_ptr<vpPanda3DRGBRenderer> &inputRenderer, bool isOutput);
FrameBufferProperties getBufferProperties() const vp_override;
void getRender(vpImage<unsigned char> &I) const;

private:
static const char *FRAGMENT_SHADER;

};
#endif
#endif
1 change: 1 addition & 0 deletions modules/ar/include/visp3/ar/vpPanda3DGeometryRenderer.h
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,7 @@ class VISP_EXPORT vpPanda3DGeometryRenderer : public vpPanda3DBaseRenderer
void getRender(vpImage<float> &depth) const;


GraphicsOutput *getMainOutputBuffer() vp_override { return m_normalDepthBuffer; }

protected:
void setupScene() vp_override;
Expand Down
47 changes: 47 additions & 0 deletions modules/ar/include/visp3/ar/vpPanda3DPostProcessFilter.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
#ifndef vpPanda3DPostProcessFilter_h
#define vpPanda3DPostProcessFilter_h

#include <visp3/core/vpConfig.h>

#if defined(VISP_HAVE_PANDA3D)
#include <visp3/ar/vpPanda3DBaseRenderer.h>
#include "cardMaker.h"
#include "orthographicLens.h"


class VISP_EXPORT vpPanda3DPostProcessFilter : public vpPanda3DBaseRenderer
{
public:
vpPanda3DPostProcessFilter(const std::string &name, const std::shared_ptr<vpPanda3DBaseRenderer> &inputRenderer, bool isOutput, std::string fragmentShader)
: vpPanda3DBaseRenderer(name), m_inputRenderer(inputRenderer), m_isOutput(isOutput), m_fragmentShader(fragmentShader)
{
m_renderOrder = m_inputRenderer->getRenderOrder() + 1;
}
bool isRendering3DScene() const vp_override
{
return false;
}

protected:
void setupScene() vp_override;

void setupCamera() vp_override;

void setupRenderTarget() vp_override;

void setRenderParameters(const vpPanda3DRenderParameters &params) vp_override;

virtual FrameBufferProperties getBufferProperties() const = 0;

std::shared_ptr<vpPanda3DBaseRenderer> m_inputRenderer;
bool m_isOutput; //! Whether this filter is an output to be used and should be copied to ram
std::string m_fragmentShader;
PT(Shader) shader;
Texture *m_texture;
GraphicsOutput *m_buffer;

static const char *FILTER_VERTEX_SHADER;
};

#endif
#endif
2 changes: 2 additions & 0 deletions modules/ar/include/visp3/ar/vpPanda3DRGBRenderer.h
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,8 @@ class VISP_EXPORT vpPanda3DRGBRenderer : public vpPanda3DBaseRenderer, public vp

void addNodeToScene(const NodePath &object) vp_override;

GraphicsOutput *getMainOutputBuffer() vp_override { return m_colorBuffer; }

protected:
void setupScene() vp_override;
void setupRenderTarget() vp_override;
Expand Down
12 changes: 11 additions & 1 deletion modules/ar/include/visp3/ar/vpPanda3DRendererSet.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,8 +47,10 @@ class VISP_EXPORT vpPanda3DRendererSet : public vpPanda3DBaseRenderer, public vp
virtual ~vpPanda3DRendererSet();

/**
* @brief Initialize the framework and propagate the created panda3D framework to the subrenderers
* @brief Initialize the framework and propagate the created panda3D framework to the subrenderers.
*
* The subrenderers will be initialized in the order of their priority as defined by vpPanda3DBaseRenderer::getRenderOrder
* Thus, if a renderer B depends on A for its render, and if B.getRenderOrder() > A.getRenderOrder() it can rely on A being initialized when B.initFromParent is called (along with the setupCamera, setupRenderTarget).
*/
void initFramework() vp_override;

Expand Down Expand Up @@ -110,12 +112,20 @@ class VISP_EXPORT vpPanda3DRendererSet : public vpPanda3DBaseRenderer, public vp
*/
vpHomogeneousMatrix getNodePose(NodePath &object) vp_override;

/**
* \warn this method is not supported and will throw
*/
void addNodeToScene(const NodePath &object) vp_override;

void setRenderParameters(const vpPanda3DRenderParameters &params) vp_override;

void addLight(const vpPanda3DLight &light) vp_override;

/**
* @brief Add a new subrenderer
*
* @param renderer
*/
void addSubRenderer(std::shared_ptr<vpPanda3DBaseRenderer> renderer);

template<typename RendererType>
Expand Down
56 changes: 56 additions & 0 deletions modules/ar/src/panda3d-simulator/vpPanda3DCommonFilters.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
#include <visp3/ar/vpPanda3DCommonFilters.h>
#include <visp3/ar/vpPanda3DRGBRenderer.h>

#if defined(VISP_HAVE_PANDA3D)

const char *vpPanda3DLuminanceFilter::FRAGMENT_SHADER = R"shader(
#version 330
in vec2 texcoords;
out vec4 p3d_FragData;
uniform sampler2D p3d_Texture0;
void main() {
vec4 v = texture(p3d_Texture0, texcoords);
p3d_FragData.b = 0.299 * v.r + 0.587 * v.g + 0.114 * v.b;
}
)shader";


vpPanda3DLuminanceFilter::vpPanda3DLuminanceFilter(const std::string &name, std::shared_ptr<vpPanda3DRGBRenderer> &inputRenderer, bool isOutput)
: vpPanda3DPostProcessFilter(name, inputRenderer, isOutput, std::string(vpPanda3DLuminanceFilter::FRAGMENT_SHADER))
{

}
FrameBufferProperties vpPanda3DLuminanceFilter::getBufferProperties() const
{
FrameBufferProperties fbp;
fbp.set_depth_bits(0);
fbp.set_rgba_bits(0, 0, 8, 0);
fbp.set_float_color(false);
return fbp;
}
void vpPanda3DLuminanceFilter::getRender(vpImage<unsigned char> &I) const
{
if (!m_isOutput) {
throw vpException(vpException::fatalError, "Tried to fetch output of a postprocessing filter that was configured as an intermediate output");
}
unsigned indexMultiplier = m_texture->get_num_components(); // we ask for only 8 bits image, but we may get an rgb image
I.resize(m_texture->get_y_size(), m_texture->get_x_size());
unsigned char *data = (unsigned char *)(&(m_texture->get_ram_image().front()));
if (indexMultiplier != 1) {
for (unsigned int i = 0; i < I.getSize(); ++i) {
I.bitmap[i] = data[i * indexMultiplier];
}
}
else {
memcpy(I.bitmap, &data[0], I.getSize() * sizeof(unsigned char));
}
}



#endif
114 changes: 114 additions & 0 deletions modules/ar/src/panda3d-simulator/vpPanda3DPostProcessFilter.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,114 @@
#include <visp3/ar/vpPanda3DPostProcessFilter.h>


#if defined(VISP_HAVE_PANDA3D)

const char *vpPanda3DPostProcessFilter::FILTER_VERTEX_SHADER = R"shader(
#version 330
in vec4 p3d_Vertex;
uniform mat4 p3d_ModelViewProjectionMatrix;
in vec2 p3d_MultiTexCoord0;
out vec2 texcoords;
void main()
{
gl_Position = p3d_ModelViewProjectionMatrix * p3d_Vertex;
texcoords = p3d_MultiTexCoord0;
}
)shader";


void vpPanda3DPostProcessFilter::setupScene()
{
CardMaker cm("cm");
cm.set_frame_fullscreen_quad();
m_renderRoot = NodePath(cm.generate()); // Render root is a 2D rectangle
m_renderRoot.set_depth_test(false);
m_renderRoot.set_depth_write(false);
GraphicsOutput *buffer = m_inputRenderer->getMainOutputBuffer();
if (buffer == nullptr) {
throw vpException(vpException::fatalError,
"Cannot add a postprocess filter to a renderer that does not define getMainOutputBuffer()");
}
shader = Shader::make(Shader::ShaderLanguage::SL_GLSL,
FILTER_VERTEX_SHADER,
m_fragmentShader);
m_renderRoot.set_shader(shader);
std::cout << m_fragmentShader << std::endl;
m_renderRoot.set_texture(buffer->get_texture());
m_renderRoot.set_attrib(LightRampAttrib::make_identity());
}

void vpPanda3DPostProcessFilter::setupCamera()
{
m_cameraPath = m_window->make_camera();
m_camera = (Camera *)m_cameraPath.node();
PT(OrthographicLens) lens = new OrthographicLens();
lens->set_film_size(2, 2);
lens->set_film_offset(0, 0);
lens->set_near_far(-1000, 1000);
m_camera->set_lens(lens);
m_cameraPath = m_renderRoot.attach_new_node(m_camera);
m_camera->set_scene(m_renderRoot);
}

void vpPanda3DPostProcessFilter::setupRenderTarget()
{

if (m_window == nullptr) {
throw vpException(vpException::fatalError, "Cannot setup render target when window is null");
}
FrameBufferProperties fbp = getBufferProperties();
WindowProperties win_prop;
win_prop.set_size(m_renderParameters.getImageWidth(), m_renderParameters.getImageHeight());

// Don't open a window - force it to be an offscreen buffer.
int flags = GraphicsPipe::BF_refuse_window | GraphicsPipe::BF_resizeable;
GraphicsOutput *windowOutput = m_window->get_graphics_output();
GraphicsEngine *engine = windowOutput->get_engine();
GraphicsStateGuardian *gsg = windowOutput->get_gsg();
GraphicsPipe *pipe = windowOutput->get_pipe();
m_buffer = engine->make_output(pipe, m_name, m_renderOrder,
fbp, win_prop, flags,
gsg, windowOutput);
if (m_buffer == nullptr) {
throw vpException(vpException::fatalError, "Could not create buffer");
}
m_buffers.push_back(m_buffer);
m_buffer->set_inverted(gsg->get_copy_texture_inverted());
m_texture = new Texture();
//fbp.setup_color_texture(m_texture);
m_buffer->add_render_texture(m_texture, m_isOutput ? GraphicsOutput::RenderTextureMode::RTM_copy_ram : GraphicsOutput::RenderTextureMode::RTM_copy_texture);
m_buffer->set_clear_color(LColor(0.f));
m_buffer->set_clear_color_active(true);
DisplayRegion *region = m_buffer->make_display_region();
if (region == nullptr) {
throw vpException(vpException::fatalError, "Could not create display region");
}
region->set_camera(m_cameraPath);
region->set_clear_color(LColor(0.f));
}

void vpPanda3DPostProcessFilter::setRenderParameters(const vpPanda3DRenderParameters &params)
{
m_renderParameters = params;
unsigned int previousH = m_renderParameters.getImageHeight(), previousW = m_renderParameters.getImageWidth();
bool resize = previousH != params.getImageHeight() || previousW != params.getImageWidth();

m_renderParameters = params;

if (resize) {
for (GraphicsOutput *buffer: m_buffers) {
//buffer->get_type().is_derived_from()
GraphicsBuffer *buf = dynamic_cast<GraphicsBuffer *>(buffer);
if (buf == nullptr) {
throw vpException(vpException::fatalError, "Panda3D: could not cast to GraphicsBuffer when rendering.");
}
else {
buf->set_size(m_renderParameters.getImageWidth(), m_renderParameters.getImageHeight());
}
}
}
}

#endif
2 changes: 1 addition & 1 deletion modules/ar/src/panda3d-simulator/vpPanda3DRGBRenderer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -267,7 +267,7 @@ void vpPanda3DRGBRenderer::setupRenderTarget()
GraphicsEngine *engine = windowOutput->get_engine();
GraphicsStateGuardian *gsg = windowOutput->get_gsg();
GraphicsPipe *pipe = windowOutput->get_pipe();
m_colorBuffer = engine->make_output(pipe, "Color Buffer", -100,
m_colorBuffer = engine->make_output(pipe, "Color Buffer", m_renderOrder,
fbp, win_prop, flags,
gsg, windowOutput);
if (m_colorBuffer == nullptr) {
Expand Down
Loading

0 comments on commit ebfbdc8

Please sign in to comment.