Skip to content

Commit

Permalink
Revert "Node logger through singleton (warehouse) (#2445)"
Browse files Browse the repository at this point in the history
This reverts commit 6a7b557.

Signed-off-by: Tyler Weaver <maybe@tylerjw.dev>
  • Loading branch information
tylerjw committed Nov 9, 2023
1 parent 86403e9 commit f81d095
Show file tree
Hide file tree
Showing 26 changed files with 109 additions and 526 deletions.
3 changes: 0 additions & 3 deletions moveit_core/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -72,9 +72,6 @@
<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_cmake_gmock</test_depend>
<test_depend>ament_index_cpp</test_depend>
<test_depend>launch_testing_ament_cmake</test_depend>
<test_depend>rclpy</test_depend>
<test_depend>rcl_interfaces</test_depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
Expand Down
8 changes: 1 addition & 7 deletions moveit_core/utils/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,13 +2,12 @@ add_library(moveit_utils SHARED
src/lexical_casts.cpp
src/message_checks.cpp
src/rclcpp_utils.cpp
src/logger.cpp
)
target_include_directories(moveit_utils PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include/moveit_core>
)
ament_target_dependencies(moveit_utils Boost moveit_msgs rclcpp)
ament_target_dependencies(moveit_utils Boost moveit_msgs)
set_target_properties(moveit_utils PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")

install(DIRECTORY include/ DESTINATION include/moveit_core)
Expand All @@ -29,10 +28,5 @@ ament_target_dependencies(moveit_test_utils
srdfdom
urdfdom
urdfdom_headers
rclcpp
)
set_target_properties(moveit_test_utils PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")

if(BUILD_TESTING)
add_subdirectory(test)
endif()
57 changes: 0 additions & 57 deletions moveit_core/utils/include/moveit/utils/logger.hpp

This file was deleted.

77 changes: 0 additions & 77 deletions moveit_core/utils/src/logger.cpp

This file was deleted.

25 changes: 0 additions & 25 deletions moveit_core/utils/test/CMakeLists.txt

This file was deleted.

54 changes: 0 additions & 54 deletions moveit_core/utils/test/logger_dut.cpp

This file was deleted.

56 changes: 0 additions & 56 deletions moveit_core/utils/test/logger_from_child_dut.cpp

This file was deleted.

Loading

0 comments on commit f81d095

Please sign in to comment.