Skip to content

Commit

Permalink
Add an interface to add lights to the scene
Browse files Browse the repository at this point in the history
  • Loading branch information
SamFlt committed Apr 23, 2024
1 parent ca6b537 commit 1d88517
Show file tree
Hide file tree
Showing 8 changed files with 162 additions and 21 deletions.
5 changes: 5 additions & 0 deletions modules/ar/include/visp3/ar/vpPanda3DBaseRenderer.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@
#include <visp3/core/vpConfig.h>

#if defined(VISP_HAVE_PANDA3D)
#include <visp3/core/vpPoint.h>
#include <visp3/core/vpCameraParameters.h>
#include <visp3/ar/vpPanda3DRenderParameters.h>

Expand Down Expand Up @@ -225,6 +226,10 @@ class VISP_EXPORT vpPanda3DBaseRenderer
void setAbortOnPandaError(bool abort);
void setForcedInvertTextures(bool invert);

static vpPoint vispPointToPanda(const vpPoint &point);

void printStructure();

protected:

/**
Expand Down
102 changes: 102 additions & 0 deletions modules/ar/include/visp3/ar/vpPanda3DLight.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,102 @@
#ifndef vpPand3DLight_h
#define vpPand3DLight_h

#include <visp3/core/vpConfig.h>

#if defined(VISP_HAVE_PANDA3D)

#include <string>
#include <visp3/core/vpPoint.h>
#include <visp3/core/vpRGBf.h>
#include <visp3/ar/vpPanda3DBaseRenderer.h>
#include "nodePath.h"
#include "ambientLight.h"
#include "directionalLight.h"
#include "pointLight.h"



class VISP_EXPORT vpPanda3DLight
{
public:
vpPanda3DLight(const std::string &name, const vpRGBf &color) : m_name(name), m_color(color) { }

const std::string &getName() const { return m_name; }
const vpRGBf &getColor() const { return m_color; }
virtual void addToScene(NodePath &scene) const = 0;

protected:
std::string m_name;
vpRGBf m_color;
};

class VISP_EXPORT vpPanda3DAmbientLight : public vpPanda3DLight
{
public:
vpPanda3DAmbientLight(const std::string &name, const vpRGBf &color) : vpPanda3DLight(name, color) { }
void addToScene(NodePath &scene) const vp_override
{
PT(AmbientLight) light = new AmbientLight(m_name);
light->set_color(LColor(m_color.R, m_color.G, m_color.B, 1));
NodePath alnp = scene.attach_new_node(light);
scene.set_light(alnp);
}
};

class VISP_EXPORT vpPanda3DPointLight : public vpPanda3DLight
{
public:
vpPanda3DPointLight(const std::string &name, const vpRGBf &color, const vpColVector &position) : vpPanda3DLight(name, color), m_position(position)
{
if (position.size() != 3) {
throw vpException(vpException::dimensionError, "Point light position must be a 3 dimensional vector");
}
}
void addToScene(NodePath &scene) const vp_override
{
PT(PointLight) light = new PointLight(m_name);
light->set_color(LColor(m_color.R, m_color.G, m_color.B, 1));
NodePath np = scene.attach_new_node(light);
vpPoint posPanda = vpPanda3DBaseRenderer::vispPointToPanda(m_position);
np.set_pos(posPanda.get_X(), posPanda.get_Y(), posPanda.get_Z());
scene.set_light(np);
}
private:
const vpPoint m_position;
};

class VISP_EXPORT vpPanda3DLightable
{
public:
virtual ~vpPanda3DLightable() = default;
virtual void addLight(const vpPanda3DLight &light) = 0;
};

class VISP_EXPORT vpPanda3DLightableScene : public vpPanda3DLightable
{
public:
vpPanda3DLightableScene() : vpPanda3DLightable()
{ }

vpPanda3DLightableScene(NodePath &scene) : vpPanda3DLightable(), m_lightableScene(scene)
{ }



void addLight(const vpPanda3DLight &light) vp_override
{
if (m_lightableScene.is_empty()) {
throw vpException(vpException::notInitialized, "Tried to add a light to a scene that is not initialized.");
}
light.addToScene(m_lightableScene);
}
protected:
void setLightableScene(NodePath &scene) { m_lightableScene = scene; }
private:
NodePath m_lightableScene;
};



#endif
#endif
7 changes: 3 additions & 4 deletions modules/ar/include/visp3/ar/vpPanda3DRGBRenderer.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,11 +37,10 @@
#if defined(VISP_HAVE_PANDA3D)

#include <visp3/ar/vpPanda3DBaseRenderer.h>
#include <visp3/ar/vpPanda3DLight.h>
#include <visp3/core/vpImage.h>

#include <directionalLight.h>

class VISP_EXPORT vpPanda3DRGBRenderer : public vpPanda3DBaseRenderer
class VISP_EXPORT vpPanda3DRGBRenderer : public vpPanda3DBaseRenderer, public vpPanda3DLightableScene
{
public:
vpPanda3DRGBRenderer() : vpPanda3DBaseRenderer("RGB") { }
Expand All @@ -56,7 +55,7 @@ class VISP_EXPORT vpPanda3DRGBRenderer : public vpPanda3DBaseRenderer
void getRender(vpImage<vpRGBa> &I) const;

protected:

void setupScene() vp_override;
void setupRenderTarget() vp_override;

private:
Expand Down
5 changes: 4 additions & 1 deletion modules/ar/include/visp3/ar/vpPanda3DRendererSet.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,9 @@
#include <vector>

#include <visp3/ar/vpPanda3DBaseRenderer.h>
#include <visp3/ar/vpPanda3DLight.h>

class VISP_EXPORT vpPanda3DRendererSet : public vpPanda3DBaseRenderer
class VISP_EXPORT vpPanda3DRendererSet : public vpPanda3DBaseRenderer, public vpPanda3DLightable
{
public:
vpPanda3DRendererSet(const vpPanda3DRenderParameters &renderParameters);
Expand Down Expand Up @@ -114,6 +115,8 @@ class VISP_EXPORT vpPanda3DRendererSet : public vpPanda3DBaseRenderer

void setRenderParameters(const vpPanda3DRenderParameters &params) vp_override;

void addLight(const vpPanda3DLight& light) vp_override;

void addSubRenderer(std::shared_ptr<vpPanda3DBaseRenderer> renderer);

template<typename RendererType>
Expand Down
10 changes: 10 additions & 0 deletions modules/ar/src/panda3d-simulator/vpPanda3DBaseRenderer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -202,7 +202,17 @@ void vpPanda3DBaseRenderer::setForcedInvertTextures(bool invert)
else {
load_prc_file_data("", "copy-texture-inverted 0");
}
}

vpPoint vpPanda3DBaseRenderer::vispPointToPanda(const vpPoint &point)
{
return PANDA_T_VISP * point;
}

void vpPanda3DBaseRenderer::printStructure()
{
m_renderRoot.ls();
}


#endif
6 changes: 6 additions & 0 deletions modules/ar/src/panda3d-simulator/vpPanda3DRGBRenderer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,12 @@ void vpPanda3DRGBRenderer::getRender(vpImage<vpRGBa> &I) const
// memcpy(I.bitmap, data, sizeof(unsigned char) * I.getSize() * 4);
}

void vpPanda3DRGBRenderer::setupScene()
{
vpPanda3DBaseRenderer::setupScene();
setLightableScene(m_renderRoot);
}

void vpPanda3DRGBRenderer::setupRenderTarget()
{
FrameBufferProperties fbp;
Expand Down
10 changes: 10 additions & 0 deletions modules/ar/src/panda3d-simulator/vpPanda3DRendererSet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -117,6 +117,16 @@ void vpPanda3DRendererSet::setRenderParameters(const vpPanda3DRenderParameters &
}
}

void vpPanda3DRendererSet::addLight(const vpPanda3DLight &light)
{
for (std::shared_ptr<vpPanda3DBaseRenderer> &renderer: m_subRenderers) {
vpPanda3DLightable *lightable = dynamic_cast<vpPanda3DLightable *>(renderer.get());
if (lightable != nullptr) {
lightable->addLight(light);
}
}
}

void vpPanda3DRendererSet::addSubRenderer(std::shared_ptr<vpPanda3DBaseRenderer> renderer)
{
for (std::shared_ptr<vpPanda3DBaseRenderer> &otherRenderer: m_subRenderers) {
Expand Down
38 changes: 22 additions & 16 deletions tutorial/ar/tutorial-panda3d-renderer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ int main(int argc, const char **argv)
}

std::cout << "Initializing framework" << std::endl;
renderer.initFramework(false);
renderer.initFramework(true);

std::cout << "Loading object" << std::endl;
NodePath object = renderer.loadObject(objectName, modelPath);
Expand All @@ -109,16 +109,12 @@ int main(int argc, const char **argv)
renderer.addNodeToScene(object);

// rgbRenderer->getRenderRoot().set_shader_auto(100);
PT(AmbientLight) alight = new AmbientLight("ambient");
alight->set_color(LColor(0.2, 0.2, 0.2, 1));
NodePath alnp = rgbRenderer->getRenderRoot().attach_new_node(alight);
rgbRenderer->getRenderRoot().set_light(alnp);
PT(PointLight) plight = new PointLight("sun");
plight->set_color(LColor(2.0, 2.0, 2.0, 1));
NodePath plnp = rgbRenderer->getRenderRoot().attach_new_node(plight);
plnp.set_pos(0.4, -0.5, 0.1);
rgbRenderer->getRenderRoot().set_light(plnp);
vpPanda3DAmbientLight alight("Ambient", vpRGBf(0.2));
renderer.addLight(alight);
vpPanda3DPointLight plight("Point", vpRGBf(50.0), vpColVector({ 0.4, -0.5, -0.5 }));
renderer.addLight(plight);

rgbRenderer->printStructure();
std::cout << "Setting camera pose" << std::endl;
renderer.setCameraPose(vpHomogeneousMatrix(0.0, 0.0, -0.5, 0.0, 0.0, 0.0));

Expand Down Expand Up @@ -148,8 +144,9 @@ int main(int argc, const char **argv)
DisplayCls dNormalsCamera(cameraNormalDisplayImage, 0, renderParams.getImageHeight() + 80, "normals in camera space");
DisplayCls dDepth(depthDisplayImage, renderParams.getImageWidth() + 80, 0, "depth");
DisplayCls dColor(colorImage, renderParams.getImageWidth() * 2 + 90, 0, "color");

renderer.renderFrame();
bool end = false;
bool firstFrame = true;
std::vector<double> renderTime, fetchTime, displayTime;
while (!end) {
float near = 0, far = 0;
Expand All @@ -163,7 +160,6 @@ int main(int argc, const char **argv)
renderer.renderFrame();

const double beforeFetch = vpTime::measureTimeMs();

renderer.getRenderer<vpPanda3DGeometryRenderer>(geometryRenderer->getName())->getRender(normalsImage, depthImage);
renderer.getRenderer<vpPanda3DGeometryRenderer>(cameraRenderer->getName())->getRender(cameraNormalsImage);
renderer.getRenderer<vpPanda3DRGBRenderer>()->getRender(colorImage);
Expand All @@ -175,6 +171,7 @@ int main(int argc, const char **argv)
displayDepth(depthImage, depthDisplayImage, near, far);
vpDisplay::display(colorImage);
vpDisplay::displayText(colorImage, 15, 15, "Click to quit", vpColor::red);

if (stepByStep) {
vpDisplay::displayText(colorImage, 50, 15, "Next frame: space", vpColor::red);
}
Expand All @@ -186,21 +183,30 @@ int main(int argc, const char **argv)
renderTime.push_back(beforeFetch - beforeRender);
fetchTime.push_back(beforeConvert - beforeFetch);
displayTime.push_back(endDisplay - beforeConvert);
std::string s;
if (stepByStep) {
std::string s;
bool next = false;
while (!next) {
vpDisplay::getKeyboardEvent(colorImage, s, true);
if (s == " ") {
next = true;
}
}

}
// if (firstFrame) {
// renderParams.setImageResolution(renderParams.getImageHeight() * 0.5, renderParams.getImageWidth() * 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 << renderParams.getImageHeight() << std::endl;
// //dDepth.setDownScalingFactor(0.5);
// renderer.setRenderParameters(renderParams);
// }
// firstFrame = false;
const double afterAll = vpTime::measureTimeMs();
const double delta = (afterAll - beforeRender) / 1000.0;
vpHomogeneousMatrix wTo = renderer.getNodePose(objectName);
vpHomogeneousMatrix oToo = vpExponentialMap::direct(vpColVector({ 0.0, 0.0, 0.0, 0.0, vpMath::rad(20.0), 0.0 }), delta);
const vpHomogeneousMatrix wTo = renderer.getNodePose(objectName);
const vpHomogeneousMatrix oToo = vpExponentialMap::direct(vpColVector({ 0.0, 0.0, 0.0, 0.0, vpMath::rad(20.0), 0.0 }), delta);
renderer.setNodePose(objectName, wTo * oToo);
}
if (renderTime.size() > 0) {
Expand Down

0 comments on commit 1d88517

Please sign in to comment.