Skip to content

Commit

Permalink
Merge pull request #992 from ros-visualization/wjwwood-qt5
Browse files Browse the repository at this point in the history
make Qt5 the default for Kinetic, fix issues
  • Loading branch information
wjwwood committed Apr 11, 2016
2 parents c2298ce + 8e8fe4e commit 351f2d4
Show file tree
Hide file tree
Showing 10 changed files with 36 additions and 117 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@ find_package(OpenGL REQUIRED)
set(CMAKE_AUTOMOC ON)
set(CMAKE_INCLUDE_CURRENT_DIR ON)

option(UseQt5 "UseQt5" OFF)
option(UseQt5 "UseQt5" ON)
if (UseQt5)
find_package(Qt5Widgets REQUIRED)
find_package(Qt5Core REQUIRED)
Expand Down
10 changes: 6 additions & 4 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,8 @@
<build_depend>interactive_markers</build_depend>
<build_depend>laser_geometry</build_depend>
<build_depend>libogre-dev</build_depend>
<build_depend>libqt4-dev</build_depend>
<build_depend>libqt4-opengl-dev</build_depend>
<build_depend>qtbase5-dev</build_depend>
<build_depend>libqt5-opengl-dev</build_depend>
<build_depend>map_msgs</build_depend>
<build_depend>message_filters</build_depend>
<build_depend>nav_msgs</build_depend>
Expand Down Expand Up @@ -58,8 +58,10 @@
<run_depend>interactive_markers</run_depend>
<run_depend>laser_geometry</run_depend>
<run_depend>libogre-dev</run_depend>
<run_depend>libqt4-dev</run_depend>
<run_depend>libqt4-opengl-dev</run_depend>
<run_depend>libqt5-core</run_depend>
<run_depend>libqt5-gui</run_depend>
<run_depend>libqt5-widgets</run_depend>
<run_depend>libqt5-opengl</run_depend>
<run_depend>map_msgs</run_depend>
<run_depend>media_export</run_depend>
<run_depend>message_filters</run_depend>
Expand Down
26 changes: 14 additions & 12 deletions rviz.sublime-project
Original file line number Diff line number Diff line change
Expand Up @@ -10,24 +10,26 @@
"sublimeclang_options":
[
"-I/Applications/Xcode.app/Contents/Developer/Toolchains/XcodeDefault.xctoolchain/usr/bin/../include/c++/v1",
"-I/Applications/Xcode.app/Contents/Developer/Toolchains/XcodeDefault.xctoolchain/usr/bin/../lib/clang/7.0.2/include",
"-I/Applications/Xcode.app/Contents/Developer/Toolchains/XcodeDefault.xctoolchain/usr/bin/../lib/clang/7.3.0/include",
"-I/Applications/Xcode.app/Contents/Developer/Toolchains/XcodeDefault.xctoolchain/usr/include",
"-I/Applications/Xcode.app/Contents/Developer/Platforms/MacOSX.platform/Developer/SDKs/MacOSX10.11.sdk/usr/include",
"-I/Applications/Xcode.app/Contents/Developer/Platforms/MacOSX.platform/Developer/SDKs/MacOSX10.11.sdk/System/Library/Frameworks",
"-framework QtCore",
"-framework QtGui",
"-I/usr/local/Cellar/qt/4.8.6/lib/QtCore.framework/Versions/4/Headers",
"-I/usr/local/Cellar/qt/4.8.6/lib/QtGui.framework/Versions/4/Headers",
// "-framework QtCore",
// "-framework QtGui",
// "-I/usr/local/Cellar/qt/4.8.6/lib/QtCore.framework/Versions/4/Headers",
// "-I/usr/local/Cellar/qt/4.8.6/lib/QtGui.framework/Versions/4/Headers",
"-I/usr/local/Cellar/qt5/5.5.1_2/include",
"-I/usr/local/Cellar/qt5/5.5.1_2/Frameworks/QtCore.framework/Versions/Current/Headers",
"-I/usr/local/Cellar/qt5/5.5.1_2/Frameworks/QtGui.framework/Versions/Current/Headers",
"-I/usr/local/Cellar/qt5/5.5.1_2/Frameworks/QtWidgets.framework/Versions/Current/Headers",
"-I/usr/local/Cellar/ogre-1.9/1.9.0/include",
"-I/usr/local/Cellar/ogre-1.9/1.9.0/include/OGRE",
"-I/Users/william/indigo/install/include",
"-I/usr/local/Cellar/ogre-1.9/1.9.0/include/OGRE/Overlay",
"-I/Users/william/rviz_ws/install_isolated/include",
"-I${folder:${project_path:rviz.sublime-project}}/src",
"-I/Library/Developer/CommandLineTools/usr/bin/../include/c++/v1",
"-I/usr/local/include",
"-I/Library/Developer/CommandLineTools/usr/bin/../lib/clang/6.1.0/include",
"-I/Library/Developer/CommandLineTools/usr/include",
"-I/usr/include",
"-Wno-deprecated-register"
"-I${folder:${project_path:rviz.sublime-project}}/src/rviz",
"-DROS_PACKAGE_NAME=\"rviz\"",
"-Wno-deprecated-register",
]
}
}
5 changes: 2 additions & 3 deletions src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,7 @@ add_subdirectory(image_view)
if (CATKIN_ENABLE_TESTING)
add_subdirectory(test)
endif()
# Disable Python bindings when using Qt5.
# Will be re-enabled in Kinetic where our Qt Python packages will support Qt5.
if (NOT UseQt5)
# Python bindings are only support with Qt5, PyQt5, and PySide2 for Kinetic+.
if (UseQt5)
add_subdirectory(python_bindings)
endif()
3 changes: 2 additions & 1 deletion src/python_bindings/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
set(rviz_BINDINGS "")

add_subdirectory(shiboken)
# TODO(wjwwood): re-enabled PySide2 support when it is fixed.
# add_subdirectory(shiboken)
add_subdirectory(sip)

message("Python binding generators: ${rviz_BINDINGS}")
Expand Down
3 changes: 1 addition & 2 deletions src/python_bindings/rviz/__init__.py
Original file line number Diff line number Diff line change
@@ -1,11 +1,10 @@
#### Python package 'rviz' initialization.
# Python package 'rviz' initialization.
#
# The actual implementations are defined in C++ and wrapped by
# shiboken or sip. This wrapper finds which binding is available and
# presents it as package rviz.

import sys
import roslib; roslib.load_manifest('rviz')

# Can use the following setattr() call to force one binding or the other.
# setattr(sys, 'SELECT_QT_BINDING', 'pyside')
Expand Down
88 changes: 0 additions & 88 deletions src/python_bindings/sip/configure.py

This file was deleted.

1 change: 1 addition & 0 deletions src/python_bindings/sip/rviz.sip
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

%Import QtCore/QtCoremod.sip
%Import QtGui/QtGuimod.sip
%Import QtWidgets/QtWidgetsmod.sip

%DefaultSupertype sip.simplewrapper

Expand Down
11 changes: 7 additions & 4 deletions src/rviz/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -130,13 +130,14 @@ target_link_libraries(${PROJECT_NAME}
${catkin_LIBRARIES}
${OGRE_OV_LIBRARIES_ABS}
${OPENGL_LIBRARIES}
${QT_LIBRARIES}
${rviz_ADDITIONAL_LIBRARIES}
assimp
yaml-cpp
)
if (UseQt5)
if(UseQt5)
target_link_libraries(${PROJECT_NAME} Qt5::Widgets)
else()
target_link_libraries(${PROJECT_NAME} ${QT_LIBRARIES})
endif()


Expand All @@ -147,9 +148,11 @@ endif(APPLE)
########### The rviz executable ###########
add_executable(executable main.cpp)

target_link_libraries(executable ${PROJECT_NAME} ${QT_LIBRARIES} ${OGRE_OV_LIBRARIES_ABS})
if (UseQt5)
target_link_libraries(executable ${PROJECT_NAME} ${OGRE_OV_LIBRARIES_ABS})
if(UseQt5)
target_link_libraries(executable Qt5::Widgets)
else()
target_link_libraries(executable ${QT_LIBRARIES})
endif()

set_target_properties(executable
Expand Down
4 changes: 2 additions & 2 deletions src/rviz/ogre_helpers/render_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -291,7 +291,7 @@ void RenderSystem::setupResources()
std::vector<std::string> media_paths;
ros::package::getPlugins( "media_export", "ogre_media_path", media_paths );
std::string delim(":");
for( std::vector<std::string>::iterator iter = media_paths.begin(); iter != media_paths.end(); iter++ )
for( std::vector<std::string>::iterator iter = media_paths.begin(); iter != media_paths.end(); ++iter )
{
if( !iter->empty() )
{
Expand Down Expand Up @@ -462,7 +462,7 @@ Ogre::RenderWindow* RenderSystem::tryMakeRenderWindow(
x_baddrawable_error = false;
}
}
catch( std::exception ex )
catch( const std::exception & ex )
{
std::cerr << "rviz::RenderSystem: error creating render window: "
<< ex.what() << std::endl;
Expand Down

0 comments on commit 351f2d4

Please sign in to comment.