Skip to content

Commit

Permalink
4 ➡️ 5 (#264)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <louise@openrobotics.org>
  • Loading branch information
chapulina committed Mar 18, 2021
2 parents 8f738e4 + d98ea2a commit e66fbad
Show file tree
Hide file tree
Showing 28 changed files with 732 additions and 112 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ jobs:
uses: actions/checkout@v2
- name: Compile and test
id: ci
uses: ignition-tooling/action-ignition-ci@master
uses: ignition-tooling/action-ignition-ci@bionic
with:
codecov-token: ${{ secrets.CODECOV_TOKEN }}
focal-ci:
Expand Down
31 changes: 31 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,37 @@

### Ignition Rendering 4.X

### Ignition Rendering 4.7.0 (2021-03-17)

1. Enable depth write in particles example
* [Pull Request #217](https://github.com/ignitionrobotics/ign-rendering/pull/217)

1. Fix gazebo_scene_viewer for macOS and ensure clean exit
* [Pull Request #259](https://github.com/ignitionrobotics/ign-rendering/pull/259)

1. Master branch updates
* [Pull Request #268](https://github.com/ignitionrobotics/ign-rendering/pull/268)

1. Expose particle scatter ratio parameter
* [Pull Request #269](https://github.com/ignitionrobotics/ign-rendering/pull/269)

1. Fix overriding blend mode
* [Pull Request #266](https://github.com/ignitionrobotics/ign-rendering/pull/266)

1. Fix DepthGaussianNoise test
* [Pull Request #271](https://github.com/ignitionrobotics/ign-rendering/pull/271)

1. Handle non-positive object temperatures
* [Pull Request #243](https://github.com/ignitionrobotics/ign-rendering/pull/243)

### Ignition Rendering 4.6.0 (2021-03-01)

1. Improve particle scattering noise
* [Pull Request #261](https://github.com/ignitionrobotics/ign-rendering/pull/261)

1. Fix custom_scene_viewer for macOS
* [Pull Request #256](https://github.com/ignitionrobotics/ign-rendering/pull/256)

### Ignition Rendering 4.5.0 (2021-02-17)

1. More verbose messages when failing to load render engines
Expand Down
14 changes: 7 additions & 7 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,11 +9,10 @@

Build | Status
-- | --
Test coverage | [![codecov](https://codecov.io/gh/ignitionrobotics/ign-rendering/branch/master/graph/badge.svg)](https://codecov.io/gh/ignitionrobotics/ign-rendering/branch/default)
Ubuntu Xenial | [![](https://build.osrfoundation.org/buildStatus/icon?job=ignition_rendering-ci-master-xenial-amd64)](https://build.osrfoundation.org/job/ignition_rendering-ci-master-xenial-amd64/)
Ubuntu Bionic | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_rendering-ci-master-bionic-amd64)](https://build.osrfoundation.org/job/ignition_rendering-ci-master-bionic-amd64)
Homebrew | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_rendering-ci-master-homebrew-amd64)](https://build.osrfoundation.org/job/ignition_rendering-ci-master-homebrew-amd64)
Windows | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ign_rendering-ci-win)](https://build.osrfoundation.org/job/ign_rendering-ci-win)
Test coverage | [![codecov](https://codecov.io/gh/ignitionrobotics/ign-rendering/branch/main/graph/badge.svg)](https://codecov.io/gh/ignitionrobotics/ign-rendering/branch/default)
Ubuntu Bionic | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_rendering-ci-main-bionic-amd64)](https://build.osrfoundation.org/job/ignition_rendering-ci-main-bionic-amd64)
Homebrew | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_rendering-ci-main-homebrew-amd64)](https://build.osrfoundation.org/job/ignition_rendering-ci-main-homebrew-amd64)
Windows | [![Build Status](https://build.osrfoundation.org/job/ign_rendering-ci-win/badge/icon)](https://build.osrfoundation.org/job/ign_rendering-ci-win/)

Ignition Rendering is a C++ library designed to provide an abstraction
for different rendering engines. It offers unified APIs for creating
Expand Down Expand Up @@ -87,12 +86,13 @@ Please see
# Code of Conduct

Please see
[CODE_OF_CONDUCT.md](https://github.com/ignitionrobotics/ign-gazebo/blob/master/CODE_OF_CONDUCT.md).
[CODE_OF_CONDUCT.md](https://github.com/ignitionrobotics/ign-gazebo/blob/main/CODE_OF_CONDUCT.md).

# Versioning

This library uses [Semantic Versioning](https://semver.org/). Additionally, this library is part of the [Ignition Robotics project](https://ignitionrobotics.org) which periodically releases a versioned set of compatible and complimentary libraries. See the [Ignition Robotics website](https://ignitionrobotics.org) for version and release information.

# License

This library is licensed under [Apache 2.0](https://www.apache.org/licenses/LICENSE-2.0). See also the [LICENSE](https://github.com/ignitionrobotics/ign-rendering/blob/master/LICENSE) file.
This library is licensed under [Apache 2.0](https://www.apache.org/licenses/LICENSE-2.0). See also the [LICENSE](https://github.com/ignitionrobotics/ign-rendering/blob/main/LICENSE) file.

40 changes: 30 additions & 10 deletions examples/custom_scene_viewer/DemoWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,11 @@
*
*/

#if defined(__APPLE__)
#if __APPLE__
#include <OpenGL/gl.h>
#include <OpenGL/OpenGL.h>
#include <GLUT/glut.h>
#elif !defined(_WIN32)
#else
#include <GL/glew.h>
#include <GL/gl.h>
#include <GL/glut.h>
Expand Down Expand Up @@ -52,7 +53,11 @@ unsigned int imgh = 0;

bool g_initContext = false;

#if not (__APPLE__ || _WIN32)
#if __APPLE__
CGLContextObj g_context;
CGLContextObj g_glutContext;
#elif _WIN32
#else
GLXContext g_context;
Display *g_display;
GLXDrawable g_drawable;
Expand Down Expand Up @@ -159,7 +164,10 @@ void printFPS()
//////////////////////////////////////////////////
void displayCB()
{
#if not (__APPLE__ || _WIN32)
#if __APPLE__
CGLSetCurrentContext(g_context);
#elif _WIN32
#else
if (g_display)
{
glXMakeCurrent(g_display, g_drawable, g_context);
Expand All @@ -171,7 +179,10 @@ void displayCB()

camera->Capture(*g_image);

#if not (__APPLE__ || _WIN32)
#if __APPLE__
CGLSetCurrentContext(g_glutContext);
#elif _WIN32
#else
glXMakeCurrent(g_glutDisplay, g_glutDrawable, g_glutContext);
#endif

Expand All @@ -198,7 +209,10 @@ void idleCB()
//////////////////////////////////////////////////
void keyboardCB(unsigned char _key, int, int)
{
#if not (__APPLE__ || _WIN32)
#if __APPLE__
CGLSetCurrentContext(g_context);
#elif _WIN32
#else
if (g_display)
{
glXMakeCurrent(g_display, g_drawable, g_context);
Expand Down Expand Up @@ -241,7 +255,10 @@ void keyboardCB(unsigned char _key, int, int)
g_demo->SelectScene(index);
}

#if not (__APPLE__ || _WIN32)
#if __APPLE__
CGLSetCurrentContext(g_glutContext);
#elif _WIN32
#else
glXMakeCurrent(g_glutDisplay, g_glutDrawable, g_glutContext);
#endif
}
Expand All @@ -259,9 +276,6 @@ void initCamera(CameraPtr _camera)
//////////////////////////////////////////////////
void initContext()
{
int argc = 0;
char **argv = 0;
glutInit(&argc, argv);
glutInitDisplayMode(GLUT_DOUBLE);
glutInitWindowPosition(0, 0);
glutInitWindowSize(imgw, imgh);
Expand All @@ -278,6 +292,9 @@ void initContext()
//////////////////////////////////////////////////
void run(ManualSceneDemoPtr _demo)
{
#if __APPLE__
g_context = CGLGetCurrentContext();
#endif
#if not (__APPLE__ || _WIN32)
g_context = glXGetCurrentContext();
g_display = glXGetCurrentDisplay();
Expand All @@ -290,6 +307,9 @@ void run(ManualSceneDemoPtr _demo)
initContext();
printUsage();

#if __APPLE__
g_glutContext = CGLGetCurrentContext();
#endif
#if not (__APPLE__ || _WIN32)
g_glutDisplay = glXGetCurrentDisplay();
g_glutDrawable = glXGetCurrentDrawable();
Expand Down
25 changes: 23 additions & 2 deletions examples/custom_scene_viewer/ManualSceneDemo.cc
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,16 @@
* limitations under the License.
*
*/

#if defined(__APPLE__)
#include <OpenGL/gl.h>
#include <GLUT/glut.h>
#elif not defined(_WIN32)
#include <GL/glew.h>
#include <GL/gl.h>
#include <GL/glut.h>
#endif

#include <iostream>
#include <ignition/common/Console.hh>
#include "ManualSceneDemo.hh"
Expand Down Expand Up @@ -169,8 +179,18 @@ void ManualSceneDemo::ChangeScene()

//////////////////////////////////////////////////
//////////////////////////////////////////////////
int main(int, char**)
int main(int _argc, char** _argv)
{
glutInit(&_argc, _argv);

// Expose engine name to command line because we can't instantiate both
// ogre and ogre2 at the same time
std::string ogreEngine("ogre");
if (_argc > 1)
{
ogreEngine = _argv[1];
}

common::Console::SetVerbosity(4);
//! [add scenes]
ManualSceneDemoPtr sceneDemo(new ManualSceneDemo);
Expand All @@ -188,8 +208,9 @@ int main(int, char**)
sceneDemo->AddScene(SceneBuilderPtr(new ShadowSceneBuilder(4)));
sceneDemo->AddScene(SceneBuilderPtr(new ShadowSceneBuilder(5)));
//! [add scenes]
sceneDemo->AddCamera("ogre");
sceneDemo->AddCamera(ogreEngine);
sceneDemo->AddCamera("optix");
sceneDemo->Run();
return 0;
}

5 changes: 3 additions & 2 deletions examples/gazebo_scene_viewer/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@ if (NOT APPLE)
find_package(GLEW REQUIRED)
include_directories(SYSTEM ${GLEW_INCLUDE_DIRS})
link_directories(${GLEW_LIBRARY_DIRS})
set(STD_CXX_FS_LIBRARIES "stdc++fs")
endif()

set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-deprecated-declarations")
Expand All @@ -33,7 +34,7 @@ target_link_libraries(gazebo_scene_viewer
${GLEW_LIBRARIES}
${GAZEBO_LIBRARIES}
${IGNITION-RENDERING_LIBRARIES}
stdc++fs
${STD_CXX_FS_LIBRARIES}
)

add_executable(gazebo_scene_viewer2_demo
Expand All @@ -48,5 +49,5 @@ target_link_libraries(gazebo_scene_viewer2_demo
${GLEW_LIBRARIES}
${GAZEBO_LIBRARIES}
${IGNITION-RENDERING_LIBRARIES}
stdc++fs
${STD_CXX_FS_LIBRARIES}
)
44 changes: 34 additions & 10 deletions examples/gazebo_scene_viewer/CameraWindow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@

#if __APPLE__
#include <OpenGL/gl.h>
#include <OpenGL/OpenGL.h>
#include <GLUT/glut.h>
#else
#include <GL/glew.h>
Expand All @@ -30,6 +31,7 @@
#endif

#include <gazebo/common/Console.hh>
#include <gazebo/transport/TransportIface.hh>

#include <ignition/rendering/Camera.hh>
#include <ignition/rendering/Image.hh>
Expand All @@ -52,7 +54,11 @@ gz::ImagePtr g_image;

bool g_initContext = false;

#if not (__APPLE__ || _WIN32)
#if __APPLE__
CGLContextObj g_context;
CGLContextObj g_glutContext;
#elif _WIN32
#else
GLXContext g_context;
Display *g_display;
GLXDrawable g_drawable;
Expand All @@ -66,7 +72,10 @@ double g_offset = 0.0;
//////////////////////////////////////////////////
void GlutRun(std::vector<gz::CameraPtr> _cameras)
{
#if not (__APPLE__ || _WIN32)
#if __APPLE__
g_context = CGLGetCurrentContext();
#elif _WIN32
#else
g_context = glXGetCurrentContext();
g_display = glXGetCurrentDisplay();
g_drawable = glXGetCurrentDrawable();
Expand All @@ -77,7 +86,10 @@ void GlutRun(std::vector<gz::CameraPtr> _cameras)
GlutInitContext();
GlutPrintUsage();

#if not (__APPLE__ || _WIN32)
#if __APPLE__
g_glutContext = CGLGetCurrentContext();
#elif _WIN32
#else
g_glutDisplay = glXGetCurrentDisplay();
g_glutDrawable = glXGetCurrentDrawable();
g_glutContext = glXGetCurrentContext();
Expand All @@ -89,7 +101,10 @@ void GlutRun(std::vector<gz::CameraPtr> _cameras)
//////////////////////////////////////////////////
void GlutDisplay()
{
#if not (__APPLE__ || _WIN32)
#if __APPLE__
CGLSetCurrentContext(g_context);
#elif _WIN32
#else
if (g_display)
{
glXMakeCurrent(g_display, g_drawable, g_context);
Expand All @@ -98,7 +113,10 @@ void GlutDisplay()

g_cameras[g_cameraIndex]->Capture(*g_image);

#if not (__APPLE__ || _WIN32)
#if __APPLE__
CGLSetCurrentContext(g_glutContext);
#elif _WIN32
#else
glXMakeCurrent(g_glutDisplay, g_glutDrawable, g_glutContext);
#endif

Expand All @@ -116,7 +134,10 @@ void GlutDisplay()
//////////////////////////////////////////////////
void GlutIdle()
{
#if not (__APPLE__ || _WIN32)
#if __APPLE__
CGLSetCurrentContext(g_context);
#elif _WIN32
#else
if (g_display)
{
glXMakeCurrent(g_display, g_drawable, g_context);
Expand All @@ -128,7 +149,10 @@ void GlutIdle()

manager->UpdateScenes();

#if not (__APPLE__ || _WIN32)
#if __APPLE__
CGLSetCurrentContext(g_glutContext);
#elif _WIN32
#else
glXMakeCurrent(g_glutDisplay, g_glutDrawable, g_glutContext);
#endif

Expand All @@ -140,6 +164,9 @@ void GlutKeyboard(unsigned char _key, int, int)
{
if (_key == KEY_ESC || _key == 'q' || _key == 'Q')
{
// stop transport
gazebo::transport::stop();
gazebo::transport::fini();
exit(0);
}
else if (_key == KEY_TAB)
Expand Down Expand Up @@ -167,9 +194,6 @@ void GlutInitCamera(gz::CameraPtr _camera)
//////////////////////////////////////////////////
void GlutInitContext()
{
int argc = 0;
char **argv = 0;
glutInit(&argc, argv);
glutInitDisplayMode(GLUT_DOUBLE);
glutInitWindowPosition(0, 0);
glutInitWindowSize(imgw, imgh);
Expand Down
Loading

0 comments on commit e66fbad

Please sign in to comment.