From 54e36bc940e5aad53f44396d0d16967a84090ab4 Mon Sep 17 00:00:00 2001 From: David Anthony Date: Wed, 20 Sep 2023 14:15:08 -0500 Subject: [PATCH] Cleaning up old distro support and removing build warnigns --- CMakeLists.txt | 16 +--------------- include/swri_console/defines.h | 14 -------------- src/console_window.cpp | 19 +++++++++++++------ src/ros_thread.cpp | 11 ----------- 4 files changed, 14 insertions(+), 46 deletions(-) delete mode 100644 include/swri_console/defines.h diff --git a/CMakeLists.txt b/CMakeLists.txt index 318f773..78579f8 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,7 +1,7 @@ cmake_minimum_required(VERSION 3.10) if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 14) + set(CMAKE_CXX_STANDARD 17) endif() if (CMAKE_COMPILER_IS_GNUCXX OR CMAKE_COMPILER_ID MATCHES "Clang") @@ -12,7 +12,6 @@ project(swri_console) ### ROS PACKAGES ### find_package(ament_cmake REQUIRED) -# find_package(rosbag_storage REQUIRED) find_package(rclcpp REQUIRED) find_package(rcl_interfaces REQUIRED) @@ -23,13 +22,6 @@ find_package(Qt5Widgets REQUIRED) find_package(Boost COMPONENTS thread REQUIRED) -### Compile flag to support different versions of ROS ### -if($ENV{ROS_DISTRO} STRGREATER "foxy") - set(USE_NEW_QOS_DEFN 1) -else() - set(USE_NEW_QOS_DEFN 0) -endif() - set(CMAKE_INCLUDE_CURRENT_DIR ON) include_directories(include) @@ -38,7 +30,6 @@ set(UI_FILES ui/console_window.ui) set(HEADER_FILES include/swri_console/bag_reader.h - include/swri_console/defines.h include/swri_console/console_master.h include/swri_console/console_window.h include/swri_console/log_database.h @@ -66,11 +57,6 @@ qt5_wrap_cpp(SRC_FILES ${HEADER_FILES}) add_executable(swri_console ${HEADER_FILES} ${SRC_FILES} ${RCC_SRCS} src/main.cpp) -target_compile_definitions(swri_console - PRIVATE - USE_NEW_QOS_DEFN=${USE_NEW_QOS_DEFN} -) - target_link_libraries(swri_console Qt5::Core Qt5::Gui diff --git a/include/swri_console/defines.h b/include/swri_console/defines.h deleted file mode 100644 index 01775fa..0000000 --- a/include/swri_console/defines.h +++ /dev/null @@ -1,14 +0,0 @@ -#ifndef SWRI_CONSOLE_DEFINES_H_ -#define SWRI_CONSOLE_DEFINES_H_ - -#include - -namespace LogLevelMask { - const uint8_t DEBUG = 0x01; - const uint8_t INFO = 0x02; - const uint8_t WARN = 0x04; - const uint8_t ERROR = 0x08; - const uint8_t FATAL = 0x10; -}; - -#endif // DEFINES_H diff --git a/src/console_window.cpp b/src/console_window.cpp index cdd37f0..31d6b1f 100644 --- a/src/console_window.cpp +++ b/src/console_window.cpp @@ -42,7 +42,6 @@ #include #include #include -#include #include #include @@ -65,6 +64,14 @@ using namespace Qt; +namespace log_level_mask { + static constexpr uint8_t DEBUG = 1 << 0; + static constexpr uint8_t INFO = 1 << 1; + static constexpr uint8_t WARN = 1 << 2; + static constexpr uint8_t ERROR = 1 << 3; + static constexpr uint8_t FATAL = 1 << 4; +}; + namespace swri_console { ConsoleWindow::ConsoleWindow(LogDatabase *db) @@ -286,19 +293,19 @@ void ConsoleWindow::setSeverityFilter() uint8_t mask = 0; if (ui.checkDebug->isChecked()) { - mask |= LogLevelMask::DEBUG; + mask |= log_level_mask::DEBUG; } if (ui.checkInfo->isChecked()) { - mask |= LogLevelMask::INFO; + mask |= log_level_mask::INFO; } if (ui.checkWarn->isChecked()) { - mask |= LogLevelMask::WARN; + mask |= log_level_mask::WARN; } if (ui.checkError->isChecked()) { - mask |= LogLevelMask::ERROR; + mask |= log_level_mask::ERROR; } if (ui.checkFatal->isChecked()) { - mask |= LogLevelMask::FATAL; + mask |= log_level_mask::FATAL; } QSettings settings; diff --git a/src/ros_thread.cpp b/src/ros_thread.cpp index eb38a7f..d498f2c 100644 --- a/src/ros_thread.cpp +++ b/src/ros_thread.cpp @@ -121,18 +121,7 @@ void RosThread::emptyLogQueue(rcl_interfaces::msg::Log::ConstSharedPtr msg) rclcpp::QoS RosThread::getQos() { -#if USE_NEW_QOS_DEFN == 0 - // Foxy does not have a rosout QoS profile, so we copy the initialization from - // rclc/logging_rosout.c - auto qos_profile = rmw_qos_profile_default; - qos_profile.depth = 1000; - qos_profile.durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL; - qos_profile.lifespan.sec = 10; - qos_profile.lifespan.nsec = 0; - return rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile)); -#else // Humble and on can use the same QoS as the standard rosout config return rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rcl_qos_profile_rosout_default)); -#endif } }