From 631e7027c4b1f1a603f9dc8abf216766378f0094 Mon Sep 17 00:00:00 2001 From: Denis Draca Date: Fri, 27 Sep 2024 12:02:06 +1000 Subject: [PATCH 1/7] chore: windows compatibility --- diagnostic_updater/CMakeLists.txt | 125 +++++++++++++++--------------- 1 file changed, 64 insertions(+), 61 deletions(-) diff --git a/diagnostic_updater/CMakeLists.txt b/diagnostic_updater/CMakeLists.txt index ebca013e..72b0e421 100644 --- a/diagnostic_updater/CMakeLists.txt +++ b/diagnostic_updater/CMakeLists.txt @@ -18,7 +18,9 @@ find_package(rclcpp REQUIRED) find_package(rclpy REQUIRED) find_package(std_msgs REQUIRED) -add_library(${PROJECT_NAME} +set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) + +add_library(${PROJECT_NAME} STATIC src/diagnostic_updater.cpp ) target_include_directories( @@ -27,6 +29,7 @@ target_include_directories( $ $ ) + ament_target_dependencies( ${PROJECT_NAME} PUBLIC @@ -39,65 +42,65 @@ install( EXPORT ${PROJECT_NAME}Targets LIBRARY DESTINATION lib ARCHIVE DESTINATION lib - RUNTIME DESTINATION bin + RUNTIME DESTINATION lib/${PROJECT_NAME} INCLUDES DESTINATION include ) -add_executable(example src/example.cpp) -ament_target_dependencies( - example - "diagnostic_msgs" - "rclcpp" - "std_msgs" -) -target_link_libraries(example ${PROJECT_NAME}) - -if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - set(ament_cmake_copyright_FOUND TRUE) - set(ament_cmake_flake8_FOUND TRUE) # skip for https://github.com/ros-tooling/action-ros-lint/issues/354 - ament_lint_auto_find_test_dependencies() - - find_package(ament_cmake_gtest REQUIRED) - find_package(rclcpp_lifecycle REQUIRED) - ament_add_gtest(diagnostic_updater_test test/diagnostic_updater_test.cpp) - target_include_directories(diagnostic_updater_test - PUBLIC - $ - $ - ) - target_link_libraries(diagnostic_updater_test ${PROJECT_NAME}) - ament_target_dependencies( - diagnostic_updater_test - "rclcpp_lifecycle" - ) - - ament_add_gtest(diagnostic_status_wrapper_test test/diagnostic_status_wrapper_test.cpp) - target_include_directories(diagnostic_status_wrapper_test - PUBLIC - $ - $ - ) - ament_target_dependencies( - diagnostic_status_wrapper_test - "diagnostic_msgs" - "rclcpp" - "rclcpp_lifecycle" - "std_msgs" - ) - ament_add_gtest(status_msg_test test/status_msg_test.cpp) - target_include_directories(status_msg_test - PUBLIC - $ - $ - ) - target_link_libraries(status_msg_test ${PROJECT_NAME}) - - find_package(ament_cmake_pytest REQUIRED) - ament_add_pytest_test(diagnostic_updater_test.py "test/diagnostic_updater_test.py") - ament_add_pytest_test(test_DiagnosticStatusWrapper.py "test/test_diagnostic_status_wrapper.py") - ament_add_pytest_test(status_msg_test.py "test/status_msg_test.py") -endif() +# add_executable(example src/example.cpp) +# ament_target_dependencies( +# example +# "diagnostic_msgs" +# "rclcpp" +# "std_msgs" +# ) +# target_link_libraries(example ${PROJECT_NAME}) + +# if(BUILD_TESTING) +# find_package(ament_lint_auto REQUIRED) +# set(ament_cmake_copyright_FOUND TRUE) +# set(ament_cmake_flake8_FOUND TRUE) # skip for https://github.com/ros-tooling/action-ros-lint/issues/354 +# ament_lint_auto_find_test_dependencies() + +# find_package(ament_cmake_gtest REQUIRED) +# find_package(rclcpp_lifecycle REQUIRED) +# ament_add_gtest(diagnostic_updater_test test/diagnostic_updater_test.cpp) +# target_include_directories(diagnostic_updater_test +# PUBLIC +# $ +# $ +# ) +# target_link_libraries(diagnostic_updater_test ${PROJECT_NAME}) +# ament_target_dependencies( +# diagnostic_updater_test +# "rclcpp_lifecycle" +# ) + +# ament_add_gtest(diagnostic_status_wrapper_test test/diagnostic_status_wrapper_test.cpp) +# target_include_directories(diagnostic_status_wrapper_test +# PUBLIC +# $ +# $ +# ) +# ament_target_dependencies( +# diagnostic_status_wrapper_test +# "diagnostic_msgs" +# "rclcpp" +# "rclcpp_lifecycle" +# "std_msgs" +# ) +# ament_add_gtest(status_msg_test test/status_msg_test.cpp) +# target_include_directories(status_msg_test +# PUBLIC +# $ +# $ +# ) +# target_link_libraries(status_msg_test ${PROJECT_NAME}) + +# find_package(ament_cmake_pytest REQUIRED) +# ament_add_pytest_test(diagnostic_updater_test.py "test/diagnostic_updater_test.py") +# ament_add_pytest_test(test_DiagnosticStatusWrapper.py "test/test_diagnostic_status_wrapper.py") +# ament_add_pytest_test(status_msg_test.py "test/status_msg_test.py") +# endif() ament_python_install_package(${PROJECT_NAME}) install( @@ -105,10 +108,10 @@ install( DESTINATION lib/${PROJECT_NAME} ) -install( - TARGETS example - DESTINATION lib/${PROJECT_NAME} -) +# install( +# TARGETS example +# DESTINATION lib/${PROJECT_NAME} +# ) install( DIRECTORY include/ From de91c5dc69ce9f7be91b21a5c403e2c413dd42cf Mon Sep 17 00:00:00 2001 From: David Revay Date: Fri, 13 Dec 2024 10:16:01 +1100 Subject: [PATCH 2/7] feat: add release workflow --- .github/workflows/release.yaml | 77 ++++++++++++++++++++++++++++++++++ 1 file changed, 77 insertions(+) create mode 100644 .github/workflows/release.yaml diff --git a/.github/workflows/release.yaml b/.github/workflows/release.yaml new file mode 100644 index 00000000..773cc805 --- /dev/null +++ b/.github/workflows/release.yaml @@ -0,0 +1,77 @@ +name: Tag & Release + +on: + workflow_dispatch: + inputs: + package: + type: choice + description: 'If not specified, all packages will be released.' + options: + - "" + - diagnostic_aggregator + - diagnostic_common_diagnostics + - diagnostic_updater + - diagnostics + - self_test + +jobs: + build: + strategy: + fail-fast: true + matrix: + job: + - runner: buildjet-2vcpu-ubuntu-2204 + arch: amd64 + ros_distro: iron + - runner: buildjet-4vcpu-ubuntu-2204-arm + arch: arm64 + ros_distro: iron + - runner: buildjet-2vcpu-ubuntu-2204 + arch: amd64 + ros_distro: jazzy + - runner: buildjet-4vcpu-ubuntu-2204-arm + arch: arm64 + ros_distro: jazzy + + name: Build - ${{ matrix.job.arch }} - ${{ matrix.job.ros_distro }} + runs-on: ${{ matrix.job.runner }} + + steps: + - name: Checkout this repository + uses: actions/checkout@v4 + + - name: Semantic release - Build + uses: Greenroom-Robotics/ros_semantic_release_action@main + with: + token: ${{ secrets.API_TOKEN_GITHUB }} + package: ${{ github.event.inputs.package }} + arch: ${{ matrix.job.arch }} + ros_distro: ${{ matrix.job.ros_distro }} + github_release: false + public: true + changelog: false + skip_build: false + skip_tag: true + release_branches: "ros2-iron" + + release: + name: Create Release + runs-on: buildjet-2vcpu-ubuntu-2204 + needs: + - build + + steps: + - name: Checkout this repository + uses: actions/checkout@v4 + + - name: Release + uses: Greenroom-Robotics/ros_semantic_release_action@main + with: + token: ${{ secrets.API_TOKEN_GITHUB }} + package: ${{ github.event.inputs.package }} + github_release: true + public: true + changelog: false + skip_build: true + skip_tag: false + release_branches: ros2 \ No newline at end of file From 61426ee144acfb0d931c930507e5fa5c6b038ede Mon Sep 17 00:00:00 2001 From: David Revay Date: Fri, 13 Dec 2024 10:16:52 +1100 Subject: [PATCH 3/7] chore: delete other workflows --- .github/workflows/lint.yaml | 45 ------------------------------------- .github/workflows/test.yaml | 37 ------------------------------ 2 files changed, 82 deletions(-) delete mode 100644 .github/workflows/lint.yaml delete mode 100644 .github/workflows/test.yaml diff --git a/.github/workflows/lint.yaml b/.github/workflows/lint.yaml deleted file mode 100644 index 4f926eef..00000000 --- a/.github/workflows/lint.yaml +++ /dev/null @@ -1,45 +0,0 @@ -name: Lint diagnostics -on: - pull_request: - push: - branches: - - ros2 - schedule: - # Run every week at 20:00 on Sunday - - cron: "0 20 * * 0" - -jobs: - ament_lint: - name: Lint ${{ matrix.linter }} - strategy: - fail-fast: false - matrix: - linter: [ - cppcheck, - cpplint, - flake8, - # pep257, TODO: enable when we fixed - # Error: diagnostic_common_diagnostics/diagnostic_common_diagnostics/ntp_monitor.py:113 in public method `ntp_diag`: D417: Missing argument descriptions in the docstring (argument(s) st are missing descriptions in 'ntp_diag' docstring) - # using ros-rolling-ament-pep257 amd64 0.18.0-1noble.20240426.150718 - uncrustify, - xmllint, - ] - include: - - distro: rolling - os: ubuntu-24.04 - runs-on: ${{ matrix.os }} - env: - AMENT_CPPCHECK_ALLOW_SLOW_VERSIONS: 1 - steps: - - uses: actions/checkout@v1 - - uses: ros-tooling/setup-ros@master - with: - required-ros-distributions: ${{ matrix.distro }} - - uses: ros-tooling/action-ros-lint@master - with: - linter: ${{ matrix.linter }} - package-name: | - diagnostic_aggregator - diagnostic_common_diagnostics - diagnostic_updater - self_test diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml deleted file mode 100644 index 224a0cf3..00000000 --- a/.github/workflows/test.yaml +++ /dev/null @@ -1,37 +0,0 @@ -name: Test diagnostics -on: - pull_request: - push: - branches: - - ros2 - schedule: - # Run every week at 20:00 on Sunday - - cron: "0 20 * * 0" - -jobs: - build_and_test: - name: ${{ matrix.package }} on ${{ matrix.distro }} - strategy: - fail-fast: false - matrix: - package: [ - diagnostic_aggregator, - diagnostic_common_diagnostics, - diagnostic_updater, - self_test, - ] - include: - - distro: rolling - os: 24.04 - runs-on: ubuntu-latest - container: ubuntu:${{ matrix.os }} - steps: - - uses: ros-tooling/setup-ros@master - with: - required-ros-distributions: ${{ matrix.distro }} - - uses: ros-tooling/action-ros-ci@master - with: - target-ros2-distro: ${{ matrix.distro }} - package-name: ${{ matrix.package }} - # vcs-repo-file-url: | - # https://raw.githubusercontent.com/ros2/ros2/master/ros2.repos From d7e08dc333e17c3ffa5cbb64ad5bc2c2ce7550aa Mon Sep 17 00:00:00 2001 From: David Revay Date: Fri, 13 Dec 2024 10:42:15 +1100 Subject: [PATCH 4/7] feat: add publish_values parameter --- .../include/diagnostic_aggregator/aggregator.hpp | 5 +++++ diagnostic_aggregator/mainpage.dox | 1 + diagnostic_aggregator/src/aggregator.cpp | 12 ++++++++++++ 3 files changed, 18 insertions(+) diff --git a/diagnostic_aggregator/include/diagnostic_aggregator/aggregator.hpp b/diagnostic_aggregator/include/diagnostic_aggregator/aggregator.hpp index 5f48dd6b..176ae729 100644 --- a/diagnostic_aggregator/include/diagnostic_aggregator/aggregator.hpp +++ b/diagnostic_aggregator/include/diagnostic_aggregator/aggregator.hpp @@ -159,6 +159,11 @@ class Aggregator */ bool critical_; + /*! + *\brief If true, the aggregator will publish "values" for each DiagnosticStatus + */ + bool publish_values_; + /*! *\brief Store the last top level value to publish the critical error only once. */ diff --git a/diagnostic_aggregator/mainpage.dox b/diagnostic_aggregator/mainpage.dox index b720b86e..675823f2 100644 --- a/diagnostic_aggregator/mainpage.dox +++ b/diagnostic_aggregator/mainpage.dox @@ -50,6 +50,7 @@ Reads the following parameters from the parameter server - \b "~base_path" : \b double [optional] Prepended to all analyzed output - \b "~analyzers" : \b {} Configuration for loading analyzers - \b "~critical" : \b bool [optional] React immediately to a degradation in diagnostic state +- \b "~publish_values: \b bool [optional] Publish the "values" for each diagnostic status. Default: "true" \subsection analyzer_loader analyzer_loader diff --git a/diagnostic_aggregator/src/aggregator.cpp b/diagnostic_aggregator/src/aggregator.cpp index 4619ec29..aabd0b71 100644 --- a/diagnostic_aggregator/src/aggregator.cpp +++ b/diagnostic_aggregator/src/aggregator.cpp @@ -67,6 +67,7 @@ Aggregator::Aggregator() clock_(n_->get_clock()), base_path_(""), critical_(false), + publish_values_(true), last_top_level_state_(DiagnosticStatus::STALE) { RCLCPP_DEBUG(logger_, "constructor"); @@ -123,6 +124,8 @@ void Aggregator::initAnalyzers() history_depth_ = param.second.as_int(); } else if (param.first.compare("critical") == 0) { critical_ = param.second.as_bool(); + } else if (param.first.compare("publish_values") == 0) { + publish_values_ = param.second.as_bool(); } } RCLCPP_DEBUG(logger_, "Aggregator publication rate configured to: %f", pub_rate_); @@ -131,6 +134,8 @@ void Aggregator::initAnalyzers() logger_, "Aggregator other_as_errors configured to: %s", (other_as_errors ? "true" : "false")); RCLCPP_DEBUG( logger_, "Aggregator critical publisher configured to: %s", (critical_ ? "true" : "false")); + RCLCPP_DEBUG( + logger_, "Aggregator publish_values configured to: %s", (publish_values_ ? "true" : "false")); { // lock the mutex while analyzer_group_ and other_analyzer_ are being updated std::lock_guard lock(mutex_); @@ -244,6 +249,13 @@ void Aggregator::publishData() } } + // If "publish_values" is false, clear all values + if (!publish_values_) { + for (auto & status : diag_array.status) { + status.values.clear(); + } + } + diag_array.header.stamp = clock_->now(); agg_pub_->publish(diag_array); From d9192aa581b6f11999aed306bfdfc708b166440b Mon Sep 17 00:00:00 2001 From: David Revay Date: Fri, 13 Dec 2024 10:54:04 +1100 Subject: [PATCH 5/7] chore: woops --- .github/workflows/lint.yaml | 45 ++++++++++++++++++++ .github/workflows/release.yaml | 77 ---------------------------------- .github/workflows/test.yaml | 37 ++++++++++++++++ 3 files changed, 82 insertions(+), 77 deletions(-) create mode 100644 .github/workflows/lint.yaml delete mode 100644 .github/workflows/release.yaml create mode 100644 .github/workflows/test.yaml diff --git a/.github/workflows/lint.yaml b/.github/workflows/lint.yaml new file mode 100644 index 00000000..4f926eef --- /dev/null +++ b/.github/workflows/lint.yaml @@ -0,0 +1,45 @@ +name: Lint diagnostics +on: + pull_request: + push: + branches: + - ros2 + schedule: + # Run every week at 20:00 on Sunday + - cron: "0 20 * * 0" + +jobs: + ament_lint: + name: Lint ${{ matrix.linter }} + strategy: + fail-fast: false + matrix: + linter: [ + cppcheck, + cpplint, + flake8, + # pep257, TODO: enable when we fixed + # Error: diagnostic_common_diagnostics/diagnostic_common_diagnostics/ntp_monitor.py:113 in public method `ntp_diag`: D417: Missing argument descriptions in the docstring (argument(s) st are missing descriptions in 'ntp_diag' docstring) + # using ros-rolling-ament-pep257 amd64 0.18.0-1noble.20240426.150718 + uncrustify, + xmllint, + ] + include: + - distro: rolling + os: ubuntu-24.04 + runs-on: ${{ matrix.os }} + env: + AMENT_CPPCHECK_ALLOW_SLOW_VERSIONS: 1 + steps: + - uses: actions/checkout@v1 + - uses: ros-tooling/setup-ros@master + with: + required-ros-distributions: ${{ matrix.distro }} + - uses: ros-tooling/action-ros-lint@master + with: + linter: ${{ matrix.linter }} + package-name: | + diagnostic_aggregator + diagnostic_common_diagnostics + diagnostic_updater + self_test diff --git a/.github/workflows/release.yaml b/.github/workflows/release.yaml deleted file mode 100644 index 773cc805..00000000 --- a/.github/workflows/release.yaml +++ /dev/null @@ -1,77 +0,0 @@ -name: Tag & Release - -on: - workflow_dispatch: - inputs: - package: - type: choice - description: 'If not specified, all packages will be released.' - options: - - "" - - diagnostic_aggregator - - diagnostic_common_diagnostics - - diagnostic_updater - - diagnostics - - self_test - -jobs: - build: - strategy: - fail-fast: true - matrix: - job: - - runner: buildjet-2vcpu-ubuntu-2204 - arch: amd64 - ros_distro: iron - - runner: buildjet-4vcpu-ubuntu-2204-arm - arch: arm64 - ros_distro: iron - - runner: buildjet-2vcpu-ubuntu-2204 - arch: amd64 - ros_distro: jazzy - - runner: buildjet-4vcpu-ubuntu-2204-arm - arch: arm64 - ros_distro: jazzy - - name: Build - ${{ matrix.job.arch }} - ${{ matrix.job.ros_distro }} - runs-on: ${{ matrix.job.runner }} - - steps: - - name: Checkout this repository - uses: actions/checkout@v4 - - - name: Semantic release - Build - uses: Greenroom-Robotics/ros_semantic_release_action@main - with: - token: ${{ secrets.API_TOKEN_GITHUB }} - package: ${{ github.event.inputs.package }} - arch: ${{ matrix.job.arch }} - ros_distro: ${{ matrix.job.ros_distro }} - github_release: false - public: true - changelog: false - skip_build: false - skip_tag: true - release_branches: "ros2-iron" - - release: - name: Create Release - runs-on: buildjet-2vcpu-ubuntu-2204 - needs: - - build - - steps: - - name: Checkout this repository - uses: actions/checkout@v4 - - - name: Release - uses: Greenroom-Robotics/ros_semantic_release_action@main - with: - token: ${{ secrets.API_TOKEN_GITHUB }} - package: ${{ github.event.inputs.package }} - github_release: true - public: true - changelog: false - skip_build: true - skip_tag: false - release_branches: ros2 \ No newline at end of file diff --git a/.github/workflows/test.yaml b/.github/workflows/test.yaml new file mode 100644 index 00000000..224a0cf3 --- /dev/null +++ b/.github/workflows/test.yaml @@ -0,0 +1,37 @@ +name: Test diagnostics +on: + pull_request: + push: + branches: + - ros2 + schedule: + # Run every week at 20:00 on Sunday + - cron: "0 20 * * 0" + +jobs: + build_and_test: + name: ${{ matrix.package }} on ${{ matrix.distro }} + strategy: + fail-fast: false + matrix: + package: [ + diagnostic_aggregator, + diagnostic_common_diagnostics, + diagnostic_updater, + self_test, + ] + include: + - distro: rolling + os: 24.04 + runs-on: ubuntu-latest + container: ubuntu:${{ matrix.os }} + steps: + - uses: ros-tooling/setup-ros@master + with: + required-ros-distributions: ${{ matrix.distro }} + - uses: ros-tooling/action-ros-ci@master + with: + target-ros2-distro: ${{ matrix.distro }} + package-name: ${{ matrix.package }} + # vcs-repo-file-url: | + # https://raw.githubusercontent.com/ros2/ros2/master/ros2.repos From 6480e071cd8dd5918beb7af86a24895ae917d510 Mon Sep 17 00:00:00 2001 From: David Revay Date: Fri, 13 Dec 2024 10:55:36 +1100 Subject: [PATCH 6/7] chore: how did that get in here? --- diagnostic_updater/CMakeLists.txt | 17 +++++++---------- 1 file changed, 7 insertions(+), 10 deletions(-) diff --git a/diagnostic_updater/CMakeLists.txt b/diagnostic_updater/CMakeLists.txt index 91ed6a0e..269d9086 100644 --- a/diagnostic_updater/CMakeLists.txt +++ b/diagnostic_updater/CMakeLists.txt @@ -18,9 +18,7 @@ find_package(rclcpp REQUIRED) find_package(rclpy REQUIRED) find_package(std_msgs REQUIRED) -set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON) - -add_library(${PROJECT_NAME} STATIC +add_library(${PROJECT_NAME} src/diagnostic_updater.cpp ) target_include_directories( @@ -29,7 +27,6 @@ target_include_directories( $ $ ) - ament_target_dependencies( ${PROJECT_NAME} PUBLIC @@ -42,7 +39,7 @@ install( EXPORT ${PROJECT_NAME}Targets LIBRARY DESTINATION lib ARCHIVE DESTINATION lib - RUNTIME DESTINATION lib/${PROJECT_NAME} + RUNTIME DESTINATION bin INCLUDES DESTINATION include ) @@ -109,10 +106,10 @@ install( DESTINATION lib/${PROJECT_NAME} ) -# install( -# TARGETS example -# DESTINATION lib/${PROJECT_NAME} -# ) +install( + TARGETS example + DESTINATION lib/${PROJECT_NAME} +) install( DIRECTORY include/ @@ -130,4 +127,4 @@ ament_export_dependencies(rclcpp) ament_export_dependencies(rclpy) ament_export_dependencies(std_msgs) -ament_package() +ament_package() \ No newline at end of file From 532d1e41a22a3ec34e6ca4b26064392e20e16611 Mon Sep 17 00:00:00 2001 From: David Revay Date: Fri, 13 Dec 2024 10:56:23 +1100 Subject: [PATCH 7/7] chore: formatting --- diagnostic_updater/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/diagnostic_updater/CMakeLists.txt b/diagnostic_updater/CMakeLists.txt index 269d9086..eafa9891 100644 --- a/diagnostic_updater/CMakeLists.txt +++ b/diagnostic_updater/CMakeLists.txt @@ -127,4 +127,4 @@ ament_export_dependencies(rclcpp) ament_export_dependencies(rclpy) ament_export_dependencies(std_msgs) -ament_package() \ No newline at end of file +ament_package()