diff --git a/CMakeLists.txt b/CMakeLists.txt index 75be0e1eb2..9205abd743 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -226,7 +226,7 @@ option(PCL_OMP "With PCL OMP implementations" ON) ENDIF() set(RTABMAP_QT_VERSION AUTO CACHE STRING "Force a specific Qt version.") -set_property(CACHE RTABMAP_QT_VERSION PROPERTY STRINGS AUTO 4 5) +set_property(CACHE RTABMAP_QT_VERSION PROPERTY STRINGS AUTO 4 5 6) FIND_PACKAGE(OpenCV REQUIRED QUIET COMPONENTS core calib3d imgproc highgui stitching photo video OPTIONAL_COMPONENTS aruco xfeatures2d nonfree gpu cudafeatures2d) @@ -297,20 +297,31 @@ IF(WITH_QT) ENDIF(NOT VTK_FOUND) # If Qt is here, the GUI will be built - # look for Qt5 (if vtk>5 is installed) before Qt4 - IF("${VTK_MAJOR_VERSION}" GREATER 5) - if(RTABMAP_QT_VERSION STREQUAL "AUTO" OR RTABMAP_QT_VERSION STREQUAL "5") - FIND_PACKAGE(Qt5 QUIET COMPONENTS Widgets Core Gui PrintSupport OpenGL OPTIONAL_COMPONENTS Svg) - ENDIF(RTABMAP_QT_VERSION STREQUAL "AUTO" OR RTABMAP_QT_VERSION STREQUAL "5") - ENDIF("${VTK_MAJOR_VERSION}" GREATER 5) - - IF(NOT Qt5_FOUND) + IF("${VTK_MAJOR_VERSION}" GREATER_EQUAL 9) + MESSAGE(STATUS "VTK>=9 detected, will use VTK_QT_VERSION=${VTK_QT_VERSION} for Qt version.") + IF(${VTK_QT_VERSION} EQUAL 6) + FIND_PACKAGE(Qt6 COMPONENTS Widgets Core Gui OpenGL PrintSupport QUIET OPTIONAL_COMPONENTS Svg) + ELSEIF(${VTK_QT_VERSION} EQUAL 5) + FIND_PACKAGE(Qt5 COMPONENTS Widgets Core Gui OpenGL PrintSupport QUIET OPTIONAL_COMPONENTS Svg) + ELSE() + FIND_PACKAGE(Qt4 COMPONENTS QtCore QtGui OPTIONAL_COMPONENTS QtSvg) + ENDIF() + ELSE() + # look for Qt5 (if vtk>5 is installed) before Qt4 + IF("${VTK_MAJOR_VERSION}" GREATER 5) + IF(RTABMAP_QT_VERSION STREQUAL "AUTO" OR RTABMAP_QT_VERSION STREQUAL "5") + FIND_PACKAGE(Qt5 COMPONENTS Widgets Core Gui OpenGL PrintSupport QUIET OPTIONAL_COMPONENTS Svg) + ENDIF(RTABMAP_QT_VERSION STREQUAL "AUTO" OR RTABMAP_QT_VERSION STREQUAL "5") + ENDIF("${VTK_MAJOR_VERSION}" GREATER 5) + + IF(NOT Qt5_FOUND) IF(RTABMAP_QT_VERSION STREQUAL "AUTO" OR RTABMAP_QT_VERSION STREQUAL "4") - FIND_PACKAGE(Qt4 QUIET COMPONENTS QtCore QtGui OPTIONAL_COMPONENTS QtSvg) + FIND_PACKAGE(Qt4 COMPONENTS QtCore QtGui OPTIONAL_COMPONENTS QtSvg) ENDIF(RTABMAP_QT_VERSION STREQUAL "AUTO" OR RTABMAP_QT_VERSION STREQUAL "4") - ENDIF(NOT Qt5_FOUND) + ENDIF(NOT Qt5_FOUND) + ENDIF() - IF(QT4_FOUND OR Qt5_FOUND) + IF(QT4_FOUND OR Qt5_FOUND OR Qt6_FOUND) IF("${VTK_MAJOR_VERSION}" EQUAL 5) FIND_PACKAGE(QVTK REQUIRED) # only for VTK 5 ELSE() @@ -318,7 +329,7 @@ IF(WITH_QT) IF(value EQUAL -1) list(FIND PCL_LIBRARIES vtkGUISupportQt value) IF(value EQUAL -1) - IF("${VTK_MAJOR_VERSION}" GREATER 8) + IF("${VTK_MAJOR_VERSION}" GREATER_EQUAL 9) SET(PCL_LIBRARIES "${PCL_LIBRARIES};VTK::GUISupportQt") ELSE() SET(PCL_LIBRARIES "${PCL_LIBRARIES};vtkGUISupportQt") @@ -354,7 +365,7 @@ IF(WITH_QT) ENDIF() ADD_DEFINITIONS(-DQT_NO_KEYWORDS) # To avoid conflicts with boost signals/foreach and Qt macros - ENDIF(QT4_FOUND OR Qt5_FOUND) + ENDIF(QT4_FOUND OR Qt5_FOUND OR Qt6_FOUND) ENDIF(WITH_QT) IF(NOT VTK_FOUND) @@ -752,7 +763,18 @@ IF(WITH_ORB_SLAM AND NOT G2O_FOUND) ENDIF(WITH_ORB_SLAM AND NOT G2O_FOUND) IF(NOT MSVC) - IF((NOT WITH_MSCKF_VIO OR NOT msckf_vio_FOUND) AND (loam_velodyne_FOUND OR floam_FOUND OR PCL_VERSION VERSION_GREATER "1.9.1" OR TORCH_FOUND OR G2O_FOUND OR CCCoreLib_FOUND OR Open3D_FOUND)) + IF(Qt6_FOUND) + # Qt6 requires c++17 + include(CheckCXXCompilerFlag) + CHECK_CXX_COMPILER_FLAG("-std=c++17" COMPILER_SUPPORTS_CXX17) + IF(COMPILER_SUPPORTS_CXX17) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++17") + set(CMAKE_CXX_STANDARD 17) + ELSE() + message(STATUS "The compiler ${CMAKE_CXX_COMPILER} has no C++17 support. Please use a different C++ compiler if you want to use Qt6.") + ENDIF() + ENDIF() + IF((NOT (${CMAKE_CXX_STANDARD} STREQUAL "17")) AND ((NOT WITH_MSCKF_VIO OR NOT msckf_vio_FOUND) AND (loam_velodyne_FOUND OR floam_FOUND OR PCL_VERSION VERSION_GREATER "1.9.1" OR TORCH_FOUND OR G2O_FOUND OR CCCoreLib_FOUND OR Open3D_FOUND))) #LOAM, PCL>=1.10, latest g2o and CCCoreLib require c++14, but MSCKF_VIO requires c++11 include(CheckCXXCompilerFlag) CHECK_CXX_COMPILER_FLAG("-std=c++14" COMPILER_SUPPORTS_CXX14) @@ -764,7 +786,7 @@ IF(NOT MSVC) ENDIF() ENDIF() - IF( (NOT (${CMAKE_CXX_STANDARD} STREQUAL "14")) AND ( + IF( (NOT (${CMAKE_CXX_STANDARD} STREQUAL "17") AND NOT (${CMAKE_CXX_STANDARD} STREQUAL "14")) AND ( G2O_FOUND OR GTSAM_FOUND OR CERES_FOUND OR @@ -796,7 +818,7 @@ ENDIF() ####### OSX BUNDLE CMAKE_INSTALL_PREFIX ####### IF(APPLE AND BUILD_AS_BUNDLE) - IF(Qt5_FOUND OR (QT4_FOUND AND QT_QTCORE_FOUND AND QT_QTGUI_FOUND)) + IF(Qt6_FOUND OR Qt5_FOUND OR (QT4_FOUND AND QT_QTCORE_FOUND AND QT_QTGUI_FOUND)) # Required when packaging, and set CMAKE_INSTALL_PREFIX to "/". SET(CMAKE_INSTALL_PREFIX "/") @@ -1023,7 +1045,7 @@ IF(ANDROID) IF(BUILD_APP) ADD_SUBDIRECTORY( app ) ENDIF(BUILD_APP) -ELSEIF(Qt5_FOUND OR (QT4_FOUND AND QT_QTCORE_FOUND AND QT_QTGUI_FOUND)) +ELSEIF(Qt6_FOUND OR Qt5_FOUND OR (QT4_FOUND AND QT_QTCORE_FOUND AND QT_QTGUI_FOUND)) ADD_SUBDIRECTORY( guilib ) IF(BUILD_APP) ADD_SUBDIRECTORY( app ) @@ -1055,12 +1077,14 @@ ADD_CUSTOM_TARGET(uninstall #### add_library(rtabmap INTERFACE) add_library(rtabmap::rtabmap ALIAS rtabmap) -IF(QT4_FOUND OR Qt5_FOUND) +IF(QT4_FOUND OR Qt5_FOUND OR Qt6_FOUND) set(CONF_WITH_GUI ON) IF(QT4_FOUND) set(CONF_QT_VERSION 4) - ELSE() + ELSEIF(Qt5_FOUND) set(CONF_QT_VERSION 5) + ELSE() + set(CONF_QT_VERSION 6) ENDIF() target_link_libraries(rtabmap INTERFACE rtabmap_utilite rtabmap_core rtabmap_gui) ELSE() @@ -1271,6 +1295,9 @@ MESSAGE(STATUS " With VTK ${VTK_MAJOR_VERSION}.${VTK_MINOR_VERSION} ELSEIF(Qt5_FOUND) MESSAGE(STATUS " With Qt ${Qt5_VERSION} = YES (License: Open Source or Commercial)") MESSAGE(STATUS " With VTK ${VTK_MAJOR_VERSION}.${VTK_MINOR_VERSION} = YES (License: BSD)") +ELSEIF(Qt6_FOUND) +MESSAGE(STATUS " With Qt ${Qt6_VERSION} = YES (License: Open Source or Commercial)") +MESSAGE(STATUS " With VTK ${VTK_MAJOR_VERSION}.${VTK_MINOR_VERSION} = YES (License: BSD)") ELSEIF(NOT WITH_QT) MESSAGE(STATUS " With Qt = NO (WITH_QT=OFF)") diff --git a/RTABMapConfig.cmake.in b/RTABMapConfig.cmake.in index 695c058ef9..0f156f0142 100644 --- a/RTABMapConfig.cmake.in +++ b/RTABMapConfig.cmake.in @@ -6,7 +6,9 @@ find_dependency(OpenCV COMPONENTS core calib3d imgproc highgui stitching photo v if(EXISTS "${CMAKE_CURRENT_LIST_DIR}/RTABMap_guiTargets.cmake") find_dependency(PCL 1.7 COMPONENTS common io kdtree search surface filters registration sample_consensus segmentation visualization) - if(@CONF_QT_VERSION@ EQUAL 5) + if(@CONF_QT_VERSION@ EQUAL 6) + find_dependency(Qt6 COMPONENTS Widgets Core Gui OpenGL) + elseif(@CONF_QT_VERSION@ EQUAL 5) find_dependency(Qt5 COMPONENTS Widgets Core Gui OpenGL) else() # Qt4 find_dependency(Qt4 COMPONENTS QtCore QtGui) diff --git a/cmake_modules/FindZEDOC.cmake b/cmake_modules/FindZEDOC.cmake index 76563ed943..8c96c2bd1c 100644 --- a/cmake_modules/FindZEDOC.cmake +++ b/cmake_modules/FindZEDOC.cmake @@ -17,7 +17,7 @@ ENDIF (ZEDOC_INCLUDE_DIR AND ZEDOC_LIBRARY) IF (ZEDOC_FOUND) # show which ZEDOC was found only if not quiet - IF (NOT _FIND_QUIETLY) + IF (NOT ZEDOC_FIND_QUIETLY) MESSAGE(STATUS "Found ZEDOC: ${ZEDOC_LIBRARIES}") ENDIF (NOT ZEDOC_FIND_QUIETLY) ELSE (ZEDOC_FOUND) diff --git a/docker/latest_deps/Dockerfile b/docker/latest_deps/Dockerfile new file mode 100644 index 0000000000..3c8437cd99 --- /dev/null +++ b/docker/latest_deps/Dockerfile @@ -0,0 +1,63 @@ + +FROM osrf/ros:humble-desktop + +# Install build dependencies +RUN apt-get update && \ + apt-get install -y git software-properties-common ros-humble-rtabmap-ros libqt6* qt6* && \ + apt-get remove -y ros-humble-rtabmap libpcl* libqt5* qt5* libvtk* libopencv* && \ + apt-get clean && rm -rf /var/lib/apt/lists/ + +WORKDIR /root/ + +RUN rm /bin/sh && ln -s /bin/bash /bin/sh + +# ros2 seems not sourcing by default its multi-arch folders +ENV LD_LIBRARY_PATH=$LD_LIBRARY_PATH:/opt/ros/humble/lib/x86_64-linux-gnu + +# Build latest VTK with Qt6 +RUN git clone https://github.com/Kitware/VTK.git && \ + cd VTK && \ + mkdir build && \ + cd build && \ + cmake -DVTK_GROUP_ENABLE_Qt=YES .. && \ + make -j$(nproc) && \ + make install && \ + cd ../.. && \ + rm -rf VTK + +# Build latest PCL with latest VTK +RUN git clone https://github.com/PointCloudLibrary/pcl.git && \ + cd pcl && \ + mkdir build && \ + cd build && \ + cmake -DBUILD_tools=OFF .. && \ + make -j$(nproc) && \ + make install && \ + cd ../.. && \ + rm -rf pcl + +# Build latest OpenCV +RUN git clone https://github.com/opencv/opencv.git && \ + git clone https://github.com/opencv/opencv_contrib.git && \ + cd opencv && \ + mkdir build && \ + cd build && \ + cmake -DBUILD_opencv_python3=OFF -DBUILD_opencv_python_bindings_generator=OFF -DBUILD_opencv_python_tests=OFF -DBUILD_PERF_TESTS=OFF -DBUILD_TESTS=OFF -DOPENCV_EXTRA_MODULES_PATH=/root/opencv_contrib/modules .. && \ + make -j$(nproc) && \ + make install && \ + cd ../.. && \ + rm -rf opencv + +# Copy current source code +COPY . /root/rtabmap + +# Build RTAB-Map project +RUN source /ros_entrypoint.sh && \ + cd rtabmap/build && \ + cmake .. && \ + make -j$(nproc) && \ + make install && \ + cd ../.. && \ + rm -rf rtabmap && \ + ldconfig + diff --git a/examples/NoEventsExample/CMakeLists.txt b/examples/NoEventsExample/CMakeLists.txt index 8a43b3aec2..3bdb9fdc08 100644 --- a/examples/NoEventsExample/CMakeLists.txt +++ b/examples/NoEventsExample/CMakeLists.txt @@ -13,8 +13,10 @@ endif() IF(QT4_FOUND) QT4_WRAP_CPP(moc_srcs MapBuilder.h) -ELSE() +ELSEIF(Qt5_FOUND) QT5_WRAP_CPP(moc_srcs MapBuilder.h) +ELSE() + QT6_WRAP_CPP(moc_srcs MapBuilder.h) ENDIF() ADD_EXECUTABLE(noEventsExample main.cpp ${moc_srcs}) diff --git a/examples/RGBDMapping/CMakeLists.txt b/examples/RGBDMapping/CMakeLists.txt index 05d69a2fc7..cae6f0cd86 100644 --- a/examples/RGBDMapping/CMakeLists.txt +++ b/examples/RGBDMapping/CMakeLists.txt @@ -13,8 +13,10 @@ endif() IF(QT4_FOUND) QT4_WRAP_CPP(moc_srcs MapBuilder.h) -ELSE() +ELSEIF(Qt5_FOUND) QT5_WRAP_CPP(moc_srcs MapBuilder.h) +ELSE() + QT6_WRAP_CPP(moc_srcs MapBuilder.h) ENDIF() ADD_EXECUTABLE(rgbd_mapping main.cpp ${moc_srcs}) diff --git a/examples/WifiMapping/CMakeLists.txt b/examples/WifiMapping/CMakeLists.txt index 8c79826fdc..460609cbb9 100644 --- a/examples/WifiMapping/CMakeLists.txt +++ b/examples/WifiMapping/CMakeLists.txt @@ -13,8 +13,10 @@ endif() IF(QT4_FOUND) QT4_WRAP_CPP(moc_srcs MapBuilder.h MapBuilderWifi.h) -ELSE() +ELSEIF(Qt5_FOUND) QT5_WRAP_CPP(moc_srcs MapBuilder.h MapBuilderWifi.h) +ELSE() + QT6_WRAP_CPP(moc_srcs MapBuilder.h MapBuilderWifi.h) ENDIF() SET(srcs diff --git a/guilib/include/rtabmap/gui/ConsoleWidget.h b/guilib/include/rtabmap/gui/ConsoleWidget.h index b0c074771b..cdb62af53e 100644 --- a/guilib/include/rtabmap/gui/ConsoleWidget.h +++ b/guilib/include/rtabmap/gui/ConsoleWidget.h @@ -35,6 +35,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include +#include class Ui_consoleWidget; class QMessageBox; @@ -69,7 +70,7 @@ private Q_SLOTS: QMutex _errorMessageMutex; QMutex _msgListMutex; QTimer _timer; - QTime _time; + QElapsedTimer _time; QTextCursor * _textCursor; QList > _msgList; }; diff --git a/guilib/include/rtabmap/gui/MainWindow.h b/guilib/include/rtabmap/gui/MainWindow.h index 533e4cec51..31639048ed 100644 --- a/guilib/include/rtabmap/gui/MainWindow.h +++ b/guilib/include/rtabmap/gui/MainWindow.h @@ -33,6 +33,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include "rtabmap/utilite/UEventsHandler.h" #include #include +#include #include "rtabmap/core/RtabmapEvent.h" #include "rtabmap/core/SensorData.h" #include "rtabmap/core/OdometryEvent.h" @@ -400,8 +401,8 @@ protected Q_SLOTS: bool _processingOdometry; QTimer * _oneSecondTimer; - QTime * _elapsedTime; - QTime * _logEventTime; + QElapsedTimer * _elapsedTime; + QElapsedTimer * _logEventTime; PdfPlotCurve * _posteriorCurve; PdfPlotCurve * _likelihoodCurve; diff --git a/guilib/include/rtabmap/gui/ProgressDialog.h b/guilib/include/rtabmap/gui/ProgressDialog.h index 3fbf6deb68..fa287520b9 100644 --- a/guilib/include/rtabmap/gui/ProgressDialog.h +++ b/guilib/include/rtabmap/gui/ProgressDialog.h @@ -45,7 +45,7 @@ class RTABMAP_GUI_EXPORT ProgressDialog : public QDialog Q_OBJECT public: - ProgressDialog(QWidget *parent = 0, Qt::WindowFlags flags = 0); + ProgressDialog(QWidget *parent = 0, Qt::WindowFlags flags = Qt::WindowFlags()); virtual ~ProgressDialog(); void setEndMessage(const QString & message) {_endMessage = message;} // Message shown when the progress is finished diff --git a/guilib/include/rtabmap/utilite/UPlot.h b/guilib/include/rtabmap/utilite/UPlot.h index 21ad58968a..3d78729211 100644 --- a/guilib/include/rtabmap/utilite/UPlot.h +++ b/guilib/include/rtabmap/utilite/UPlot.h @@ -32,6 +32,7 @@ #include #include #include +#include class QGraphicsView; class QGraphicsScene; @@ -602,9 +603,9 @@ private Q_SLOTS: UOrientableLabel * _yLabel; QLabel * _refreshRate; QString _workingDirectory; - QTime _refreshIntervalTime; + QElapsedTimer _refreshIntervalTime; int _lowestRefreshRate; - QTime _refreshStartTime; + QElapsedTimer _refreshStartTime; QString _autoScreenCaptureFormat; QPoint _mousePressedPos; QPoint _mouseCurrentPos; diff --git a/guilib/src/3rdParty/QMultiComboBox.cpp b/guilib/src/3rdParty/QMultiComboBox.cpp index fe07837015..fc7673856e 100644 --- a/guilib/src/3rdParty/QMultiComboBox.cpp +++ b/guilib/src/3rdParty/QMultiComboBox.cpp @@ -11,7 +11,8 @@ #include "QMultiComboBox.h" #include #include -#include +#include +#include #include "rtabmap/utilite/ULogger.h" @@ -46,7 +47,11 @@ QMultiComboBox::~QMultiComboBox() void QMultiComboBox::SetDisplayText(QString text) { m_DisplayText_ = text; +#if QT_VERSION >= QT_VERSION_CHECK(5, 15, 0) + const int textWidth = fontMetrics().horizontalAdvance(text); +#else const int textWidth = fontMetrics().width(text); +#endif setMinimumWidth(textWidth + 30); updateGeometry(); repaint(); @@ -88,7 +93,7 @@ void QMultiComboBox::showPopup() //QRect rec2(p , p + QPoint(rec.width(), rec.height())); // get the two possible list points and height - QRect screen = QApplication::desktop()->screenGeometry(this); + QRect screen = this->window()->windowHandle()->screen()->availableGeometry(); QPoint above = this->mapToGlobal(QPoint(0,0)); int aboveHeight = above.y() - screen.y(); QPoint below = this->mapToGlobal(QPoint(0,rec.height())); diff --git a/guilib/src/CMakeLists.txt b/guilib/src/CMakeLists.txt index 44d218dd97..1f8d76070b 100644 --- a/guilib/src/CMakeLists.txt +++ b/guilib/src/CMakeLists.txt @@ -70,10 +70,14 @@ IF(QT4_FOUND) #This will generate moc_* for Qt QT4_WRAP_CPP(moc_srcs ${headers_ui}) ### Qt Gui stuff end### -ELSE() +ELSEIF(Qt5_FOUND) QT5_ADD_RESOURCES(srcs_qrc ${qrc}) QT5_WRAP_UI(moc_uis ${uis}) QT5_WRAP_CPP(moc_srcs ${headers_ui}) +ELSE() + QT6_ADD_RESOURCES(srcs_qrc ${qrc}) + QT6_WRAP_UI(moc_uis ${uis}) + QT6_WRAP_CPP(moc_srcs ${headers_ui}) ENDIF() @@ -140,8 +144,14 @@ ENDIF(QT4_FOUND) SET(LIBRARIES "") SET(PUBLIC_LIBRARIES "") -IF(Qt5_FOUND) - SET(PUBLIC_LIBRARIES ${PUBLIC_LIBRARIES} Qt5::Widgets Qt5::Core Qt5::Gui) +IF(Qt6_FOUND) + SET(PUBLIC_LIBRARIES ${PUBLIC_LIBRARIES} Qt6::Widgets Qt6::Core Qt6::Gui Qt6::OpenGL) + SET(LIBRARIES ${LIBRARIES} Qt6::PrintSupport) + IF(Qt6Svg_FOUND) + SET(LIBRARIES ${LIBRARIES} Qt6::Svg) + ENDIF() +ELSEIF(Qt5_FOUND) + SET(PUBLIC_LIBRARIES ${PUBLIC_LIBRARIES} Qt5::Widgets Qt5::Core Qt5::Gui Qt5::OpenGL) SET(LIBRARIES ${LIBRARIES} Qt5::PrintSupport) IF(Qt5Svg_FOUND) SET(LIBRARIES ${LIBRARIES} Qt5::Svg) diff --git a/guilib/src/CameraViewer.cpp b/guilib/src/CameraViewer.cpp index cb9fd04356..569721ed18 100644 --- a/guilib/src/CameraViewer.cpp +++ b/guilib/src/CameraViewer.cpp @@ -59,7 +59,7 @@ CameraViewer::CameraViewer(QWidget * parent, const ParametersMap & parameters) : imageView_->setImageDepthShown(true); imageView_->setMinimumSize(320, 240); QHBoxLayout * layout = new QHBoxLayout(); - layout->setMargin(0); + layout->setContentsMargins(0,0,0,0); layout->addWidget(imageView_,1); layout->addWidget(cloudView_,1); @@ -95,7 +95,7 @@ CameraViewer::CameraViewer(QWidget * parent, const ParametersMap & parameters) : layout2->addWidget(buttonBox); QVBoxLayout * vlayout = new QVBoxLayout(this); - vlayout->setMargin(0); + vlayout->setContentsMargins(0,0,0,0); vlayout->setSpacing(0); vlayout->addLayout(layout, 1); vlayout->addLayout(layout2); diff --git a/guilib/src/CloudViewer.cpp b/guilib/src/CloudViewer.cpp index d2b41d52b5..5b6d239c72 100644 --- a/guilib/src/CloudViewer.cpp +++ b/guilib/src/CloudViewer.cpp @@ -40,6 +40,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include +#include #include #include #include diff --git a/guilib/src/DataRecorder.cpp b/guilib/src/DataRecorder.cpp index 5edeb40289..3af6637f36 100644 --- a/guilib/src/DataRecorder.cpp +++ b/guilib/src/DataRecorder.cpp @@ -58,7 +58,7 @@ DataRecorder::DataRecorder(QWidget * parent) : imageView_->setImageDepthShown(true); imageView_->setMinimumSize(320, 240); QVBoxLayout * layout = new QVBoxLayout(this); - layout->setMargin(0); + layout->setContentsMargins(0,0,0,0); layout->addWidget(imageView_); layout->addWidget(label_); layout->setStretch(0,1); diff --git a/guilib/src/DatabaseViewer.cpp b/guilib/src/DatabaseViewer.cpp index 9fbe7a37ab..51cb2e98e6 100644 --- a/guilib/src/DatabaseViewer.cpp +++ b/guilib/src/DatabaseViewer.cpp @@ -31,7 +31,6 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include -#include #include #include #include @@ -1685,7 +1684,11 @@ void DatabaseViewer::updateIds() UINFO("Loading all IDs..."); std::set ids; dbDriver_->getAllNodeIds(ids); +#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0) + ids_ = QList(ids.begin(), ids.end()); +#else ids_ = QList::fromStdList(std::list(ids.begin(), ids.end())); +#endif lastWmIds_.clear(); dbDriver_->getLastNodeIds(lastWmIds_); idToIndex_.clear(); @@ -2222,10 +2225,18 @@ void DatabaseViewer::updateInfo() ui_->textEdit_info->append(""); ParametersMap parameters = dbDriver_->getLastParameters(); QFontMetrics metrics(ui_->textEdit_info->font()); +#if QT_VERSION >= QT_VERSION_CHECK(5, 15, 0) + int tabW = ui_->textEdit_info->tabStopDistance(); +#else int tabW = ui_->textEdit_info->tabStopWidth(); +#endif for(ParametersMap::iterator iter=parameters.begin(); iter!=parameters.end(); ++iter) { +#if QT_VERSION >= QT_VERSION_CHECK(5, 15, 0) + int strW = metrics.horizontalAdvance(QString(iter->first.c_str()) + "="); +#else int strW = metrics.width(QString(iter->first.c_str()) + "="); +#endif ui_->textEdit_info->append(tr("%1=%2%3") .arg(iter->first.c_str()) .arg(strW < tabW?"\t\t\t\t":strW < tabW*2?"\t\t\t":strW < tabW*3?"\t\t":"\t") @@ -3889,7 +3900,11 @@ void DatabaseViewer::regenerateCurrentLocalMaps() QSet idsSet; idsSet.insert(ids_.at(ui_->horizontalSlider_A->value())); idsSet.insert(ids_.at(ui_->horizontalSlider_B->value())); +#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0) + QList ids(idsSet.begin(), idsSet.end()); +#else QList ids = idsSet.toList(); +#endif rtabmap::ProgressDialog progressDialog(this); progressDialog.setMaximumSteps(ids.size()); @@ -6832,7 +6847,7 @@ void DatabaseViewer::sliderIterationsValueChanged(int value) if(graph.size() && localMaps.size() && (ui_->graphViewer->isGridMapVisible() || ui_->dockWidget_occupancyGridView->isVisible())) { - QTime time; + QElapsedTimer time; time.start(); #ifdef RTABMAP_OCTOMAP @@ -7509,7 +7524,7 @@ void DatabaseViewer::updateGraphView() posesOut, linksOut); UINFO("Connected graph of %d poses and %d links", (int)posesOut.size(), (int)linksOut.size()); - QTime time; + QElapsedTimer time; time.start(); std::map finalPoses = optimizer->optimize(fromId, posesOut, linksOut, ui_->comboBox_optimizationFlavor->currentIndex()==0?&graphes_:0); ui_->label_timeOptimization->setNum(double(time.elapsed())/1000.0); diff --git a/guilib/src/DepthCalibrationDialog.cpp b/guilib/src/DepthCalibrationDialog.cpp index 9654c664bd..dbdc1135bd 100644 --- a/guilib/src/DepthCalibrationDialog.cpp +++ b/guilib/src/DepthCalibrationDialog.cpp @@ -465,7 +465,7 @@ void DepthCalibrationDialog::calibrate( ImageView * imageView2 = new ImageView(dialog); imageView2->setMinimumSize(320, 240); QVBoxLayout * vlayout = new QVBoxLayout(); - vlayout->setMargin(0); + vlayout->setContentsMargins(0,0,0,0); vlayout->addWidget(imageView1, 1); vlayout->addWidget(imageView2, 1); dialog->setLayout(vlayout); diff --git a/guilib/src/EditDepthArea.cpp b/guilib/src/EditDepthArea.cpp index 4be707ed5d..027bfb7d7b 100644 --- a/guilib/src/EditDepthArea.cpp +++ b/guilib/src/EditDepthArea.cpp @@ -30,6 +30,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include +#include #include #include "rtabmap/gui/EditDepthArea.h" diff --git a/guilib/src/EditMapArea.cpp b/guilib/src/EditMapArea.cpp index d61f882c97..f16217be1f 100644 --- a/guilib/src/EditMapArea.cpp +++ b/guilib/src/EditMapArea.cpp @@ -30,6 +30,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include +#include #include #include "rtabmap/gui/EditMapArea.h" diff --git a/guilib/src/ExportCloudsDialog.cpp b/guilib/src/ExportCloudsDialog.cpp index 9def478149..378ddbae15 100644 --- a/guilib/src/ExportCloudsDialog.cpp +++ b/guilib/src/ExportCloudsDialog.cpp @@ -62,7 +62,8 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include -#include +#include +#include #ifdef RTABMAP_CPUTSDF #include @@ -1212,7 +1213,7 @@ void ExportCloudsDialog::viewClouds( } window->setMinimumWidth(120); window->setMinimumHeight(90); - window->resize(QDesktopWidget().availableGeometry(this).size() * 0.7); + window->resize(this->window()->windowHandle()->screen()->availableGeometry().size() * 0.7); CloudViewer * viewer = new CloudViewer(window); if(_ui->comboBox_pipeline->currentIndex() == 0) @@ -4169,7 +4170,7 @@ void ExportCloudsDialog::saveClouds( #else QString extensions = tr("Save clouds to (*.ply *.pcd)..."); #endif - QString path = QFileDialog::getExistingDirectory(this, extensions, workingDirectory, 0); + QString path = QFileDialog::getExistingDirectory(this, extensions, workingDirectory, QFileDialog::ShowDirsOnly); if(!path.isEmpty()) { bool ok = false; @@ -4394,7 +4395,7 @@ void ExportCloudsDialog::saveMeshes( } else if(meshes.size()) { - QString path = QFileDialog::getExistingDirectory(this, tr("Save meshes to (*.ply *.obj)..."), workingDirectory, 0); + QString path = QFileDialog::getExistingDirectory(this, tr("Save meshes to (*.ply *.obj)..."), workingDirectory, QFileDialog::ShowDirsOnly); if(!path.isEmpty()) { bool ok = false; @@ -4799,7 +4800,7 @@ void ExportCloudsDialog::saveTextureMeshes( } else if(meshes.size()) { - QString path = QFileDialog::getExistingDirectory(this, tr("Save texture meshes to (*.obj)..."), workingDirectory, 0); + QString path = QFileDialog::getExistingDirectory(this, tr("Save texture meshes to (*.obj)..."), workingDirectory, QFileDialog::ShowDirsOnly); if(!path.isEmpty()) { bool ok = false; diff --git a/guilib/src/GraphViewer.cpp b/guilib/src/GraphViewer.cpp index cbb97eda8b..0953e93d34 100644 --- a/guilib/src/GraphViewer.cpp +++ b/guilib/src/GraphViewer.cpp @@ -1777,7 +1777,7 @@ void GraphViewer::restoreDefaults() void GraphViewer::wheelEvent ( QWheelEvent * event ) { - if(event->delta() < 0) + if(event->angleDelta().y() < 0) { this->scale(0.95, 0.95); } @@ -2039,7 +2039,7 @@ void GraphViewer::contextMenuEvent(QContextMenuEvent * event) if(QFileInfo(filePath).suffix().compare("pdf") == 0) { QPrinter printer(QPrinter::HighResolution); - printer.setOrientation(QPrinter::Portrait); + printer.setPageOrientation(QPageLayout::Portrait); printer.setOutputFileName( filePath ); QPainter p(&printer); scene()->render(&p); diff --git a/guilib/src/ImageView.cpp b/guilib/src/ImageView.cpp index 4ce9777408..118954a8c4 100644 --- a/guilib/src/ImageView.cpp +++ b/guilib/src/ImageView.cpp @@ -33,6 +33,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include +#include #include #include #include @@ -880,12 +881,12 @@ void ImageView::contextMenuEvent(QContextMenuEvent * e) if(QFileInfo(text).suffix().compare("pdf") == 0) { QPrinter printer(QPrinter::HighResolution); - printer.setOrientation(QPrinter::Portrait); + printer.setPageOrientation(QPageLayout::Portrait); printer.setOutputFileName( text ); QPainter p(&printer); p.begin(&printer); - double xscale = printer.pageRect().width()/double(_graphicsView->sceneRect().width()); - double yscale = printer.pageRect().height()/double(_graphicsView->sceneRect().height()); + double xscale = printer.pageLayout().paintRectPixels(printer.resolution()).width()/double(_graphicsView->sceneRect().width()); + double yscale = printer.pageLayout().paintRectPixels(printer.resolution()).height()/double(_graphicsView->sceneRect().height()); double scale = qMin(xscale, yscale); p.scale(scale, scale); _graphicsView->scene()->render(&p, _graphicsView->sceneRect(), _graphicsView->sceneRect()); diff --git a/guilib/src/MainWindow.cpp b/guilib/src/MainWindow.cpp index 2a91e41838..8b0811957a 100644 --- a/guilib/src/MainWindow.cpp +++ b/guilib/src/MainWindow.cpp @@ -168,6 +168,7 @@ MainWindow::MainWindow(PreferencesDialog * prefDialog, QWidget * parent, bool sh _processingOdometry(false), _oneSecondTimer(0), _elapsedTime(0), + _logEventTime(0), _posteriorCurve(0), _likelihoodCurve(0), _rawLikelihoodCurve(0), @@ -266,10 +267,10 @@ MainWindow::MainWindow(PreferencesDialog * prefDialog, QWidget * parent, bool sh // Timer _oneSecondTimer = new QTimer(this); _oneSecondTimer->setInterval(1000); - _elapsedTime = new QTime(); + _elapsedTime = new QElapsedTimer(); _ui->label_elapsedTime->setText("00:00:00"); connect(_oneSecondTimer, SIGNAL(timeout()), this, SLOT(updateElapsedTime())); - _logEventTime = new QTime(); + _logEventTime = new QElapsedTimer(); _logEventTime->start(); //Graphics scenes @@ -694,6 +695,7 @@ MainWindow::~MainWindow() this->stopDetection(); delete _ui; delete _elapsedTime; + delete _logEventTime; #ifdef RTABMAP_OCTOMAP delete _octomap; #endif @@ -1893,7 +1895,7 @@ void MainWindow::processStats(const rtabmap::Statistics & stat) { _processingStatistics = true; ULOGGER_DEBUG(""); - QTime time, totalTime; + QElapsedTimer time, totalTime; time.start(); totalTime.start(); //Affichage des stats et images @@ -4968,7 +4970,12 @@ void MainWindow::drawKeypoints(const std::multimap & refWords { _lastId = (*refWords.rbegin()).first; } - _lastIds = QSet::fromList(QList::fromStdList(uKeysList(refWords))); + std::list kpts = uKeysList(refWords); +#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0) + _lastIds = QSet(kpts.begin(), kpts.end()); +#else + _lastIds = QSet::fromList(QList::fromStdList(kpts)); +#endif } // Draw lines between corresponding features... @@ -5211,7 +5218,7 @@ QString MainWindow::captureScreen(bool cacheInRAM, bool png) { QString name = (QDateTime::currentDateTime().toString("yyMMddhhmmsszzz") + (png?".png":".jpg")); _ui->statusbar->clearMessage(); - QPixmap figure = QPixmap::grabWidget(this); + QPixmap figure = this->grab(); QString targetDir = _preferencesDialog->getWorkingDirectory() + QDir::separator() + "ScreensCaptured"; QString msg; diff --git a/guilib/src/OdometryViewer.cpp b/guilib/src/OdometryViewer.cpp index ae46022dcf..27c6125565 100644 --- a/guilib/src/OdometryViewer.cpp +++ b/guilib/src/OdometryViewer.cpp @@ -126,13 +126,13 @@ OdometryViewer::OdometryViewer( //layout QHBoxLayout * layout = new QHBoxLayout(); - layout->setMargin(0); + layout->setContentsMargins(0,0,0,0); layout->setSpacing(0); layout->addWidget(imageView_,1); layout->addWidget(cloudView_,1); QHBoxLayout * hlayout2 = new QHBoxLayout(); - hlayout2->setMargin(0); + hlayout2->setContentsMargins(0,0,0,0); hlayout2->addWidget(maxCloudsLabel); hlayout2->addWidget(maxCloudsSpin_); hlayout2->addWidget(voxelLabel); @@ -151,7 +151,7 @@ OdometryViewer::OdometryViewer( hlayout2->addWidget(closeButton); QVBoxLayout * vlayout = new QVBoxLayout(this); - vlayout->setMargin(0); + vlayout->setContentsMargins(0,0,0,0); vlayout->setSpacing(0); vlayout->addLayout(layout, 1); vlayout->addLayout(hlayout2); diff --git a/guilib/src/StatsToolBox.cpp b/guilib/src/StatsToolBox.cpp index bda8a167b9..ce0daf3fc8 100644 --- a/guilib/src/StatsToolBox.cpp +++ b/guilib/src/StatsToolBox.cpp @@ -170,7 +170,7 @@ void StatItem::setupUi(QGridLayout * grid) layout->addWidget(_value); layout->addWidget(_unit); layout->addStretch(); - layout->setMargin(0); + layout->setContentsMargins(0,0,0,0); } } @@ -220,7 +220,7 @@ StatsToolBox::StatsToolBox(QWidget * parent) : //Statistics in the GUI (for plotting) _statBox = new QToolBox(this); this->setLayout(new QVBoxLayout()); - this->layout()->setMargin(0); + this->layout()->setContentsMargins(0,0,0,0); this->layout()->addWidget(_statBox); _statBox->layout()->setSpacing(0); _plotMenu = new QMenu(this); diff --git a/guilib/src/opencv/vtkImageMatSource.cpp b/guilib/src/opencv/vtkImageMatSource.cpp index 24a91f347e..2914ffbe32 100644 --- a/guilib/src/opencv/vtkImageMatSource.cpp +++ b/guilib/src/opencv/vtkImageMatSource.cpp @@ -48,6 +48,7 @@ #include #include #include +#include namespace rtabmap { vtkStandardNewMacro(vtkImageMatSource); diff --git a/guilib/src/utilite/UPlot.cpp b/guilib/src/utilite/UPlot.cpp index 5928d7e3f7..26f275d35c 100644 --- a/guilib/src/utilite/UPlot.cpp +++ b/guilib/src/utilite/UPlot.cpp @@ -37,6 +37,7 @@ #include #include #include +#include #include #include #include @@ -788,28 +789,44 @@ void UPlotCurve::draw(QPainter * painter, const QRect & limits) { QPointF intersection; QLineF::IntersectType type; +#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0) + type = lineItem->line().intersects(QLineF(limits.topLeft(), limits.bottomLeft()), &intersection); +#else type = lineItem->line().intersect(QLineF(limits.topLeft(), limits.bottomLeft()), &intersection); +#endif if(type == QLineF::BoundedIntersection) { !limits.contains(line.p1())?line.setP1(intersection.toPoint()):line.setP2(intersection.toPoint()); } else { +#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0) + type = lineItem->line().intersects(QLineF(limits.topLeft(), limits.topRight()), &intersection); +#else type = lineItem->line().intersect(QLineF(limits.topLeft(), limits.topRight()), &intersection); +#endif if(type == QLineF::BoundedIntersection) { !limits.contains(line.p1())?line.setP1(intersection.toPoint()):line.setP2(intersection.toPoint()); } else { +#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0) + type = lineItem->line().intersects(QLineF(limits.bottomLeft(), limits.bottomRight()), &intersection); +#else type = lineItem->line().intersect(QLineF(limits.bottomLeft(), limits.bottomRight()), &intersection); +#endif if(type == QLineF::BoundedIntersection) { !limits.contains(line.p1())?line.setP1(intersection.toPoint()):line.setP2(intersection.toPoint()); } else { +#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0) + type = lineItem->line().intersects(QLineF(limits.topRight(), limits.bottomRight()), &intersection); +#else type = lineItem->line().intersect(QLineF(limits.topRight(), limits.bottomRight()), &intersection); +#endif if(type == QLineF::BoundedIntersection) { !limits.contains(line.p1())?line.setP1(intersection.toPoint()):line.setP2(intersection.toPoint()); @@ -968,7 +985,7 @@ void UPlotCurve::setData(const std::vector & x, const std::vector void UPlotCurve::setData(const QVector & y) { - this->setData(y.toStdVector()); + this->setData(std::vector(y.begin(), y.end())); } void UPlotCurve::setData(const std::vector & y) @@ -1194,8 +1211,13 @@ void UPlotAxis::setAxis(qreal & min, qreal & max) } else { +#if QT_VERSION >= QT_VERSION_CHECK(5, 15, 0) + borderMin = this->fontMetrics().horizontalAdvance(QString::number(_min,'g',_gradMaxDigits))/2; + borderMax = this->fontMetrics().horizontalAdvance(QString::number(_max,'g',_gradMaxDigits))/2; +#else borderMin = this->fontMetrics().width(QString::number(_min,'g',_gradMaxDigits))/2; borderMax = this->fontMetrics().width(QString::number(_max,'g',_gradMaxDigits))/2; +#endif } int border = borderMin>borderMax?borderMin:borderMax; int borderDelta; @@ -1303,10 +1325,18 @@ void UPlotAxis::setAxis(qreal & min, qreal & max) for (int i = 0; i <= _count; i+=5) { QString n(QString::number(_min + (i/5)*((_max-_min)/(_count/5)),'g',_gradMaxDigits)); +#if QT_VERSION >= QT_VERSION_CHECK(5, 15, 0) + if(this->fontMetrics().horizontalAdvance(n) > minWidth) + { + minWidth = this->fontMetrics().horizontalAdvance(n); + } +#else if(this->fontMetrics().width(n) > minWidth) { minWidth = this->fontMetrics().width(n); } +#endif + } this->setMinimumWidth(15+minWidth); } @@ -1592,7 +1622,7 @@ void UPlotLegend::addItem(UPlotCurve * curve) QHBoxLayout * hLayout = new QHBoxLayout(); hLayout->addWidget(legendItem); hLayout->addStretch(0); - hLayout->setMargin(0); + hLayout->setContentsMargins(0,0,0,0); // add to the legend ((QVBoxLayout*)_contentLayout)->insertLayout(_contentLayout->count()-1, hLayout); @@ -1644,7 +1674,7 @@ void UPlotLegend::moveUp(UPlotLegendItem * item) QHBoxLayout * hLayout = new QHBoxLayout(); hLayout->addWidget(layoutItem->layout()->itemAt(0)->widget()); hLayout->addStretch(0); - hLayout->setMargin(0); + hLayout->setContentsMargins(0,0,0,0); ((QVBoxLayout*)_contentLayout)->insertLayout(index-1, hLayout); delete layoutItem; Q_EMIT legendItemMoved(item->curve(), index-1); @@ -1671,7 +1701,7 @@ void UPlotLegend::moveDown(UPlotLegendItem * item) QHBoxLayout * hLayout = new QHBoxLayout(); hLayout->addWidget(layoutItem->layout()->itemAt(0)->widget()); hLayout->addStretch(0); - hLayout->setMargin(0); + hLayout->setContentsMargins(0,0,0,0); ((QVBoxLayout*)_contentLayout)->insertLayout(index+1, hLayout); delete layoutItem; Q_EMIT legendItemMoved(item->curve(), index+1); @@ -1694,7 +1724,7 @@ QString UPlotLegend::getAllCurveDataAsText() const xAxisMap.insert(iter.key(), iter.value()); } } - QList xAxis = xAxisMap.uniqueKeys(); + QList xAxis = xAxisMap.keys(); QVector > axes; for(int i=0; iisChecked() && xPos>=0 && yPos>=0 && xPos<_graphicsViewHolder->width() && yPos<_graphicsViewHolder->height())) { +#if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0) + QToolTip::showText(event->globalPosition().toPoint(), QString("%1,%2").arg(x).arg(y)); +#else QToolTip::showText(event->globalPos(), QString("%1,%2").arg(x).arg(y)); +#endif } else { @@ -2831,8 +2865,8 @@ void UPlot::contextMenuEvent(QContextMenuEvent * event) QPalette p(palette()); // Set background color to white - QColor c = p.color(QPalette::Background); - p.setColor(QPalette::Background, Qt::white); + QColor c = p.color(QPalette::Window); + p.setColor(QPalette::Window, Qt::white); setPalette(p); #ifdef QT_SVG_LIB @@ -2858,14 +2892,14 @@ void UPlot::contextMenuEvent(QContextMenuEvent * event) } else { - QPixmap figure = QPixmap::grabWidget(this); + QPixmap figure = this->grab(); figure.save(text); } #ifdef QT_SVG_LIB } #endif // revert background color - p.setColor(QPalette::Background, c); + p.setColor(QPalette::Window, c); setPalette(p); if(flatModified) @@ -2923,7 +2957,7 @@ void UPlot::captureScreen() } targetDir += "/"; QString name = (QDateTime::currentDateTime().toString("yyMMddhhmmsszzz") + ".") + _autoScreenCaptureFormat; - QPixmap figure = QPixmap::grabWidget(this); + QPixmap figure = this->grab(); figure.save(targetDir + name); } @@ -3181,7 +3215,7 @@ void UPlot::removeCurves() void UPlot::removeCurve(const UPlotCurve * curve) { - QList::iterator iter = qFind(_curves.begin(), _curves.end(), curve); + QList::iterator iter = std::find(_curves.begin(), _curves.end(), curve); #if PRINT_DEBUG ULOGGER_DEBUG("Plot=\"%s\" removing curve=\"%s\"", this->objectName().toStdString().c_str(), curve?curve->name().toStdString().c_str():""); #endif @@ -3215,7 +3249,7 @@ void UPlot::removeCurve(const UPlotCurve * curve) void UPlot::showCurve(const UPlotCurve * curve, bool shown) { - QList::iterator iter = qFind(_curves.begin(), _curves.end(), curve); + QList::iterator iter = std::find(_curves.begin(), _curves.end(), curve); if(iter!=_curves.end()) { UPlotCurve * value = *iter; diff --git a/tools/EpipolarGeometry/main.cpp b/tools/EpipolarGeometry/main.cpp index 93fe8ae534..aa309fa97f 100644 --- a/tools/EpipolarGeometry/main.cpp +++ b/tools/EpipolarGeometry/main.cpp @@ -51,6 +51,7 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include #include +#include #include @@ -183,11 +184,10 @@ int main(int argc, char** argv) showUsage(); } - QTime timer; + QElapsedTimer timer; timer.start(); // Extract words - timer.start(); VWDictionary dictionary; ParametersMap param; param.insert(ParametersPair(Parameters::kSURFExtended(), "true"));