From 09329fb020480eea7d53b8b2fe3968f418bc62fa Mon Sep 17 00:00:00 2001 From: "Dr. Denis" Date: Tue, 4 Apr 2023 13:24:23 +0200 Subject: [PATCH] Apply suggestions from code review --- controller_manager/src/controller_manager.cpp | 9 ++++----- .../include/hardware_interface/resource_manager.hpp | 6 +++--- hardware_interface/src/resource_manager.cpp | 4 ++-- 3 files changed, 9 insertions(+), 10 deletions(-) diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index a55b30993a1..a46f8ff7aea 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -157,7 +157,7 @@ ControllerManager::ControllerManager( // set QoS to transient local to get messages that have already been published // (if robot state publisher starts before controller manager) RCLCPP_INFO( - get_logger(), "Subscribing to ~/robot_description topic for robot description file."); + get_logger(), "Subscribing to '~/robot_description' topic for robot description file."); robot_description_subscription_ = create_subscription( namespace_ + "/robot_description", rclcpp::QoS(1).transient_local(), std::bind(&ControllerManager::robot_description_callback, this, std::placeholders::_1)); @@ -174,7 +174,6 @@ ControllerManager::ControllerManager( diagnostics_updater_.setHardwareID("ros2_control"); diagnostics_updater_.add( "Controllers Activity", this, &ControllerManager::controller_activity_diagnostic_callback); - init_services(); } @@ -207,7 +206,7 @@ void ControllerManager::robot_description_callback(const std_msgs::msg::String & RCLCPP_INFO(get_logger(), "Received robot description file."); RCLCPP_DEBUG( get_logger(), "'Content of robot description file: %s", robot_description.data.c_str()); - // TODO(Manuel) errors should probably be caught since we don't want controller_manager node + // TODO(Manuel): errors should probably be caught since we don't want controller_manager node // to die if a non valid urdf is passed. However, should maybe be fine tuned. try { @@ -225,8 +224,8 @@ void ControllerManager::robot_description_callback(const std_msgs::msg::String & { RCLCPP_ERROR_STREAM( get_logger(), - "The published robot description file (urdf) seems not to be genuine. Following error was " - "caught:" + "The published robot description file (urdf) seems not to be genuine. The following error " + "was caught:" << e.what()); } } diff --git a/hardware_interface/include/hardware_interface/resource_manager.hpp b/hardware_interface/include/hardware_interface/resource_manager.hpp index 4a6567a7ea3..3d78cf7b445 100644 --- a/hardware_interface/include/hardware_interface/resource_manager.hpp +++ b/hardware_interface/include/hardware_interface/resource_manager.hpp @@ -87,10 +87,10 @@ class HARDWARE_INTERFACE_PUBLIC ResourceManager /** * @brief if the resource manager load_urdf(...) function has been called this returns true. * We want to permit to load the urdf later on but we currently don't want to permit multiple - * calls to load_urdf (reloading/loading different urdf) + * calls to load_urdf (reloading/loading different urdf). * - * @return true if resource manager's load_urdf() has been called - * @return false if resource manager's load_urdf() has not been called + * @return true if resource manager's load_urdf() has been already called. + * @return false if resource manager's load_urdf() has not been yet called. */ bool load_urdf_called() const; diff --git a/hardware_interface/src/resource_manager.cpp b/hardware_interface/src/resource_manager.cpp index 9d438dfad09..42285a28395 100644 --- a/hardware_interface/src/resource_manager.cpp +++ b/hardware_interface/src/resource_manager.cpp @@ -574,8 +574,8 @@ ResourceManager::ResourceManager() : resource_storage_(std::make_unique()), load_urdf_called_(load_urdf_called) + const std::string & urdf, bool validate_interfaces, bool activate_all) +: resource_storage_(std::make_unique()) { load_urdf(urdf, validate_interfaces);