From eef44bacaf1cbc259bee298c7573f171cc9111f6 Mon Sep 17 00:00:00 2001
From: Tyler Weaver <maybe@tylerjw.dev>
Date: Thu, 9 Nov 2023 09:29:30 -0700
Subject: [PATCH] Revert "Node logger through singleton (warehouse) (#2445)"

This reverts commit 6a7b557bb6e9b49ecdc80db348f000ddc641656d.

Signed-off-by: Tyler Weaver <maybe@tylerjw.dev>
---
 moveit_core/package.xml                       |   3 -
 moveit_core/utils/CMakeLists.txt              |   8 +-
 .../utils/include/moveit/utils/logger.hpp     |  57 ---------
 moveit_core/utils/src/logger.cpp              |  77 ------------
 moveit_core/utils/test/CMakeLists.txt         |  25 ----
 moveit_core/utils/test/logger_dut.cpp         |  54 ---------
 .../utils/test/logger_from_child_dut.cpp      |  56 ---------
 moveit_core/utils/test/rosout_publish_test.py | 111 ------------------
 .../moveit/warehouse/constraints_storage.h    |   3 -
 .../moveit/warehouse/planning_scene_storage.h |   2 -
 .../warehouse/planning_scene_world_storage.h  |   2 -
 .../include/moveit/warehouse/state_storage.h  |   2 -
 .../trajectory_constraints_storage.h          |   2 -
 .../moveit/warehouse/warehouse_connector.h    |   2 -
 moveit_ros/warehouse/src/broadcast.cpp        |  16 ++-
 .../warehouse/src/constraints_storage.cpp     |  11 +-
 moveit_ros/warehouse/src/import_from_text.cpp |  16 ++-
 .../warehouse/src/initialize_demo_db.cpp      |  14 +--
 .../warehouse/src/planning_scene_storage.cpp  |  27 +++--
 .../src/planning_scene_world_storage.cpp      |  10 +-
 moveit_ros/warehouse/src/save_as_text.cpp     |  16 ++-
 .../warehouse/src/save_to_warehouse.cpp       |  55 ++++-----
 moveit_ros/warehouse/src/state_storage.cpp    |  11 +-
 .../src/trajectory_constraints_storage.cpp    |  10 +-
 .../warehouse/src/warehouse_connector.cpp     |  14 +--
 .../warehouse/src/warehouse_services.cpp      |  31 +++--
 26 files changed, 109 insertions(+), 526 deletions(-)
 delete mode 100644 moveit_core/utils/include/moveit/utils/logger.hpp
 delete mode 100644 moveit_core/utils/src/logger.cpp
 delete mode 100644 moveit_core/utils/test/CMakeLists.txt
 delete mode 100644 moveit_core/utils/test/logger_dut.cpp
 delete mode 100644 moveit_core/utils/test/logger_from_child_dut.cpp
 delete mode 100644 moveit_core/utils/test/rosout_publish_test.py

diff --git a/moveit_core/package.xml b/moveit_core/package.xml
index 85c2c2633aa..1cbe79cfb7d 100644
--- a/moveit_core/package.xml
+++ b/moveit_core/package.xml
@@ -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>
diff --git a/moveit_core/utils/CMakeLists.txt b/moveit_core/utils/CMakeLists.txt
index a206662a197..7be8dd822d2 100644
--- a/moveit_core/utils/CMakeLists.txt
+++ b/moveit_core/utils/CMakeLists.txt
@@ -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)
@@ -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()
diff --git a/moveit_core/utils/include/moveit/utils/logger.hpp b/moveit_core/utils/include/moveit/utils/logger.hpp
deleted file mode 100644
index fcd3e72b6da..00000000000
--- a/moveit_core/utils/include/moveit/utils/logger.hpp
+++ /dev/null
@@ -1,57 +0,0 @@
-/*********************************************************************
- * Software License Agreement (BSD License)
- *
- *  Copyright (c) 2023, PickNik Robotics Inc.
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of PickNik Robotics Inc. nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *********************************************************************/
-
-/* Author: Tyler Weaver */
-
-#pragma once
-
-#include <rclcpp/logger.hpp>
-#include <string>
-
-namespace moveit
-{
-
-// Function for getting a reference to a logger object kept in a global variable.
-// Use getLoggerMut to set the logger to a node logger.
-const rclcpp::Logger& getLogger();
-
-// Function for getting a child logger. In Humble this also creates a node.
-// Do not use this in place as it will create a new logger each time,
-// instead store it in the state of your class or method.
-rclcpp::Logger makeChildLogger(const std::string& name);
-
-// Mutable access to global logger for setting to node logger.
-rclcpp::Logger& getLoggerMut();
-
-}  // namespace moveit
diff --git a/moveit_core/utils/src/logger.cpp b/moveit_core/utils/src/logger.cpp
deleted file mode 100644
index f444235d68e..00000000000
--- a/moveit_core/utils/src/logger.cpp
+++ /dev/null
@@ -1,77 +0,0 @@
-/*********************************************************************
- * Software License Agreement (BSD License)
- *
- *  Copyright (c) 2023, PickNik Robotics Inc.
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of Willow Garage nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *********************************************************************/
-
-/* Author: Tyler Weaver */
-
-#include <rclcpp/rclcpp.hpp>
-#include <moveit/utils/logger.hpp>
-#include <rclcpp/version.h>
-#include <unordered_map>
-#include <string>
-
-namespace moveit
-{
-
-const rclcpp::Logger& getLogger()
-{
-  return getLoggerMut();
-}
-
-rclcpp::Logger makeChildLogger(const std::string& name)
-{
-  // On versions of ROS older than Iron we need to create a node for each child logger
-  // Remove once Humble is EOL
-  // References:
-  // Use parent logger (rcl PR) - https://github.com/ros2/rcl/pull/921
-  // Request for backport (rclpy issue) - https://github.com/ros2/rclpy/issues/1131
-  // MoveIt PR that added this - https://github.com/ros-planning/moveit2/pull/2445
-#if !RCLCPP_VERSION_GTE(21, 0, 3)
-  static std::unordered_map<std::string, std::shared_ptr<rclcpp::Node>> child_nodes;
-  if (child_nodes.find(name) == child_nodes.end())
-  {
-    std::string ns = getLogger().get_name();
-    child_nodes[name] = std::make_shared<rclcpp::Node>(name, ns);
-  }
-#endif
-
-  return getLoggerMut().get_child(name);
-}
-
-rclcpp::Logger& getLoggerMut()
-{
-  static rclcpp::Logger logger = rclcpp::get_logger("moveit");
-  return logger;
-}
-
-}  // namespace moveit
diff --git a/moveit_core/utils/test/CMakeLists.txt b/moveit_core/utils/test/CMakeLists.txt
deleted file mode 100644
index bb52a7e292b..00000000000
--- a/moveit_core/utils/test/CMakeLists.txt
+++ /dev/null
@@ -1,25 +0,0 @@
-# Build devices under test
-add_executable(logger_dut logger_dut.cpp)
-target_link_libraries(logger_dut rclcpp::rclcpp moveit_utils)
-
-add_executable(logger_from_child_dut logger_from_child_dut.cpp)
-target_link_libraries(logger_from_child_dut rclcpp::rclcpp moveit_utils)
-
-# Install is needed to run these as launch tests
-install(
-  TARGETS
-    logger_dut
-    logger_from_child_dut
-  DESTINATION lib/${PROJECT_NAME}
-)
-
-# Add the launch tests
-find_package(launch_testing_ament_cmake)
-add_launch_test(rosout_publish_test.py
-    TARGET test-node_logging
-    ARGS "dut:=logger_dut"
-)
-add_launch_test(rosout_publish_test.py
-    TARGET test-node_logging_from_child
-    ARGS "dut:=logger_from_child_dut"
-)
diff --git a/moveit_core/utils/test/logger_dut.cpp b/moveit_core/utils/test/logger_dut.cpp
deleted file mode 100644
index 01201d62b3b..00000000000
--- a/moveit_core/utils/test/logger_dut.cpp
+++ /dev/null
@@ -1,54 +0,0 @@
-/*********************************************************************
- * Software License Agreement (BSD License)
- *
- *  Copyright (c) 2023, PickNik Robotics Inc.
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of Willow Garage nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *********************************************************************/
-
-/* Author: Tyler Weaver */
-
-#include <chrono>
-#include <rclcpp/rclcpp.hpp>
-#include <moveit/utils/logger.hpp>
-
-int main(int argc, char** argv)
-{
-  rclcpp::init(argc, argv);
-  rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("dut_node");
-
-  // Set the moveit logger to be from node
-  moveit::getLoggerMut() = node->get_logger();
-
-  // A node logger, should be in the file output and rosout
-  auto wall_timer = node->create_wall_timer(std::chrono::milliseconds(100),
-                                            [&] { RCLCPP_INFO(moveit::getLogger(), "hello from node!"); });
-
-  rclcpp::spin(node);
-}
diff --git a/moveit_core/utils/test/logger_from_child_dut.cpp b/moveit_core/utils/test/logger_from_child_dut.cpp
deleted file mode 100644
index b051a98e30e..00000000000
--- a/moveit_core/utils/test/logger_from_child_dut.cpp
+++ /dev/null
@@ -1,56 +0,0 @@
-/*********************************************************************
- * Software License Agreement (BSD License)
- *
- *  Copyright (c) 2023, PickNik Robotics Inc.
- *  All rights reserved.
- *
- *  Redistribution and use in source and binary forms, with or without
- *  modification, are permitted provided that the following conditions
- *  are met:
- *
- *   * Redistributions of source code must retain the above copyright
- *     notice, this list of conditions and the following disclaimer.
- *   * Redistributions in binary form must reproduce the above
- *     copyright notice, this list of conditions and the following
- *     disclaimer in the documentation and/or other materials provided
- *     with the distribution.
- *   * Neither the name of Willow Garage nor the names of its
- *     contributors may be used to endorse or promote products derived
- *     from this software without specific prior written permission.
- *
- *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- *  POSSIBILITY OF SUCH DAMAGE.
- *********************************************************************/
-
-/* Author: Tyler Weaver */
-
-#include <chrono>
-#include <rclcpp/rclcpp.hpp>
-#include <moveit/utils/logger.hpp>
-
-int main(int argc, char** argv)
-{
-  rclcpp::init(argc, argv);
-  rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("dut_node");
-
-  // Set the moveit logger to be from node
-  moveit::getLoggerMut() = node->get_logger();
-
-  // Make a child logger
-  const auto child_logger = moveit::makeChildLogger("child");
-
-  // publish via a timer
-  auto wall_timer = node->create_wall_timer(std::chrono::milliseconds(100),
-                                            [&] { RCLCPP_INFO(child_logger, "hello from child node!"); });
-  rclcpp::spin(node);
-}
diff --git a/moveit_core/utils/test/rosout_publish_test.py b/moveit_core/utils/test/rosout_publish_test.py
deleted file mode 100644
index 4c1ac9d2e38..00000000000
--- a/moveit_core/utils/test/rosout_publish_test.py
+++ /dev/null
@@ -1,111 +0,0 @@
-# Software License Agreement (BSD License)
-#
-#  Copyright (c) 2023, PickNik Robotics Inc.
-#  All rights reserved.
-#
-#  Redistribution and use in source and binary forms, with or without
-#  modification, are permitted provided that the following conditions
-#  are met:
-#
-#  # Redistributions of source code must retain the above copyright
-#     notice, this list of conditions and the following disclaimer.
-#  # Redistributions in binary form must reproduce the above
-#     copyright notice, this list of conditions and the following
-#     disclaimer in the documentation and/or other materials provided
-#     with the distribution.
-#  # Neither the name of Willow Garage nor the names of its
-#     contributors may be used to endorse or promote products derived
-#     from this software without specific prior written permission.
-#
-#  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-#  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-#  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-#  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-#  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-#  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-#  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
-#  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
-#  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-#  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-#  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-#  POSSIBILITY OF SUCH DAMAGE.
-
-# Author: Tyler Weaver
-
-import unittest
-from threading import Event
-from threading import Thread
-
-import launch
-import launch_ros
-import launch_testing
-import rclpy
-from rclpy.node import Node
-from rcl_interfaces.msg import Log
-
-import pytest
-
-
-@pytest.mark.launch_test
-def generate_test_description():
-    # dut: device under test
-    dut_process = launch_ros.actions.Node(
-        package="moveit_core",
-        executable=launch.substitutions.LaunchConfiguration("dut"),
-        output="screen",
-    )
-
-    return launch.LaunchDescription(
-        [
-            launch.actions.DeclareLaunchArgument(
-                "dut",
-                description="Executable to launch",
-            ),
-            dut_process,
-            # Start tests right away - no need to wait for anything
-            launch_testing.actions.ReadyToTest(),
-        ]
-    ), {"dut_process": dut_process}
-
-
-class MakeRosoutObserverNode(Node):
-    def __init__(self, name="rosout_observer_node"):
-        super().__init__(name)
-        self.msg_event_object = Event()
-
-    def start_subscriber(self):
-        # Create a subscriber
-        self.subscription = self.create_subscription(
-            Log, "rosout", self.subscriber_callback, 10
-        )
-
-        # Add a spin thread
-        self.ros_spin_thread = Thread(
-            target=lambda node: rclpy.spin(node), args=(self,)
-        )
-        self.ros_spin_thread.start()
-
-    def subscriber_callback(self, data):
-        self.msg_event_object.set()
-
-
-# These tests will run concurrently with the dut process.  After all these tests are done,
-# the launch system will shut down the processes that it started up
-class TestFixture(unittest.TestCase):
-    def test_rosout_msgs_published(self, proc_output):
-        rclpy.init()
-        try:
-            node = MakeRosoutObserverNode()
-            node.start_subscriber()
-            msgs_received_flag = node.msg_event_object.wait(timeout=5.0)
-            assert msgs_received_flag, "Did not receive msgs !"
-        finally:
-            rclpy.shutdown()
-
-
-@launch_testing.post_shutdown_test()
-class TestProcessOutput(unittest.TestCase):
-    def test_exit_code(self, proc_info):
-        # Check that all processes in the launch (in this case, there's just one) exit
-        # with code 0
-        launch_testing.asserts.assertExitCodes(proc_info)
diff --git a/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h
index 230b1c85556..6fa5b7bc8ec 100644
--- a/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h
+++ b/moveit_ros/warehouse/include/moveit/warehouse/constraints_storage.h
@@ -42,8 +42,6 @@
 
 #include <moveit_warehouse_export.h>
 
-#include <rclcpp/logger.hpp>
-
 namespace moveit_warehouse
 {
 typedef warehouse_ros::MessageWithMetadata<moveit_msgs::msg::Constraints>::ConstPtr ConstraintsWithMetadata;
@@ -85,6 +83,5 @@ class MOVEIT_WAREHOUSE_EXPORT ConstraintsStorage : public MoveItMessageStorage
   void createCollections();
 
   ConstraintsCollection constraints_collection_;
-  rclcpp::Logger logger_;
 };
 }  // namespace moveit_warehouse
diff --git a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h
index 8139c00ea88..a81057df4cb 100644
--- a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h
+++ b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_storage.h
@@ -41,7 +41,6 @@
 #include <moveit_msgs/msg/planning_scene.hpp>
 #include <moveit_msgs/msg/motion_plan_request.hpp>
 #include <moveit_msgs/msg/robot_trajectory.hpp>
-#include <rclcpp/logger.hpp>
 
 #include <moveit_warehouse_export.h>
 
@@ -120,6 +119,5 @@ class MOVEIT_WAREHOUSE_EXPORT PlanningSceneStorage : public MoveItMessageStorage
   PlanningSceneCollection planning_scene_collection_;
   MotionPlanRequestCollection motion_plan_request_collection_;
   RobotTrajectoryCollection robot_trajectory_collection_;
-  rclcpp::Logger logger_;
 };
 }  // namespace moveit_warehouse
diff --git a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h
index 4c174596566..f7aff02de42 100644
--- a/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h
+++ b/moveit_ros/warehouse/include/moveit/warehouse/planning_scene_world_storage.h
@@ -38,7 +38,6 @@
 
 #include <moveit/warehouse/moveit_message_storage.h>
 #include <moveit_msgs/msg/planning_scene_world.hpp>
-#include <rclcpp/logger.hpp>
 
 namespace moveit_warehouse
 {
@@ -71,6 +70,5 @@ class PlanningSceneWorldStorage : public MoveItMessageStorage
   void createCollections();
 
   PlanningSceneWorldCollection planning_scene_world_collection_;
-  rclcpp::Logger logger_;
 };
 }  // namespace moveit_warehouse
diff --git a/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h
index 58a8c91a703..dddc4117559 100644
--- a/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h
+++ b/moveit_ros/warehouse/include/moveit/warehouse/state_storage.h
@@ -39,7 +39,6 @@
 #include <moveit/warehouse/moveit_message_storage.h>
 #include <moveit/macros/class_forward.h>
 #include <moveit_msgs/msg/robot_state.hpp>
-#include <rclcpp/logger.hpp>
 
 #include <moveit_warehouse_export.h>
 
@@ -79,6 +78,5 @@ class MOVEIT_WAREHOUSE_EXPORT RobotStateStorage : public MoveItMessageStorage
   void createCollections();
 
   RobotStateCollection state_collection_;
-  rclcpp::Logger logger_;
 };
 }  // namespace moveit_warehouse
diff --git a/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h b/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h
index e729fac14ce..8a0d9ba0845 100644
--- a/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h
+++ b/moveit_ros/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h
@@ -39,7 +39,6 @@
 #include <moveit/warehouse/moveit_message_storage.h>
 #include <moveit/macros/class_forward.h>
 #include <moveit_msgs/msg/trajectory_constraints.hpp>
-#include <rclcpp/logger.hpp>
 
 namespace moveit_warehouse
 {
@@ -85,6 +84,5 @@ class TrajectoryConstraintsStorage : public MoveItMessageStorage
   void createCollections();
 
   TrajectoryConstraintsCollection constraints_collection_;
-  rclcpp::Logger logger_;
 };
 }  // namespace moveit_warehouse
diff --git a/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h b/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h
index 86b8e189977..04e279a3ca6 100644
--- a/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h
+++ b/moveit_ros/warehouse/include/moveit/warehouse/warehouse_connector.h
@@ -37,7 +37,6 @@
 #pragma once
 
 #include <string>
-#include <rclcpp/logger.hpp>
 
 namespace moveit_warehouse
 {
@@ -53,6 +52,5 @@ class WarehouseConnector
 private:
   std::string dbexec_;
   int child_pid_;
-  rclcpp::Logger logger_;
 };
 }  // namespace moveit_warehouse
diff --git a/moveit_ros/warehouse/src/broadcast.cpp b/moveit_ros/warehouse/src/broadcast.cpp
index 5124fa000e0..208713d589f 100644
--- a/moveit_ros/warehouse/src/broadcast.cpp
+++ b/moveit_ros/warehouse/src/broadcast.cpp
@@ -37,7 +37,6 @@
 #include <moveit/warehouse/planning_scene_storage.h>
 #include <moveit/warehouse/constraints_storage.h>
 #include <moveit/warehouse/state_storage.h>
-#include <moveit/utils/logger.hpp>
 #include <boost/program_options/cmdline.hpp>
 #include <boost/program_options/options_description.hpp>
 #include <boost/program_options/parsers.hpp>
@@ -66,7 +65,6 @@ static const std::string CONSTRAINTS_TOPIC = "constraints";
 static const std::string STATES_TOPIC = "robot_states";
 
 using namespace std::chrono_literals;
-using moveit::getLogger;
 
 int main(int argc, char** argv)
 {
@@ -75,7 +73,7 @@ int main(int argc, char** argv)
   node_options.allow_undeclared_parameters(true);
   node_options.automatically_declare_parameters_from_overrides(true);
   rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("publish_warehouse_data", node_options);
-  moveit::getLoggerMut() = node->get_logger();
+  const auto logger = node->get_logger();
 
   // time to wait in between publishing messages
   double delay = 0.001;
@@ -142,7 +140,7 @@ int main(int argc, char** argv)
       moveit_warehouse::PlanningSceneWithMetadata pswm;
       if (pss.getPlanningScene(pswm, scene_name))
       {
-        RCLCPP_INFO(getLogger(), "Publishing scene '%s'",
+        RCLCPP_INFO(logger, "Publishing scene '%s'",
                     pswm->lookupString(moveit_warehouse::PlanningSceneStorage::PLANNING_SCENE_ID_NAME).c_str());
         pub_scene->publish(static_cast<const moveit_msgs::msg::PlanningScene&>(*pswm));
         executor.spin_once(0ns);
@@ -155,14 +153,14 @@ int main(int argc, char** argv)
           std::vector<moveit_warehouse::MotionPlanRequestWithMetadata> planning_queries;
           std::vector<std::string> query_names;
           pss.getPlanningQueries(planning_queries, query_names, pswm->name);
-          RCLCPP_INFO(getLogger(), "There are %d planning queries associated to the scene",
+          RCLCPP_INFO(logger, "There are %d planning queries associated to the scene",
                       static_cast<int>(planning_queries.size()));
           rclcpp::sleep_for(500ms);
           for (std::size_t i = 0; i < planning_queries.size(); ++i)
           {
             if (req)
             {
-              RCLCPP_INFO(getLogger(), "Publishing query '%s'", query_names[i].c_str());
+              RCLCPP_INFO(logger, "Publishing query '%s'", query_names[i].c_str());
               pub_req->publish(static_cast<const moveit_msgs::msg::MotionPlanRequest&>(*planning_queries[i]));
               executor.spin_once(0ns);
             }
@@ -196,7 +194,7 @@ int main(int argc, char** argv)
       moveit_warehouse::ConstraintsWithMetadata cwm;
       if (cs.getConstraints(cwm, cname))
       {
-        RCLCPP_INFO(getLogger(), "Publishing constraints '%s'",
+        RCLCPP_INFO(logger, "Publishing constraints '%s'",
                     cwm->lookupString(moveit_warehouse::ConstraintsStorage::CONSTRAINTS_ID_NAME).c_str());
         pub_constr->publish(static_cast<const moveit_msgs::msg::Constraints&>(*cwm));
         executor.spin_once(0ns);
@@ -218,7 +216,7 @@ int main(int argc, char** argv)
       moveit_warehouse::RobotStateWithMetadata rswm;
       if (rs.getRobotState(rswm, rname))
       {
-        RCLCPP_INFO(getLogger(), "Publishing state '%s'",
+        RCLCPP_INFO(logger, "Publishing state '%s'",
                     rswm->lookupString(moveit_warehouse::RobotStateStorage::STATE_NAME).c_str());
         pub_state->publish(static_cast<const moveit_msgs::msg::RobotState&>(*rswm));
         executor.spin_once(0ns);
@@ -228,7 +226,7 @@ int main(int argc, char** argv)
   }
 
   rclcpp::sleep_for(1s);
-  RCLCPP_INFO(getLogger(), "Done.");
+  RCLCPP_INFO(logger, "Done.");
 
   return 0;
 }
diff --git a/moveit_ros/warehouse/src/constraints_storage.cpp b/moveit_ros/warehouse/src/constraints_storage.cpp
index ca56e58d6e4..f7258594142 100644
--- a/moveit_ros/warehouse/src/constraints_storage.cpp
+++ b/moveit_ros/warehouse/src/constraints_storage.cpp
@@ -35,7 +35,6 @@
 /* Author: Ioan Sucan */
 
 #include <moveit/warehouse/constraints_storage.h>
-#include <moveit/utils/logger.hpp>
 
 #include <utility>
 
@@ -45,11 +44,13 @@ const std::string moveit_warehouse::ConstraintsStorage::CONSTRAINTS_ID_NAME = "c
 const std::string moveit_warehouse::ConstraintsStorage::CONSTRAINTS_GROUP_NAME = "group_id";
 const std::string moveit_warehouse::ConstraintsStorage::ROBOT_NAME = "robot_id";
 
+static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.warehouse.constraints_storage");
+
 using warehouse_ros::Metadata;
 using warehouse_ros::Query;
 
 moveit_warehouse::ConstraintsStorage::ConstraintsStorage(warehouse_ros::DatabaseConnection::Ptr conn)
-  : MoveItMessageStorage(std::move(conn)), logger_(moveit::makeChildLogger("moveit_warehouse_constraints_storage"))
+  : MoveItMessageStorage(std::move(conn))
 {
   createCollections();
 }
@@ -80,7 +81,7 @@ void moveit_warehouse::ConstraintsStorage::addConstraints(const moveit_msgs::msg
   metadata->append(ROBOT_NAME, robot);
   metadata->append(CONSTRAINTS_GROUP_NAME, group);
   constraints_collection_->insert(msg, metadata);
-  RCLCPP_DEBUG(logger_, "%s constraints '%s'", replace ? "Replaced" : "Added", msg.name.c_str());
+  RCLCPP_DEBUG(LOGGER, "%s constraints '%s'", replace ? "Replaced" : "Added", msg.name.c_str());
 }
 
 bool moveit_warehouse::ConstraintsStorage::hasConstraints(const std::string& name, const std::string& robot,
@@ -157,7 +158,7 @@ void moveit_warehouse::ConstraintsStorage::renameConstraints(const std::string&
   Metadata::Ptr m = constraints_collection_->createMetadata();
   m->append(CONSTRAINTS_ID_NAME, new_name);
   constraints_collection_->modifyMetadata(q, m);
-  RCLCPP_DEBUG(logger_, "Renamed constraints from '%s' to '%s'", old_name.c_str(), new_name.c_str());
+  RCLCPP_DEBUG(LOGGER, "Renamed constraints from '%s' to '%s'", old_name.c_str(), new_name.c_str());
 }
 
 void moveit_warehouse::ConstraintsStorage::removeConstraints(const std::string& name, const std::string& robot,
@@ -170,5 +171,5 @@ void moveit_warehouse::ConstraintsStorage::removeConstraints(const std::string&
   if (!group.empty())
     q->append(CONSTRAINTS_GROUP_NAME, group);
   unsigned int rem = constraints_collection_->removeMessages(q);
-  RCLCPP_DEBUG(logger_, "Removed %u Constraints messages (named '%s')", rem, name.c_str());
+  RCLCPP_DEBUG(LOGGER, "Removed %u Constraints messages (named '%s')", rem, name.c_str());
 }
diff --git a/moveit_ros/warehouse/src/import_from_text.cpp b/moveit_ros/warehouse/src/import_from_text.cpp
index c345d033aa9..6b91501433b 100644
--- a/moveit_ros/warehouse/src/import_from_text.cpp
+++ b/moveit_ros/warehouse/src/import_from_text.cpp
@@ -45,11 +45,10 @@
 #include <boost/program_options/options_description.hpp>
 #include <boost/program_options/parsers.hpp>
 #include <boost/program_options/variables_map.hpp>
-#include <moveit/utils/logger.hpp>
 
 static const std::string ROBOT_DESCRIPTION = "robot_description";
 
-using moveit::getLogger;
+static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.warehouse.planning_scene_storage");
 
 void parseStart(std::istream& in, planning_scene_monitor::PlanningSceneMonitor* psm,
                 moveit_warehouse::RobotStateStorage* rs)
@@ -91,7 +90,7 @@ void parseStart(std::istream& in, planning_scene_monitor::PlanningSceneMonitor*
         st.setVariablePositions(v);
         moveit_msgs::msg::RobotState msg;
         moveit::core::robotStateToRobotStateMsg(st, msg);
-        RCLCPP_INFO(getLogger(), "Parsed start state '%s'", name.c_str());
+        RCLCPP_INFO(LOGGER, "Parsed start state '%s'", name.c_str());
         rs->addRobotState(msg, name);
       }
     }
@@ -136,7 +135,7 @@ void parseLinkConstraint(std::istream& in, planning_scene_monitor::PlanningScene
                                Eigen::AngleAxisd(y, Eigen::Vector3d::UnitZ()));
     }
     else
-      RCLCPP_ERROR(getLogger(), "Unknown link constraint element: '%s'", type.c_str());
+      RCLCPP_ERROR(LOGGER, "Unknown link constraint element: '%s'", type.c_str());
     in >> type;
   }
 
@@ -151,7 +150,7 @@ void parseLinkConstraint(std::istream& in, planning_scene_monitor::PlanningScene
     pose.header.frame_id = psm->getRobotModel()->getModelFrame();
     moveit_msgs::msg::Constraints constr = kinematic_constraints::constructGoalConstraints(link_name, pose);
     constr.name = name;
-    RCLCPP_INFO(getLogger(), "Parsed link constraint '%s'", name.c_str());
+    RCLCPP_INFO(LOGGER, "Parsed link constraint '%s'", name.c_str());
     cs->addConstraints(constr);
   }
 }
@@ -181,7 +180,7 @@ void parseGoal(std::istream& in, planning_scene_monitor::PlanningSceneMonitor* p
         }
         else
         {
-          RCLCPP_INFO(getLogger(), "Unknown goal type: '%s'", type.c_str());
+          RCLCPP_INFO(LOGGER, "Unknown goal type: '%s'", type.c_str());
         }
       }
     }
@@ -210,7 +209,7 @@ void parseQueries(std::istream& in, planning_scene_monitor::PlanningSceneMonitor
       }
       else
       {
-        RCLCPP_ERROR(getLogger(), "Unknown query type: '%s'", type.c_str());
+        RCLCPP_ERROR(LOGGER, "Unknown query type: '%s'", type.c_str());
       }
     }
   }
@@ -223,7 +222,6 @@ int main(int argc, char** argv)
   node_options.allow_undeclared_parameters(true);
   node_options.automatically_declare_parameters_from_overrides(true);
   rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("import_from_text_to_warehouse", node_options);
-  moveit::getLoggerMut() = node->get_logger();
 
   // clang-format off
   boost::program_options::options_description desc;
@@ -253,7 +251,7 @@ int main(int argc, char** argv)
   planning_scene_monitor::PlanningSceneMonitor psm(node, ROBOT_DESCRIPTION);
   if (!psm.getPlanningScene())
   {
-    RCLCPP_ERROR(getLogger(), "Unable to initialize PlanningSceneMonitor");
+    RCLCPP_ERROR(LOGGER, "Unable to initialize PlanningSceneMonitor");
     return 1;
   }
 
diff --git a/moveit_ros/warehouse/src/initialize_demo_db.cpp b/moveit_ros/warehouse/src/initialize_demo_db.cpp
index 4e93225909f..3123e484281 100644
--- a/moveit_ros/warehouse/src/initialize_demo_db.cpp
+++ b/moveit_ros/warehouse/src/initialize_demo_db.cpp
@@ -52,11 +52,10 @@
 #include <rclcpp/node.hpp>
 #include <rclcpp/node_options.hpp>
 #include <rclcpp/utilities.hpp>
-#include <moveit/utils/logger.hpp>
 
 static const std::string ROBOT_DESCRIPTION = "robot_description";
 
-using moveit::getLogger;
+static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.warehouse.initialize_demo_db");
 
 int main(int argc, char** argv)
 {
@@ -65,7 +64,6 @@ int main(int argc, char** argv)
   node_options.allow_undeclared_parameters(true);
   node_options.automatically_declare_parameters_from_overrides(true);
   rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("initialize_demo_db", node_options);
-  moveit::getLoggerMut() = node->get_logger();
 
   boost::program_options::options_description desc;
   desc.add_options()("help", "Show help message")("host", boost::program_options::value<std::string>(),
@@ -92,7 +90,7 @@ int main(int argc, char** argv)
   planning_scene_monitor::PlanningSceneMonitor psm(node, ROBOT_DESCRIPTION);
   if (!psm.getPlanningScene())
   {
-    RCLCPP_ERROR(getLogger(), "Unable to initialize PlanningSceneMonitor");
+    RCLCPP_ERROR(LOGGER, "Unable to initialize PlanningSceneMonitor");
     return 1;
   }
 
@@ -108,12 +106,12 @@ int main(int argc, char** argv)
   psm.getPlanningScene()->getPlanningSceneMsg(psmsg);
   psmsg.name = "default";
   pss.addPlanningScene(psmsg);
-  RCLCPP_INFO(getLogger(), "Added default scene: '%s'", psmsg.name.c_str());
+  RCLCPP_INFO(LOGGER, "Added default scene: '%s'", psmsg.name.c_str());
 
   moveit_msgs::msg::RobotState rsmsg;
   moveit::core::robotStateToRobotStateMsg(psm.getPlanningScene()->getCurrentState(), rsmsg);
   rs.addRobotState(rsmsg, "default");
-  RCLCPP_INFO(getLogger(), "Added default state");
+  RCLCPP_INFO(LOGGER, "Added default state");
 
   const std::vector<std::string>& gnames = psm.getRobotModel()->getJointModelGroupNames();
   for (const std::string& gname : gnames)
@@ -140,9 +138,9 @@ int main(int argc, char** argv)
     cmsg.orientation_constraints.resize(1, ocm);
     cmsg.name = ocm.link_name + ":upright";
     cs.addConstraints(cmsg, psm.getRobotModel()->getName(), jmg->getName());
-    RCLCPP_INFO(getLogger(), "Added default constraint: '%s'", cmsg.name.c_str());
+    RCLCPP_INFO(LOGGER, "Added default constraint: '%s'", cmsg.name.c_str());
   }
-  RCLCPP_INFO(getLogger(), "Default MoveIt Warehouse was reset.");
+  RCLCPP_INFO(LOGGER, "Default MoveIt Warehouse was reset.");
 
   rclcpp::spin(node);
 
diff --git a/moveit_ros/warehouse/src/planning_scene_storage.cpp b/moveit_ros/warehouse/src/planning_scene_storage.cpp
index dd5bbd19969..ae7b9710ead 100644
--- a/moveit_ros/warehouse/src/planning_scene_storage.cpp
+++ b/moveit_ros/warehouse/src/planning_scene_storage.cpp
@@ -38,7 +38,6 @@
 #include <utility>
 #include <rclcpp/serialization.hpp>
 #include <regex>
-#include <moveit/utils/logger.hpp>
 
 const std::string moveit_warehouse::PlanningSceneStorage::DATABASE_NAME = "moveit_planning_scenes";
 
@@ -48,8 +47,10 @@ const std::string moveit_warehouse::PlanningSceneStorage::MOTION_PLAN_REQUEST_ID
 using warehouse_ros::Metadata;
 using warehouse_ros::Query;
 
+static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.warehouse.planning_scene_storage");
+
 moveit_warehouse::PlanningSceneStorage::PlanningSceneStorage(warehouse_ros::DatabaseConnection::Ptr conn)
-  : MoveItMessageStorage(std::move(conn)), logger_(moveit::makeChildLogger("moveit_warehouse_planning_scene_storage"))
+  : MoveItMessageStorage(std::move(conn))
 {
   createCollections();
 }
@@ -84,7 +85,7 @@ void moveit_warehouse::PlanningSceneStorage::addPlanningScene(const moveit_msgs:
   Metadata::Ptr metadata = planning_scene_collection_->createMetadata();
   metadata->append(PLANNING_SCENE_ID_NAME, scene.name);
   planning_scene_collection_->insert(scene, metadata);
-  RCLCPP_DEBUG(logger_, "%s scene '%s'", replace ? "Replaced" : "Added", scene.name.c_str());
+  RCLCPP_DEBUG(LOGGER, "%s scene '%s'", replace ? "Replaced" : "Added", scene.name.c_str());
 }
 
 bool moveit_warehouse::PlanningSceneStorage::hasPlanningScene(const std::string& name) const
@@ -172,7 +173,7 @@ moveit_warehouse::PlanningSceneStorage::addNewPlanningRequest(const moveit_msgs:
   metadata->append(PLANNING_SCENE_ID_NAME, scene_name);
   metadata->append(MOTION_PLAN_REQUEST_ID_NAME, id);
   motion_plan_request_collection_->insert(planning_query, metadata);
-  RCLCPP_DEBUG(logger_, "Saved planning query '%s' for scene '%s'", id.c_str(), scene_name.c_str());
+  RCLCPP_DEBUG(LOGGER, "Saved planning query '%s' for scene '%s'", id.c_str(), scene_name.c_str());
   return id;
 }
 
@@ -230,7 +231,7 @@ bool moveit_warehouse::PlanningSceneStorage::getPlanningScene(PlanningSceneWithM
   std::vector<PlanningSceneWithMetadata> planning_scenes = planning_scene_collection_->queryList(q, false);
   if (planning_scenes.empty())
   {
-    RCLCPP_WARN(logger_, "Planning scene '%s' was not found in the database", scene_name.c_str());
+    RCLCPP_WARN(LOGGER, "Planning scene '%s' was not found in the database", scene_name.c_str());
     return false;
   }
   scene_m = planning_scenes.back();
@@ -250,7 +251,7 @@ bool moveit_warehouse::PlanningSceneStorage::getPlanningQuery(MotionPlanRequestW
   std::vector<MotionPlanRequestWithMetadata> planning_queries = motion_plan_request_collection_->queryList(q, false);
   if (planning_queries.empty())
   {
-    RCLCPP_ERROR(logger_, "Planning query '%s' not found for scene '%s'", query_name.c_str(), scene_name.c_str());
+    RCLCPP_ERROR(LOGGER, "Planning query '%s' not found for scene '%s'", query_name.c_str(), scene_name.c_str());
     return false;
   }
   else
@@ -368,7 +369,7 @@ void moveit_warehouse::PlanningSceneStorage::renamePlanningScene(const std::stri
   Metadata::Ptr m = planning_scene_collection_->createMetadata();
   m->append(PLANNING_SCENE_ID_NAME, new_scene_name);
   planning_scene_collection_->modifyMetadata(q, m);
-  RCLCPP_DEBUG(logger_, "Renamed planning scene from '%s' to '%s'", old_scene_name.c_str(), new_scene_name.c_str());
+  RCLCPP_DEBUG(LOGGER, "Renamed planning scene from '%s' to '%s'", old_scene_name.c_str(), new_scene_name.c_str());
 }
 
 void moveit_warehouse::PlanningSceneStorage::renamePlanningQuery(const std::string& scene_name,
@@ -381,7 +382,7 @@ void moveit_warehouse::PlanningSceneStorage::renamePlanningQuery(const std::stri
   Metadata::Ptr m = motion_plan_request_collection_->createMetadata();
   m->append(MOTION_PLAN_REQUEST_ID_NAME, new_query_name);
   motion_plan_request_collection_->modifyMetadata(q, m);
-  RCLCPP_DEBUG(logger_, "Renamed planning query for scene '%s' from '%s' to '%s'", scene_name.c_str(),
+  RCLCPP_DEBUG(LOGGER, "Renamed planning query for scene '%s' from '%s' to '%s'", scene_name.c_str(),
                old_query_name.c_str(), new_query_name.c_str());
 }
 
@@ -391,7 +392,7 @@ void moveit_warehouse::PlanningSceneStorage::removePlanningScene(const std::stri
   Query::Ptr q = planning_scene_collection_->createQuery();
   q->append(PLANNING_SCENE_ID_NAME, scene_name);
   unsigned int rem = planning_scene_collection_->removeMessages(q);
-  RCLCPP_DEBUG(logger_, "Removed %u PlanningScene messages (named '%s')", rem, scene_name.c_str());
+  RCLCPP_DEBUG(LOGGER, "Removed %u PlanningScene messages (named '%s')", rem, scene_name.c_str());
 }
 
 void moveit_warehouse::PlanningSceneStorage::removePlanningQueries(const std::string& scene_name)
@@ -400,7 +401,7 @@ void moveit_warehouse::PlanningSceneStorage::removePlanningQueries(const std::st
   Query::Ptr q = motion_plan_request_collection_->createQuery();
   q->append(PLANNING_SCENE_ID_NAME, scene_name);
   unsigned int rem = motion_plan_request_collection_->removeMessages(q);
-  RCLCPP_DEBUG(logger_, "Removed %u MotionPlanRequest messages for scene '%s'", rem, scene_name.c_str());
+  RCLCPP_DEBUG(LOGGER, "Removed %u MotionPlanRequest messages for scene '%s'", rem, scene_name.c_str());
 }
 
 void moveit_warehouse::PlanningSceneStorage::removePlanningQuery(const std::string& scene_name,
@@ -411,7 +412,7 @@ void moveit_warehouse::PlanningSceneStorage::removePlanningQuery(const std::stri
   q->append(PLANNING_SCENE_ID_NAME, scene_name);
   q->append(MOTION_PLAN_REQUEST_ID_NAME, query_name);
   unsigned int rem = motion_plan_request_collection_->removeMessages(q);
-  RCLCPP_DEBUG(logger_, "Removed %u MotionPlanRequest messages for scene '%s', query '%s'", rem, scene_name.c_str(),
+  RCLCPP_DEBUG(LOGGER, "Removed %u MotionPlanRequest messages for scene '%s', query '%s'", rem, scene_name.c_str(),
                query_name.c_str());
 }
 
@@ -420,7 +421,7 @@ void moveit_warehouse::PlanningSceneStorage::removePlanningResults(const std::st
   Query::Ptr q = robot_trajectory_collection_->createQuery();
   q->append(PLANNING_SCENE_ID_NAME, scene_name);
   unsigned int rem = robot_trajectory_collection_->removeMessages(q);
-  RCLCPP_DEBUG(logger_, "Removed %u RobotTrajectory messages for scene '%s'", rem, scene_name.c_str());
+  RCLCPP_DEBUG(LOGGER, "Removed %u RobotTrajectory messages for scene '%s'", rem, scene_name.c_str());
 }
 
 void moveit_warehouse::PlanningSceneStorage::removePlanningResults(const std::string& scene_name,
@@ -430,6 +431,6 @@ void moveit_warehouse::PlanningSceneStorage::removePlanningResults(const std::st
   q->append(PLANNING_SCENE_ID_NAME, scene_name);
   q->append(MOTION_PLAN_REQUEST_ID_NAME, query_name);
   unsigned int rem = robot_trajectory_collection_->removeMessages(q);
-  RCLCPP_DEBUG(logger_, "Removed %u RobotTrajectory messages for scene '%s', query '%s'", rem, scene_name.c_str(),
+  RCLCPP_DEBUG(LOGGER, "Removed %u RobotTrajectory messages for scene '%s', query '%s'", rem, scene_name.c_str(),
                query_name.c_str());
 }
diff --git a/moveit_ros/warehouse/src/planning_scene_world_storage.cpp b/moveit_ros/warehouse/src/planning_scene_world_storage.cpp
index 066044b1353..310e060f562 100644
--- a/moveit_ros/warehouse/src/planning_scene_world_storage.cpp
+++ b/moveit_ros/warehouse/src/planning_scene_world_storage.cpp
@@ -35,19 +35,19 @@
 /* Author: Ioan Sucan */
 
 #include <moveit/warehouse/planning_scene_world_storage.h>
-#include <moveit/utils/logger.hpp>
 
 #include <utility>
 
 const std::string moveit_warehouse::PlanningSceneWorldStorage::DATABASE_NAME = "moveit_planning_scene_worlds";
 const std::string moveit_warehouse::PlanningSceneWorldStorage::PLANNING_SCENE_WORLD_ID_NAME = "world_id";
 
+static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.warehouse.planning_scene_world_storage");
+
 using warehouse_ros::Metadata;
 using warehouse_ros::Query;
 
 moveit_warehouse::PlanningSceneWorldStorage::PlanningSceneWorldStorage(warehouse_ros::DatabaseConnection::Ptr conn)
   : MoveItMessageStorage(std::move(conn))
-  , logger_(moveit::makeChildLogger("moveit_warehouse_planning_scene_world_storage"))
 {
   createCollections();
 }
@@ -77,7 +77,7 @@ void moveit_warehouse::PlanningSceneWorldStorage::addPlanningSceneWorld(const mo
   Metadata::Ptr metadata = planning_scene_world_collection_->createMetadata();
   metadata->append(PLANNING_SCENE_WORLD_ID_NAME, name);
   planning_scene_world_collection_->insert(msg, metadata);
-  RCLCPP_DEBUG(logger_, "%s planning scene world '%s'", replace ? "Replaced" : "Added", name.c_str());
+  RCLCPP_DEBUG(LOGGER, "%s planning scene world '%s'", replace ? "Replaced" : "Added", name.c_str());
 }
 
 bool moveit_warehouse::PlanningSceneWorldStorage::hasPlanningSceneWorld(const std::string& name) const
@@ -133,7 +133,7 @@ void moveit_warehouse::PlanningSceneWorldStorage::renamePlanningSceneWorld(const
   Metadata::Ptr m = planning_scene_world_collection_->createMetadata();
   m->append(PLANNING_SCENE_WORLD_ID_NAME, new_name);
   planning_scene_world_collection_->modifyMetadata(q, m);
-  RCLCPP_DEBUG(logger_, "Renamed planning scene world from '%s' to '%s'", old_name.c_str(), new_name.c_str());
+  RCLCPP_DEBUG(LOGGER, "Renamed planning scene world from '%s' to '%s'", old_name.c_str(), new_name.c_str());
 }
 
 void moveit_warehouse::PlanningSceneWorldStorage::removePlanningSceneWorld(const std::string& name)
@@ -141,5 +141,5 @@ void moveit_warehouse::PlanningSceneWorldStorage::removePlanningSceneWorld(const
   Query::Ptr q = planning_scene_world_collection_->createQuery();
   q->append(PLANNING_SCENE_WORLD_ID_NAME, name);
   unsigned int rem = planning_scene_world_collection_->removeMessages(q);
-  RCLCPP_DEBUG(logger_, "Removed %u PlanningSceneWorld messages (named '%s')", rem, name.c_str());
+  RCLCPP_DEBUG(LOGGER, "Removed %u PlanningSceneWorld messages (named '%s')", rem, name.c_str());
 }
diff --git a/moveit_ros/warehouse/src/save_as_text.cpp b/moveit_ros/warehouse/src/save_as_text.cpp
index 96e9780db3f..d42ae85996c 100644
--- a/moveit_ros/warehouse/src/save_as_text.cpp
+++ b/moveit_ros/warehouse/src/save_as_text.cpp
@@ -49,15 +49,14 @@
 #include <rclcpp/node.hpp>
 #include <rclcpp/node_options.hpp>
 #include <rclcpp/utilities.hpp>
-#include <moveit/utils/logger.hpp>
 
 static const std::string ROBOT_DESCRIPTION = "robot_description";
 
+static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.warehouse.save_to_text");
+
 typedef std::pair<geometry_msgs::msg::Point, geometry_msgs::msg::Quaternion> LinkConstraintPair;
 typedef std::map<std::string, LinkConstraintPair> LinkConstraintMap;
 
-using moveit::getLogger;
-
 void collectLinkConstraints(const moveit_msgs::msg::Constraints& constraints, LinkConstraintMap& lcmap)
 {
   for (const moveit_msgs::msg::PositionConstraint& position_constraint : constraints.position_constraints)
@@ -76,7 +75,7 @@ void collectLinkConstraints(const moveit_msgs::msg::Constraints& constraints, Li
     }
     else
     {
-      RCLCPP_WARN(getLogger(), "Orientation constraint for %s has no matching position constraint",
+      RCLCPP_WARN(LOGGER, "Orientation constraint for %s has no matching position constraint",
                   orientation_constraint.link_name.c_str());
     }
   }
@@ -89,7 +88,6 @@ int main(int argc, char** argv)
   node_options.allow_undeclared_parameters(true);
   node_options.automatically_declare_parameters_from_overrides(true);
   rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("save_warehouse_as_text", node_options);
-  moveit::getLoggerMut() = node->get_logger();
 
   boost::program_options::options_description desc;
   desc.add_options()("help", "Show help message")("host", boost::program_options::value<std::string>(),
@@ -127,7 +125,7 @@ int main(int argc, char** argv)
     moveit_warehouse::PlanningSceneWithMetadata pswm;
     if (pss.getPlanningScene(pswm, scene_name))
     {
-      RCLCPP_INFO(getLogger(), "Saving scene '%s'", scene_name.c_str());
+      RCLCPP_INFO(LOGGER, "Saving scene '%s'", scene_name.c_str());
       psm.getPlanningScene()->setPlanningSceneMsg(static_cast<const moveit_msgs::msg::PlanningScene&>(*pswm));
       std::ofstream fout((scene_name + ".scene").c_str());
       psm.getPlanningScene()->saveGeometryToStream(fout);
@@ -157,7 +155,7 @@ int main(int argc, char** argv)
           qfout << robot_state_names.size() << '\n';
           for (const std::string& robot_state_name : robot_state_names)
           {
-            RCLCPP_INFO(getLogger(), "Saving start state %s for scene %s", robot_state_name.c_str(), scene_name.c_str());
+            RCLCPP_INFO(LOGGER, "Saving start state %s for scene %s", robot_state_name.c_str(), scene_name.c_str());
             qfout << robot_state_name << '\n';
             moveit_warehouse::RobotStateWithMetadata robot_state;
             rss.getRobotState(robot_state, robot_state_name);
@@ -174,7 +172,7 @@ int main(int argc, char** argv)
           qfout << constraint_names.size() << '\n';
           for (const std::string& constraint_name : constraint_names)
           {
-            RCLCPP_INFO(getLogger(), "Saving goal %s for scene %s", constraint_name.c_str(), scene_name.c_str());
+            RCLCPP_INFO(LOGGER, "Saving goal %s for scene %s", constraint_name.c_str(), scene_name.c_str());
             qfout << "link_constraint" << '\n';
             qfout << constraint_name << '\n';
             moveit_warehouse::ConstraintsWithMetadata constraints;
@@ -200,7 +198,7 @@ int main(int argc, char** argv)
     }
   }
 
-  RCLCPP_INFO(getLogger(), "Done.");
+  RCLCPP_INFO(LOGGER, "Done.");
   rclcpp::spin(node);
   return 0;
 }
diff --git a/moveit_ros/warehouse/src/save_to_warehouse.cpp b/moveit_ros/warehouse/src/save_to_warehouse.cpp
index f4d68a10ad3..e7f5a47bc6f 100644
--- a/moveit_ros/warehouse/src/save_to_warehouse.cpp
+++ b/moveit_ros/warehouse/src/save_to_warehouse.cpp
@@ -38,7 +38,6 @@
 #include <moveit/warehouse/constraints_storage.h>
 #include <moveit/warehouse/state_storage.h>
 #include <moveit/planning_scene_monitor/planning_scene_monitor.h>
-#include <moveit/utils/logger.hpp>
 #include <boost/program_options/cmdline.hpp>
 #include <boost/program_options/options_description.hpp>
 #include <boost/program_options/parsers.hpp>
@@ -60,13 +59,13 @@
 #include <rclcpp/subscription.hpp>
 #include <rclcpp/utilities.hpp>
 
-using moveit::getLogger;
-
 static const std::string ROBOT_DESCRIPTION = "robot_description";
 
+static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.warehouse.save_to_warehouse");
+
 void onSceneUpdate(planning_scene_monitor::PlanningSceneMonitor& psm, moveit_warehouse::PlanningSceneStorage& pss)
 {
-  RCLCPP_INFO(getLogger(), "Received an update to the planning scene...");
+  RCLCPP_INFO(LOGGER, "Received an update to the planning scene...");
 
   if (!psm.getPlanningScene()->getName().empty())
   {
@@ -78,12 +77,12 @@ void onSceneUpdate(planning_scene_monitor::PlanningSceneMonitor& psm, moveit_war
     }
     else
     {
-      RCLCPP_INFO(getLogger(), "Scene '%s' was previously added. Not adding again.",
+      RCLCPP_INFO(LOGGER, "Scene '%s' was previously added. Not adding again.",
                   psm.getPlanningScene()->getName().c_str());
     }
   }
   else
-    RCLCPP_INFO(getLogger(), "Scene name is empty. Not saving.");
+    RCLCPP_INFO(LOGGER, "Scene name is empty. Not saving.");
 }
 
 void onMotionPlanRequest(const moveit_msgs::msg::MotionPlanRequest& req,
@@ -91,7 +90,7 @@ void onMotionPlanRequest(const moveit_msgs::msg::MotionPlanRequest& req,
 {
   if (psm.getPlanningScene()->getName().empty())
   {
-    RCLCPP_INFO(getLogger(), "Scene name is empty. Not saving planning request.");
+    RCLCPP_INFO(LOGGER, "Scene name is empty. Not saving planning request.");
     return;
   }
   pss.addPlanningQuery(req, psm.getPlanningScene()->getName());
@@ -101,19 +100,19 @@ void onConstraints(const moveit_msgs::msg::Constraints& msg, moveit_warehouse::C
 {
   if (msg.name.empty())
   {
-    RCLCPP_INFO(getLogger(), "No name specified for constraints. Not saving.");
+    RCLCPP_INFO(LOGGER, "No name specified for constraints. Not saving.");
     return;
   }
 
   if (cs.hasConstraints(msg.name))
   {
-    RCLCPP_INFO(getLogger(), "Replacing constraints '%s'", msg.name.c_str());
+    RCLCPP_INFO(LOGGER, "Replacing constraints '%s'", msg.name.c_str());
     cs.removeConstraints(msg.name);
     cs.addConstraints(msg);
   }
   else
   {
-    RCLCPP_INFO(getLogger(), "Adding constraints '%s'", msg.name.c_str());
+    RCLCPP_INFO(LOGGER, "Adding constraints '%s'", msg.name.c_str());
     cs.addConstraints(msg);
   }
 }
@@ -127,7 +126,7 @@ void onRobotState(const moveit_msgs::msg::RobotState& msg, moveit_warehouse::Rob
   while (names_set.find("S" + std::to_string(n)) != names_set.end())
     n++;
   std::string name = "S" + std::to_string(n);
-  RCLCPP_INFO(getLogger(), "Adding robot state '%s'", name.c_str());
+  RCLCPP_INFO(LOGGER, "Adding robot state '%s'", name.c_str());
   rs.addRobotState(msg, name);
 }
 
@@ -138,7 +137,6 @@ int main(int argc, char** argv)
   node_options.allow_undeclared_parameters(true);
   node_options.automatically_declare_parameters_from_overrides(true);
   rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("save_to_warehouse", node_options);
-  moveit::getLoggerMut() = node->get_logger();
 
   boost::program_options::options_description desc;
   desc.add_options()("help", "Show help message")("host", boost::program_options::value<std::string>(),
@@ -165,7 +163,7 @@ int main(int argc, char** argv)
   planning_scene_monitor::PlanningSceneMonitor psm(node, ROBOT_DESCRIPTION);
   if (!psm.getPlanningScene())
   {
-    RCLCPP_ERROR(getLogger(), "Unable to initialize PlanningSceneMonitor");
+    RCLCPP_ERROR(LOGGER, "Unable to initialize PlanningSceneMonitor");
     return 1;
   }
 
@@ -178,35 +176,31 @@ int main(int argc, char** argv)
   pss.getPlanningSceneNames(names);
   if (names.empty())
   {
-    RCLCPP_INFO(getLogger(), "There are no previously stored scenes");
+    RCLCPP_INFO(LOGGER, "There are no previously stored scenes");
   }
   else
   {
-    RCLCPP_INFO(getLogger(), "Previously stored scenes:");
+    RCLCPP_INFO(LOGGER, "Previously stored scenes:");
     for (const std::string& name : names)
-      RCLCPP_INFO(getLogger(), " * %s", name.c_str());
+      RCLCPP_INFO(LOGGER, " * %s", name.c_str());
   }
   cs.getKnownConstraints(names);
   if (names.empty())
   {
-    RCLCPP_INFO(getLogger(), "There are no previously stored constraints");
+    RCLCPP_INFO(LOGGER, "There are no previously stored constraints");
   }
   else
   {
-    RCLCPP_INFO(getLogger(), "Previously stored constraints:");
+    RCLCPP_INFO(LOGGER, "Previously stored constraints:");
     for (const std::string& name : names)
-      RCLCPP_INFO(getLogger(), " * %s", name.c_str());
-  }
-  rs.getKnownRobotStates(names);
-  if (names.empty())
-  {
-    RCLCPP_INFO(getLogger(), "There are no previously stored robot states");
+      RCLCPP_INFO(LOGGER, " * %s", name.c_str());
+    RCLCPP_INFO(LOGGER, "There are no previously stored robot states");
   }
   else
   {
-    RCLCPP_INFO(getLogger(), "Previously stored robot states:");
+    RCLCPP_INFO(LOGGER, "Previously stored robot states:");
     for (const std::string& name : names)
-      RCLCPP_INFO(getLogger(), " * %s", name.c_str());
+      RCLCPP_INFO(LOGGER, " * %s", name.c_str());
   }
 
   psm.addUpdateCallback([&](auto&&) { return onSceneUpdate(psm, pss); });
@@ -223,11 +217,10 @@ int main(int argc, char** argv)
 
   std::vector<std::string> topics;
   psm.getMonitoredTopics(topics);
-  RCLCPP_INFO_STREAM(getLogger(),
-                     "Listening for scene updates on topics " << fmt::format("{}", fmt::join(topics, ", ")));
-  RCLCPP_INFO_STREAM(getLogger(), "Listening for planning requests on topic " << mplan_req_sub->get_topic_name());
-  RCLCPP_INFO_STREAM(getLogger(), "Listening for named constraints on topic " << constr_sub->get_topic_name());
-  RCLCPP_INFO_STREAM(getLogger(), "Listening for states on topic " << state_sub->get_topic_name());
+  RCLCPP_INFO_STREAM(LOGGER, "Listening for scene updates on topics " << fmt::format("{}", fmt::join(topics, ", ")));
+  RCLCPP_INFO_STREAM(LOGGER, "Listening for planning requests on topic " << mplan_req_sub->get_topic_name());
+  RCLCPP_INFO_STREAM(LOGGER, "Listening for named constraints on topic " << constr_sub->get_topic_name());
+  RCLCPP_INFO_STREAM(LOGGER, "Listening for states on topic " << state_sub->get_topic_name());
 
   rclcpp::spin(node);
   return 0;
diff --git a/moveit_ros/warehouse/src/state_storage.cpp b/moveit_ros/warehouse/src/state_storage.cpp
index bbbfa81587b..cea0e6a52f9 100644
--- a/moveit_ros/warehouse/src/state_storage.cpp
+++ b/moveit_ros/warehouse/src/state_storage.cpp
@@ -35,7 +35,6 @@
 /* Author: Ioan Sucan */
 
 #include <moveit/warehouse/state_storage.h>
-#include <moveit/utils/logger.hpp>
 
 #include <utility>
 
@@ -44,11 +43,13 @@ const std::string moveit_warehouse::RobotStateStorage::DATABASE_NAME = "moveit_r
 const std::string moveit_warehouse::RobotStateStorage::STATE_NAME = "state_id";
 const std::string moveit_warehouse::RobotStateStorage::ROBOT_NAME = "robot_id";
 
+static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.warehouse.state_storage");
+
 using warehouse_ros::Metadata;
 using warehouse_ros::Query;
 
 moveit_warehouse::RobotStateStorage::RobotStateStorage(warehouse_ros::DatabaseConnection::Ptr conn)
-  : MoveItMessageStorage(std::move(conn)), logger_(moveit::makeChildLogger("moveit_warehouse_robot_state_storage"))
+  : MoveItMessageStorage(std::move(conn))
 {
   createCollections();
 }
@@ -78,7 +79,7 @@ void moveit_warehouse::RobotStateStorage::addRobotState(const moveit_msgs::msg::
   metadata->append(STATE_NAME, name);
   metadata->append(ROBOT_NAME, robot);
   state_collection_->insert(msg, metadata);
-  RCLCPP_DEBUG(logger_, "%s robot state '%s'", replace ? "Replaced" : "Added", name.c_str());
+  RCLCPP_DEBUG(LOGGER, "%s robot state '%s'", replace ? "Replaced" : "Added", name.c_str());
 }
 
 bool moveit_warehouse::RobotStateStorage::hasRobotState(const std::string& name, const std::string& robot) const
@@ -142,7 +143,7 @@ void moveit_warehouse::RobotStateStorage::renameRobotState(const std::string& ol
   Metadata::Ptr m = state_collection_->createMetadata();
   m->append(STATE_NAME, new_name);
   state_collection_->modifyMetadata(q, m);
-  RCLCPP_DEBUG(logger_, "Renamed robot state from '%s' to '%s'", old_name.c_str(), new_name.c_str());
+  RCLCPP_DEBUG(LOGGER, "Renamed robot state from '%s' to '%s'", old_name.c_str(), new_name.c_str());
 }
 
 void moveit_warehouse::RobotStateStorage::removeRobotState(const std::string& name, const std::string& robot)
@@ -152,5 +153,5 @@ void moveit_warehouse::RobotStateStorage::removeRobotState(const std::string& na
   if (!robot.empty())
     q->append(ROBOT_NAME, robot);
   unsigned int rem = state_collection_->removeMessages(q);
-  RCLCPP_DEBUG(logger_, "Removed %u RobotState messages (named '%s')", rem, name.c_str());
+  RCLCPP_DEBUG(LOGGER, "Removed %u RobotState messages (named '%s')", rem, name.c_str());
 }
diff --git a/moveit_ros/warehouse/src/trajectory_constraints_storage.cpp b/moveit_ros/warehouse/src/trajectory_constraints_storage.cpp
index 009c162c7a4..8ba11a3ba1d 100644
--- a/moveit_ros/warehouse/src/trajectory_constraints_storage.cpp
+++ b/moveit_ros/warehouse/src/trajectory_constraints_storage.cpp
@@ -35,7 +35,6 @@
 /* Author: Mario Prats, Ioan Sucan */
 
 #include <moveit/warehouse/trajectory_constraints_storage.h>
-#include <moveit/utils/logger.hpp>
 
 #include <utility>
 
@@ -45,12 +44,13 @@ const std::string moveit_warehouse::TrajectoryConstraintsStorage::CONSTRAINTS_ID
 const std::string moveit_warehouse::TrajectoryConstraintsStorage::CONSTRAINTS_GROUP_NAME = "group_id";
 const std::string moveit_warehouse::TrajectoryConstraintsStorage::ROBOT_NAME = "robot_id";
 
+static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.warehouse.trajectory_constraints_storage");
+
 using warehouse_ros::Metadata;
 using warehouse_ros::Query;
 
 moveit_warehouse::TrajectoryConstraintsStorage::TrajectoryConstraintsStorage(warehouse_ros::DatabaseConnection::Ptr conn)
   : MoveItMessageStorage(std::move(conn))
-  , logger_(moveit::makeChildLogger("moveit_warehouse_trajectory_constraints_storage"))
 {
   createCollections();
 }
@@ -83,7 +83,7 @@ void moveit_warehouse::TrajectoryConstraintsStorage::addTrajectoryConstraints(
   metadata->append(ROBOT_NAME, robot);
   metadata->append(CONSTRAINTS_GROUP_NAME, group);
   constraints_collection_->insert(msg, metadata);
-  RCLCPP_DEBUG(logger_, "%s constraints '%s'", replace ? "Replaced" : "Added", name.c_str());
+  RCLCPP_DEBUG(LOGGER, "%s constraints '%s'", replace ? "Replaced" : "Added", name.c_str());
 }
 
 bool moveit_warehouse::TrajectoryConstraintsStorage::hasTrajectoryConstraints(const std::string& name,
@@ -165,7 +165,7 @@ void moveit_warehouse::TrajectoryConstraintsStorage::renameTrajectoryConstraints
   Metadata::Ptr m = constraints_collection_->createMetadata();
   m->append(CONSTRAINTS_ID_NAME, new_name);
   constraints_collection_->modifyMetadata(q, m);
-  RCLCPP_DEBUG(logger_, "Renamed constraints from '%s' to '%s'", old_name.c_str(), new_name.c_str());
+  RCLCPP_DEBUG(LOGGER, "Renamed constraints from '%s' to '%s'", old_name.c_str(), new_name.c_str());
 }
 
 void moveit_warehouse::TrajectoryConstraintsStorage::removeTrajectoryConstraints(const std::string& name,
@@ -179,5 +179,5 @@ void moveit_warehouse::TrajectoryConstraintsStorage::removeTrajectoryConstraints
   if (!group.empty())
     q->append(CONSTRAINTS_GROUP_NAME, group);
   unsigned int rem = constraints_collection_->removeMessages(q);
-  RCLCPP_DEBUG(logger_, "Removed %u TrajectoryConstraints messages (named '%s')", rem, name.c_str());
+  RCLCPP_DEBUG(LOGGER, "Removed %u TrajectoryConstraints messages (named '%s')", rem, name.c_str());
 }
diff --git a/moveit_ros/warehouse/src/warehouse_connector.cpp b/moveit_ros/warehouse/src/warehouse_connector.cpp
index 4c4521f61c2..f75123c50b9 100644
--- a/moveit_ros/warehouse/src/warehouse_connector.cpp
+++ b/moveit_ros/warehouse/src/warehouse_connector.cpp
@@ -40,16 +40,17 @@
 #include <rclcpp/logger.hpp>
 #include <rclcpp/logging.hpp>
 #include <rclcpp/utilities.hpp>
-#include <moveit/utils/logger.hpp>
+
+static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.warehouse.warehouse_connector");
 
 #ifdef _WIN32
 void kill(int, int)
 {
-  RCLCPP_ERROR(moveit::getLogger(), "Warehouse connector not supported on Windows");
+  RCLCPP_ERROR(LOGGER, "Warehouse connector not supported on Windows");
 }  // Should never be called
 int fork()
 {
-  RCLCPP_ERROR(moveit::getLogger(), "Warehouse connector not supported on Windows");
+  RCLCPP_ERROR(LOGGER, "Warehouse connector not supported on Windows");
   return -1;
 }
 #else
@@ -58,8 +59,7 @@ int fork()
 
 namespace moveit_warehouse
 {
-WarehouseConnector::WarehouseConnector(const std::string& dbexec)
-  : dbexec_(dbexec), child_pid_(0), logger_(moveit::makeChildLogger("moveit_warehouse_warehouse_connector"))
+WarehouseConnector::WarehouseConnector(const std::string& dbexec) : dbexec_(dbexec), child_pid_(0)
 {
 }
 
@@ -77,7 +77,7 @@ bool WarehouseConnector::connectToDatabase(const std::string& dirname)
   child_pid_ = fork();
   if (child_pid_ == -1)
   {
-    RCLCPP_ERROR(logger_, "Error forking process.");
+    RCLCPP_ERROR(LOGGER, "Error forking process.");
     child_pid_ = 0;
     return false;
   }
@@ -105,7 +105,7 @@ bool WarehouseConnector::connectToDatabase(const std::string& dirname)
       delete[] argv[1];
       delete[] argv[2];
       delete[] argv;
-      RCLCPP_ERROR_STREAM(logger_,
+      RCLCPP_ERROR_STREAM(LOGGER,
                           "execv() returned " << code << ", errno=" << errno << " string errno = " << strerror(errno));
     }
     return false;
diff --git a/moveit_ros/warehouse/src/warehouse_services.cpp b/moveit_ros/warehouse/src/warehouse_services.cpp
index 7234adc9d33..a7977f63dc4 100644
--- a/moveit_ros/warehouse/src/warehouse_services.cpp
+++ b/moveit_ros/warehouse/src/warehouse_services.cpp
@@ -48,19 +48,18 @@
 #include <rclcpp/node_options.hpp>
 #include <rclcpp/parameter_value.hpp>
 #include <rclcpp/utilities.hpp>
-#include <moveit/utils/logger.hpp>
-
-using moveit::getLogger;
 
 static const std::string ROBOT_DESCRIPTION = "robot_description";
 
+static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.warehouse.warehouse_services");
+
 bool storeState(const std::shared_ptr<moveit_msgs::srv::SaveRobotStateToWarehouse::Request>& request,
                 const std::shared_ptr<moveit_msgs::srv::SaveRobotStateToWarehouse::Response>& response,
                 moveit_warehouse::RobotStateStorage& rs)
 {
   if (request->name.empty())
   {
-    RCLCPP_ERROR(getLogger(), "You must specify a name to store a state");
+    RCLCPP_ERROR(LOGGER, "You must specify a name to store a state");
     return (response->success = false);
   }
   rs.addRobotState(request->state, request->name, request->robot);
@@ -96,7 +95,7 @@ bool getState(const std::shared_ptr<moveit_msgs::srv::GetRobotStateFromWarehouse
 {
   if (!rs.hasRobotState(request->name, request->robot))
   {
-    RCLCPP_ERROR_STREAM(getLogger(), "No state called '" << request->name << "' for robot '" << request->robot << "'.");
+    RCLCPP_ERROR_STREAM(LOGGER, "No state called '" << request->name << "' for robot '" << request->robot << "'.");
     moveit_msgs::msg::RobotState dummy;
     response->state = dummy;
     return false;
@@ -113,8 +112,7 @@ bool renameState(const std::shared_ptr<moveit_msgs::srv::RenameRobotStateInWareh
 {
   if (!rs.hasRobotState(request->old_name, request->robot))
   {
-    RCLCPP_ERROR_STREAM(getLogger(),
-                        "No state called '" << request->old_name << "' for robot '" << request->robot << "'.");
+    RCLCPP_ERROR_STREAM(LOGGER, "No state called '" << request->old_name << "' for robot '" << request->robot << "'.");
     return false;
   }
   rs.renameRobotState(request->old_name, request->new_name, request->robot);
@@ -127,7 +125,7 @@ bool deleteState(const std::shared_ptr<moveit_msgs::srv::DeleteRobotStateFromWar
 {
   if (!rs.hasRobotState(request->name, request->robot))
   {
-    RCLCPP_ERROR_STREAM(getLogger(), "No state called '" << request->name << "' for robot '" << request->robot << "'.");
+    RCLCPP_ERROR_STREAM(LOGGER, "No state called '" << request->name << "' for robot '" << request->robot << "'.");
     return false;
   }
   rs.removeRobotState(request->name, request->robot);
@@ -141,7 +139,6 @@ int main(int argc, char** argv)
   node_options.allow_undeclared_parameters(true);
   node_options.automatically_declare_parameters_from_overrides(true);
   rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("moveit_warehouse_services", node_options);
-  moveit::getLoggerMut() = node->get_logger();
 
   std::string host;
 
@@ -161,23 +158,23 @@ int main(int argc, char** argv)
     conn = moveit_warehouse::loadDatabase(node);
     conn->setParams(host, port, connection_timeout);
 
-    RCLCPP_INFO(getLogger(), "Connecting to warehouse on %s:%d", host.c_str(), port);
+    RCLCPP_INFO(LOGGER, "Connecting to warehouse on %s:%d", host.c_str(), port);
     int tries = 0;
     while (!conn->connect())
     {
       ++tries;
-      RCLCPP_WARN(getLogger(), "Failed to connect to DB on %s:%d (try %d/%d).", host.c_str(), port, tries,
+      RCLCPP_WARN(LOGGER, "Failed to connect to DB on %s:%d (try %d/%d).", host.c_str(), port, tries,
                   connection_retries);
       if (tries == connection_retries)
       {
-        RCLCPP_FATAL(getLogger(), "Failed to connect too many times, giving up");
+        RCLCPP_FATAL(LOGGER, "Failed to connect too many times, giving up");
         return 1;
       }
     }
   }
   catch (std::exception& ex)
   {
-    RCLCPP_ERROR(getLogger(), "%s", ex.what());
+    RCLCPP_ERROR(LOGGER, "%s", ex.what());
     return 1;
   }
 
@@ -187,13 +184,13 @@ int main(int argc, char** argv)
   rs.getKnownRobotStates(names);
   if (names.empty())
   {
-    RCLCPP_INFO(getLogger(), "There are no previously stored robot states");
+    RCLCPP_INFO(LOGGER, "There are no previously stored robot states");
   }
   else
   {
-    RCLCPP_INFO(getLogger(), "Previously stored robot states:");
-    for (const std::string& name : names)
-      RCLCPP_INFO(getLogger(), " * %s", name.c_str());
+    RCLCPP_INFO(LOGGER, "Previously stored robot states:");
+    RCLCPP_INFO(get_logger(), " * %s", name.c_str());
+    RCLCPP_INFO(LOGGER, " * %s", name.c_str());
   }
 
   auto save_cb = [&](const std::shared_ptr<moveit_msgs::srv::SaveRobotStateToWarehouse::Request>& request,