Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Modifications for the upcoming Render-Based Tracking submodule #1456

Merged
merged 27 commits into from
Sep 6, 2024
Merged
Show file tree
Hide file tree
Changes from 22 commits
Commits
Show all changes
27 commits
Select commit Hold shift + click to select a range
f562950
merge sinatrack changes
SamFlt Aug 6, 2024
d845b40
Remove attempts at UKF, fix some stuff for python
SamFlt Aug 23, 2024
53abcc9
[Panda3D] Improve tutorial documentation, try to fix incorrect memory…
SamFlt Aug 26, 2024
ccc47d2
Trying to replace alternated ram fetch with a unified block of extrac…
SamFlt Aug 27, 2024
b08fa4e
Remove debug print
SamFlt Aug 27, 2024
475cc34
rename normals_world shader to normals_object, to better reflect the …
SamFlt Aug 28, 2024
6b9e0bf
small optimization on normal rendering
SamFlt Aug 28, 2024
094e740
simplify normals shader
SamFlt Aug 28, 2024
12711d9
Merge branch 'fix_sinatrack' of github.com:SamFlt/visp into fix_sinat…
SamFlt Aug 28, 2024
e73c1d7
update Clipping distance computation that was wrongly calculated
SamFlt Aug 28, 2024
d32922e
Introduce getRender overload to write into a bounding box in an image
SamFlt Aug 28, 2024
cc1b82c
remove merge tag in render set, add missing include directive
SamFlt Aug 28, 2024
c8bb06a
clean old comment, add yet another missing header include directive
SamFlt Aug 28, 2024
1c653df
Remove tuple usage to be C++98 conforming
SamFlt Aug 29, 2024
3accaa3
Added Display grid functionality
SamFlt Aug 29, 2024
5cc61bc
Merge remote-tracking branch 'upstream/master' into fix_sinatrack
SamFlt Aug 29, 2024
1d438a7
Move local struct outside of function
SamFlt Aug 29, 2024
8e71f15
Further fixes for C++98
SamFlt Aug 29, 2024
9378dff
Add move assignment operator, fixed the copy operator using pass by v…
SamFlt Aug 30, 2024
62debb6
Fix move operator
SamFlt Aug 30, 2024
7dc52e3
Fix potential ownership issue on assignement operator with const ref
SamFlt Aug 30, 2024
9f37c9e
Introduce flag in JSON argument parser
SamFlt Aug 30, 2024
51c7cca
Clean code by removing empty lines and code indentation
fspindle Sep 3, 2024
a4bec8d
Fix warning: lambda capture 'parameter' is not used
fspindle Sep 3, 2024
c0b228b
Fix warning: unused vars
fspindle Sep 3, 2024
f025d37
Doxygen warnings fixes and rendering with Panda3D tutorial updates
fspindle Sep 3, 2024
983d558
Using Panda's managed pointer for texture and buffers to avoid memory…
SamFlt Sep 5, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
65 changes: 58 additions & 7 deletions doc/tutorial/rendering/tutorial-panda3d.dox
Original file line number Diff line number Diff line change
Expand Up @@ -165,31 +165,82 @@ vpPanda3DBaseRenderer, which implements basic functions for a panda renderer.

- Installer are available for Windows browsing the [download](https://www.panda3d.org/download/) page.

\section tutorial-panda3d-usage Rendere based on Panda3D usage
\section tutorial-panda3d-usage Using Panda3D for rendering

An example that shows how to exploit Panda3D in ViSP to render a color image with support for textures and lighting, a
depth image, normals in world space and in camera space is given in tutorial-panda3d-renderer.cpp.
depth image, normals in object space and in camera space is given in tutorial-panda3d-renderer.cpp.

Here you will find the code used to create the renderer:

To start rendering, we first instanciate a vpPanda3DRendererSet. This object allows to render multiple modalities (color, depth, etc.) in a single pass.
To add different rendering modalities, we will use subclasses that will be registered to the renderer set.
Internally, each sub renderer has its own scene: the renderer set synchronizes everything when the state changes (i.e, an object is added, an object is moved or the camera parameters change.)

A panda3D renderer should be instanciated with a vpPanda3DRenderParameters object. This object defines:
- The camera intrinsics (see vpCameraParameters): As of now, Only parameters for a distortion free model are supported
- The image resolution
- The near and far clipping plane values. Object parts that are too close (less than the near clipping value) or too far (greater than the far clipping value) will not be rendered.

The creation of the renderer set can be found below
\snippet tutorial-panda3d-renderer.cpp Renderer set

Here you will find the code used to create the sub renderers:

To actually render color, normals, etc., we need to define subrenderers:
\snippet tutorial-panda3d-renderer.cpp Subrenderers init

Here you will find the code used to add the sub renderers to the main renderer:
The different subrenderers are:

- vpPanda3DGeometryRenderer instances allow to retrieve 3D information about the object: these are the surface normals in the object or camera frame, as well as the depth information.
- vpPanda3DRGBRenderer objects perform the traditional color rendering. Lighting interaction can be disable, as is the case for the second renderer (diffuse only).
- Post processing renderers, such as vpPanda3DLuminanceFilter, vpPanda3DCanny, operate on the output image of another renderer. They can be used to further process the output data and can be chained together.
In this case, the chain vpPanda3DLuminanceFilter -> vpPanda3DGaussianBlur -> vpPanda3DCanny will perform a canny edge detection (without hysteresis) on a blurred, grayscale image.

For these subrenderers to actually be useful, they should be added to the main renderer:
\snippet tutorial-panda3d-renderer.cpp Adding subrenderers

\warning Once they have been added, a call to vpPanda3DBaseRenderer::initFramework() should be performed. Otherwise, no rendering will be performed and objects will not be loaded.

Here you will find the code used to configure the scene:
\snippet tutorial-panda3d-renderer.cpp Scene configuration

We start by loading the object to render with vpPanda3DBaseRenderer::loadObject, followed by vpPanda3DBaseRenderer::addNodeToScene.
For the Color-based renderer, we add lights to shade our object. Different light types are supported, reusing the available Panda3D features.

Once the scene is setup, we can start rendering. This will be performed in a loop.

The first step shown is the following:
\snippet tutorial-panda3d-renderer.cpp Updating render parameters

Each frame, we compute the values of the clipping planes, and update the rendering properties. This will ensure that the target object is visible.
Depending on your use case, this may not be necessary.

Once this is done, we can call upon Panda3D to render the object with
\snippet tutorial-panda3d-renderer.cpp Render frame

\note Note that under the hood, all subrenderers rely on the same Panda3D "framework": calling renderFrame on one will call it for the others.

To use the renders, we must convert them to ViSP images.
To do so, each subrenderer defines its own *getRender* method, that will perform the conversion from a panda texture to the relevant ViSP data type.

For each render type, we start by getting the correct renderer via the vpPanda3DRendererSet::getRenderer, then call its *getRender* method.
\snippet tutorial-panda3d-renderer.cpp Fetch render

Now that we have the retrieved the images, we can display them. To do so, we leverage utility functions defined beforehand (see the full code for more information). This may be required in cases where the data cannot be directly displayed.
For instance, normals are encoded as 3 32-bit floats, but displays require colors to be represented as 8-bit unsigned characters.
The same goes for the depth render, which is mapped back to the 0-255 range, although its value unbound.
\snippet tutorial-panda3d-renderer.cpp Display

Finally, we use the snippet below to move the object, updating the scene.
To have a constant velocity, we multiply the displacement by the time that has elapsed between the frame's start and end.
\snippet tutorial-panda3d-renderer.cpp Move object

\section tutorial-panda3d-full-code Tutorial full code

The full code of tutorial-panda3d-renderer.cpp is given below.
\include tutorial-panda3d-renderer.cpp

\section tutorial-panda3d-run Execute the tutorial
\section tutorial-panda3d-run Running the tutorial

- Once ViSP is build, you may run the tutorial by:
- Once ViSP is built, you may run the tutorial by:
\code{.sh}
$ cd $VISP_WS/visp-build
$ ./tutorial/ar/tutorial-panda3d-renderer
Expand Down
69 changes: 32 additions & 37 deletions modules/ar/include/visp3/ar/vpPanda3DBaseRenderer.h
Original file line number Diff line number Diff line change
Expand Up @@ -71,17 +71,18 @@ class VISP_EXPORT vpPanda3DBaseRenderer
* Will also perform the renderer setup (scene, camera and render targets)
*/
virtual void initFramework();
virtual void initFromParent(std::shared_ptr<PandaFramework> framework, PointerTo<WindowFramework> window);
virtual void initFromParent(const vpPanda3DBaseRenderer &renderer);

/**
* @brief
*
* @param framework
* @param window
*/
void initFromParent(std::shared_ptr<PandaFramework> framework, std::shared_ptr<WindowFramework> window);


virtual void beforeFrameRendered() { }
virtual void renderFrame();
virtual void afterFrameRendered()
{
GraphicsOutput *mainBuffer = getMainOutputBuffer();
if (mainBuffer != nullptr) {
m_framework->get_graphics_engine()->extract_texture_data(mainBuffer->get_texture(), mainBuffer->get_gsg());
}
}

/**
* @brief Get the name of the renderer
Expand All @@ -90,6 +91,8 @@ class VISP_EXPORT vpPanda3DBaseRenderer
*/
const std::string &getName() const { return m_name; }

void setName(const std::string &name) { m_name = name; }

/**
* @brief Get the scene root
*
Expand All @@ -101,31 +104,7 @@ class VISP_EXPORT vpPanda3DBaseRenderer
*
* @param params the new rendering parameters
*/
virtual void setRenderParameters(const vpPanda3DRenderParameters &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());
}
}
}

// If renderer is already initialized, modify camera properties
if (m_camera != nullptr) {
m_renderParameters.setupPandaCamera(m_camera);
}
}
virtual void setRenderParameters(const vpPanda3DRenderParameters &params);

/**
* @brief Returns true if this renderer process 3D data and its scene root can be interacted with.
Expand All @@ -143,6 +122,15 @@ class VISP_EXPORT vpPanda3DBaseRenderer
*/
int getRenderOrder() const { return m_renderOrder; }

void setRenderOrder(int order)
{
int previousOrder = m_renderOrder;
m_renderOrder = order;
for (GraphicsOutput *buffer: m_buffers) {
buffer->set_sort(buffer->get_sort() + (order - previousOrder));
}
}

/**
* @brief Set the camera's pose.
* The pose is specified using the ViSP convention (Y-down right handed).
Expand Down Expand Up @@ -206,8 +194,10 @@ class VISP_EXPORT vpPanda3DBaseRenderer
* @param name name of the node that should be used to compute near and far values.
* @param near resulting near clipping plane distance
* @param far resulting far clipping plane distance
* @param fast Whether to use the axis align bounding box to compute the clipping planes.
* This is faster than reprojecting the full geometry in the camera frame
*/
void computeNearAndFarPlanesFromNode(const std::string &name, float &near, float &far);
void computeNearAndFarPlanesFromNode(const std::string &name, float &near, float &far, bool fast);

/**
* @brief Load a 3D object. To load an .obj file, Panda3D must be compiled with assimp support.
Expand Down Expand Up @@ -250,8 +240,13 @@ class VISP_EXPORT vpPanda3DBaseRenderer

virtual GraphicsOutput *getMainOutputBuffer() { return nullptr; }

virtual void enableSharedDepthBuffer(vpPanda3DBaseRenderer &sourceBuffer);



protected:


/**
* @brief Initialize the scene for this specific renderer.
*
Expand All @@ -278,10 +273,10 @@ class VISP_EXPORT vpPanda3DBaseRenderer


protected:
const std::string m_name; //! name of the renderer
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
std::shared_ptr<WindowFramework> m_window; //! Pointer to owning window, which can create buffers etc. It is not necessarily visible.
PointerTo<WindowFramework> m_window; //! Pointer to owning window, which can create buffers etc. It is not necessarily visible.
vpPanda3DRenderParameters m_renderParameters; //! Rendering parameters
NodePath m_renderRoot; //! Node containing all the objects and the camera for this renderer
PointerTo<Camera> m_camera;
Expand Down
6 changes: 5 additions & 1 deletion modules/ar/include/visp3/ar/vpPanda3DGeometryRenderer.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@
#if defined(VISP_HAVE_PANDA3D)
#include <visp3/core/vpCameraParameters.h>
#include <visp3/core/vpImage.h>
#include <visp3/core/vpRect.h>
#include <visp3/ar/vpPanda3DBaseRenderer.h>

BEGIN_VISP_NAMESPACE
Expand Down Expand Up @@ -71,6 +72,8 @@ class VISP_EXPORT vpPanda3DGeometryRenderer : public vpPanda3DBaseRenderer
*/
void getRender(vpImage<vpRGBf> &colorData, vpImage<float> &depth) const;

void getRender(vpImage<vpRGBf> &normals, vpImage<float> &depth, const vpRect &bb, unsigned int h, unsigned w) const;

/**
* @brief Get render results into ViSP readable structures. This version only retrieves the normal data
* @param colorData Depending on the vpRenderType, normals in the world or camera frame may be stored in this image.
Expand All @@ -84,6 +87,7 @@ class VISP_EXPORT vpPanda3DGeometryRenderer : public vpPanda3DBaseRenderer

GraphicsOutput *getMainOutputBuffer() VP_OVERRIDE { return m_normalDepthBuffer; }


protected:
void setupScene() VP_OVERRIDE;
void setupRenderTarget() VP_OVERRIDE;
Expand All @@ -93,7 +97,7 @@ class VISP_EXPORT vpPanda3DGeometryRenderer : public vpPanda3DBaseRenderer
Texture *m_normalDepthTexture;
GraphicsOutput *m_normalDepthBuffer;

static const char *SHADER_VERT_NORMAL_AND_DEPTH_WORLD;
static const char *SHADER_VERT_NORMAL_AND_DEPTH_OBJECT;
static const char *SHADER_VERT_NORMAL_AND_DEPTH_CAMERA;
static const char *SHADER_FRAG_NORMAL_AND_DEPTH;

Expand Down
1 change: 0 additions & 1 deletion modules/ar/include/visp3/ar/vpPanda3DLight.h
Original file line number Diff line number Diff line change
Expand Up @@ -209,7 +209,6 @@ class VISP_EXPORT vpPanda3DDirectionalLight : public vpPanda3DLight
PT(DirectionalLight) light = new DirectionalLight(m_name);
light->set_color(LColor(m_color.R, m_color.G, m_color.B, 1));
vpColVector dir = vpPanda3DBaseRenderer::vispVectorToPanda(m_direction);
std::cout << m_direction << ", " << dir << std::endl;
light->set_direction(LVector3f(m_direction[0], m_direction[1], m_direction[2]));
NodePath np = scene.attach_new_node(light);
scene.set_light(np);
Expand Down
14 changes: 14 additions & 0 deletions modules/ar/include/visp3/ar/vpPanda3DPostProcessFilter.h
Original file line number Diff line number Diff line change
Expand Up @@ -62,13 +62,27 @@ class VISP_EXPORT vpPanda3DPostProcessFilter : public vpPanda3DBaseRenderer
m_renderOrder = m_inputRenderer->getRenderOrder() + 1;
}

~vpPanda3DPostProcessFilter()
{
// delete m_texture;
// delete m_buffer;
}
fspindle marked this conversation as resolved.
Show resolved Hide resolved

bool isRendering3DScene() const VP_OVERRIDE
{
return false;
}

GraphicsOutput *getMainOutputBuffer() VP_OVERRIDE { return m_buffer; }

void afterFrameRendered() VP_OVERRIDE
{
if (m_isOutput) {
vpPanda3DBaseRenderer::afterFrameRendered();
}
}


protected:
virtual void setupScene() VP_OVERRIDE;

Expand Down
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 @@ -98,8 +98,10 @@ class VISP_EXPORT vpPanda3DRGBRenderer : public vpPanda3DBaseRenderer, public vp


protected:

void setupScene() VP_OVERRIDE;
void setupRenderTarget() VP_OVERRIDE;

virtual std::string makeFragmentShader(bool hasTexture, bool specular);

private:
Expand Down
21 changes: 19 additions & 2 deletions modules/ar/include/visp3/ar/vpPanda3DRendererSet.h
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,8 @@ class VISP_EXPORT vpPanda3DRendererSet : public vpPanda3DBaseRenderer, public vp
* 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;
void initFromParent(std::shared_ptr<PandaFramework> framework, PointerTo<WindowFramework> window) VP_OVERRIDE;
void initFromParent(const vpPanda3DBaseRenderer &renderer) VP_OVERRIDE;

/**
* @brief Set the pose of the camera, using the ViSP convention. This change is propagated to all subrenderers
Expand Down Expand Up @@ -134,7 +136,7 @@ class VISP_EXPORT vpPanda3DRendererSet : public vpPanda3DBaseRenderer, public vp
*/
void addNodeToScene(const NodePath &object) VP_OVERRIDE;

void setRenderParameters(const vpPanda3DRenderParameters &params) VP_OVERRIDE;
virtual void setRenderParameters(const vpPanda3DRenderParameters &params) VP_OVERRIDE;

void addLight(const vpPanda3DLight &light) VP_OVERRIDE;

Expand All @@ -147,6 +149,9 @@ class VISP_EXPORT vpPanda3DRendererSet : public vpPanda3DBaseRenderer, public vp
*/
void addSubRenderer(std::shared_ptr<vpPanda3DBaseRenderer> renderer);

void enableSharedDepthBuffer(vpPanda3DBaseRenderer &sourceBuffer) VP_OVERRIDE;


/**
* @brief Retrieve the first subrenderer with the specified template type.
*
Expand Down Expand Up @@ -185,12 +190,24 @@ class VISP_EXPORT vpPanda3DRendererSet : public vpPanda3DBaseRenderer, public vp
return nullptr;
}

void beforeFrameRendered() VP_OVERRIDE
{
for (std::shared_ptr<vpPanda3DBaseRenderer> &renderer: m_subRenderers) {
renderer->beforeFrameRendered();
}
}
void afterFrameRendered() VP_OVERRIDE
{
for (std::shared_ptr<vpPanda3DBaseRenderer> &renderer: m_subRenderers) {
renderer->afterFrameRendered();
}
}

protected:
void setupScene() VP_OVERRIDE { }

void setupCamera() VP_OVERRIDE { }

private:
std::vector<std::shared_ptr<vpPanda3DBaseRenderer>> m_subRenderers;
};
END_VISP_NAMESPACE
Expand Down
Loading
Loading