From dc01ae33df33fae6a0f3a142cd2613208e3b78d4 Mon Sep 17 00:00:00 2001 From: "Dr. Denis" Date: Tue, 20 Jun 2023 21:21:35 +0200 Subject: [PATCH 1/3] [CM] Improve output when using robot description topic and give output about correct topic even remapped. (#1059) --- controller_manager/src/controller_manager.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index 69a3bbb5f3..83604cd249 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -203,16 +203,17 @@ void ControllerManager::subscribe_to_robot_description_topic() { // 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."); robot_description_subscription_ = create_subscription( "~/robot_description", rclcpp::QoS(1).transient_local(), std::bind(&ControllerManager::robot_description_callback, this, std::placeholders::_1)); + RCLCPP_INFO( + get_logger(), "Subscribing to '%s' topic for robot description.", + robot_description_subscription_->get_topic_name()); } void ControllerManager::robot_description_callback(const std_msgs::msg::String & robot_description) { - RCLCPP_INFO(get_logger(), "Received robot description file."); + RCLCPP_INFO(get_logger(), "Received robot description from topic."); 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 From e14497e9f581197a70ba8bf50fd2efac8c603281 Mon Sep 17 00:00:00 2001 From: "Dr. Denis" Date: Tue, 20 Jun 2023 22:07:36 +0200 Subject: [PATCH 2/3] Improve list hardware components output and code for better readability. (#1060) --- .../ros2controlcli/verb/list_hardware_components.py | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/ros2controlcli/ros2controlcli/verb/list_hardware_components.py b/ros2controlcli/ros2controlcli/verb/list_hardware_components.py index 54dff21bb6..8a5884f2cb 100644 --- a/ros2controlcli/ros2controlcli/verb/list_hardware_components.py +++ b/ros2controlcli/ros2controlcli/verb/list_hardware_components.py @@ -40,7 +40,7 @@ def main(self, *, args): for idx, component in enumerate(hardware_components.component): print( - f"Hardware Component {idx}\n\tname: {component.name}\n\ttype: {component.type}" + f"Hardware Component {idx+1}\n\tname: {component.name}\n\ttype: {component.type}" ) if hasattr(component, "plugin_name"): plugin_name = component.plugin_name @@ -48,7 +48,9 @@ def main(self, *, args): plugin_name = f"{bcolors.WARNING}plugin name missing!{bcolors.ENDC}" print( - f"\tplugin name: {plugin_name}\n\tstate: id={component.state.id} label={component.state.label}\n\tcommand interfaces" + f"\tplugin name: {plugin_name}\n" + f"\tstate: id={component.state.id} label={component.state.label}\n" + f"\tcommand interfaces" ) for cmd_interface in component.command_interfaces: if cmd_interface.is_available: From db34dfaf2d79fc8afcd460d9ae16f02c43265a2a Mon Sep 17 00:00:00 2001 From: Olivier Stasse Date: Wed, 21 Jun 2023 09:34:49 +0200 Subject: [PATCH 3/3] Ensure instantiation of hardware classes work for python bindings (#1058) --- hardware_interface/CMakeLists.txt | 4 +++ .../include/hardware_interface/system.hpp | 2 ++ .../test/test_inst_hardwares.cpp | 34 +++++++++++++++++++ 3 files changed, 40 insertions(+) create mode 100644 hardware_interface/test/test_inst_hardwares.cpp diff --git a/hardware_interface/CMakeLists.txt b/hardware_interface/CMakeLists.txt index 6548d6186c..2d6c72ffae 100644 --- a/hardware_interface/CMakeLists.txt +++ b/hardware_interface/CMakeLists.txt @@ -80,6 +80,10 @@ if(BUILD_TESTING) target_include_directories(test_macros PRIVATE include) ament_target_dependencies(test_macros rcpputils) + ament_add_gmock(test_inst_hardwares test/test_inst_hardwares.cpp) + target_link_libraries(test_inst_hardwares hardware_interface) + ament_target_dependencies(test_inst_hardwares rcpputils) + ament_add_gmock(test_joint_handle test/test_handle.cpp) target_link_libraries(test_joint_handle hardware_interface) ament_target_dependencies(test_joint_handle rcpputils) diff --git a/hardware_interface/include/hardware_interface/system.hpp b/hardware_interface/include/hardware_interface/system.hpp index 4c9ae67ae2..ece14f814d 100644 --- a/hardware_interface/include/hardware_interface/system.hpp +++ b/hardware_interface/include/hardware_interface/system.hpp @@ -35,6 +35,8 @@ class SystemInterface; class System final { public: + System() = default; + HARDWARE_INTERFACE_PUBLIC explicit System(std::unique_ptr impl); diff --git a/hardware_interface/test/test_inst_hardwares.cpp b/hardware_interface/test/test_inst_hardwares.cpp new file mode 100644 index 0000000000..ddd3aea0ad --- /dev/null +++ b/hardware_interface/test/test_inst_hardwares.cpp @@ -0,0 +1,34 @@ +// Copyright 2023 LAAS CNRS +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include "hardware_interface/actuator.hpp" +#include "hardware_interface/actuator_interface.hpp" +#include "hardware_interface/sensor.hpp" +#include "hardware_interface/sensor_interface.hpp" +#include "hardware_interface/system.hpp" +#include "hardware_interface/system_interface.hpp" + +class TestInstantiationHardwares : public ::testing::Test +{ +protected: + static void SetUpTestCase() {} +}; + +TEST_F(TestInstantiationHardwares, build_actuator) { hardware_interface::Actuator anActuator; } + +TEST_F(TestInstantiationHardwares, build_sensor) { hardware_interface::Sensor aSensor; } + +TEST_F(TestInstantiationHardwares, build_system) { hardware_interface::System aSystem; }