Skip to content

Commit

Permalink
Add shader generator listener
Browse files Browse the repository at this point in the history
  • Loading branch information
simonschmeisser committed Mar 28, 2022
1 parent 257cacf commit 65cd88a
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 1 deletion.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ if(NOT DEFINED ASSIMP_LIBRARIES AND TARGET assimp::assimp)
set(ASSIMP_LIBRARIES assimp::assimp)
endif()

find_package(OGRE QUIET COMPONENTS Overlay RTShaderSystem)
find_package(OGRE QUIET COMPONENTS Overlay RTShaderSystem Bites)
if(OGRE_FOUND)
if(${OGRE_VERSION} VERSION_LESS 1.11)
set(OGRE_INCLUDE_DIRS ${OGRE_INCLUDE_DIRS} ${OGRE_Overlay_INCLUDE_DIRS})
Expand Down
8 changes: 8 additions & 0 deletions src/rviz/visualization_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@
#include <OgreRenderWindow.h>
#include <OgreRTShaderSystem.h>
#include <OgreSharedPtr.h>
#include <OgreSGTechniqueResolverListener.h>
#include <OgreCamera.h>

#include <boost/filesystem.hpp>
Expand Down Expand Up @@ -116,6 +117,7 @@ class VisualizationManagerPrivate
ros::NodeHandle update_nh_;
ros::NodeHandle threaded_nh_;
boost::mutex render_mutex_;
OgreBites::SGTechniqueResolverListener* material_mgr_listener_;
};

VisualizationManager::VisualizationManager(RenderPanel* render_panel,
Expand Down Expand Up @@ -153,6 +155,12 @@ VisualizationManager::VisualizationManager(RenderPanel* render_panel,
RTShader::ShaderGenerator* shadergen = RTShader::ShaderGenerator::getSingletonPtr();
shadergen->addSceneManager(scene_manager_);

// Create and register the material manager listener if it doesn't exist yet.
// if (!mMaterialMgrListener) {
private_->material_mgr_listener_ = new OgreBites::SGTechniqueResolverListener(shadergen);
Ogre::MaterialManager::getSingleton().addListener(private_->material_mgr_listener_);
//}

directional_light_ = scene_manager_->createLight("MainDirectional");
directional_light_->setType(Ogre::Light::LT_DIRECTIONAL);
directional_light_->setDirection(Ogre::Vector3(-1, 0, -1));
Expand Down

0 comments on commit 65cd88a

Please sign in to comment.