2222#include < memory>
2323#include < string>
2424#include < thread>
25+ #include < utility>
2526#include < vector>
2627
2728#include " controller_interface/controller_interface.hpp"
2829
2930#include " controller_manager/controller_manager.hpp"
31+ #include " controller_manager_msgs/srv/list_hardware_interfaces.hpp"
3032#include " controller_manager_msgs/srv/switch_controller.hpp"
3133
3234#include " rclcpp/rclcpp.hpp"
@@ -63,14 +65,14 @@ template <typename CtrlMgr>
6365class ControllerManagerFixture : public ::testing::Test
6466{
6567public:
66- // TODO parameter hinzufügen, welche hw erwartet wird
68+ // TODO(Manuel): Maybe add parameter of which hardware is to be expected
6769 explicit ControllerManagerFixture (
6870 const std::string & robot_description = ros2_control_test_assets::minimal_robot_urdf,
6971 const std::string ns = " /" , const bool & pass_urdf_as_parameter = false )
7072 : robot_description_(robot_description), ns_(ns), pass_urdf_as_parameter_(pass_urdf_as_parameter)
7173 {
7274 executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
73- // We want ot be able to create a ResourceManager where no urdf file has been passed to
75+ // We want to be able to create a ResourceManager where no urdf file has been passed to
7476 if (robot_description_.empty ())
7577 {
7678 cm_ = std::make_shared<CtrlMgr>(
@@ -88,18 +90,37 @@ class ControllerManagerFixture : public ::testing::Test
8890 }
8991 else
9092 {
93+ // First wie create a node and a publisher for publishing the passed robot description file
9194 urdf_publisher_node_ = std::make_shared<rclcpp::Node>(" robot_description_publisher" , ns_);
9295 description_pub_ = urdf_publisher_node_->create_publisher <std_msgs::msg::String>(
9396 " robot_description" , rclcpp::QoS (1 ).transient_local ());
9497 executor_->add_node (urdf_publisher_node_);
9598 publish_robot_description_file (robot_description_);
96-
99+ // Then we create controller manager which subscribes to topic and receive
100+ // published robot description file. Publishing is transient_local so starting cm
101+ // later should not pose problem and is closer to real world applications
97102 cm_ = std::make_shared<CtrlMgr>(
98103 std::make_unique<hardware_interface::ResourceManager>(), executor_, TEST_CM_NAME);
99-
100- // TODO warten bis hw da ist und initialisiert
101- // von urdf wissen wir was da sein soll
102- // list hw
104+ executor_->add_node (cm_);
105+ // Now we have to wait for cm to process callback and initialize everything.
106+ // We have to wait here, otherwise controllers can not be initialized since
107+ // no hardware has been received.
108+ service_caller_node_ = std::make_shared<rclcpp::Node>(" service_caller_node" , ns_);
109+ executor_->add_node (service_caller_node_);
110+ auto client =
111+ service_caller_node_->create_client <controller_manager_msgs::srv::ListHardwareInterfaces>(
112+ " get_hw_interfaces" );
113+ auto request =
114+ std::make_shared<controller_manager_msgs::srv::ListHardwareInterfaces::Request>();
115+ EXPECT_TRUE (client->wait_for_service (std::chrono::milliseconds (500 )));
116+ auto future = client->async_send_request (request);
117+ EXPECT_EQ (
118+ executor_->spin_until_future_complete (future, std::chrono::milliseconds (1000 )),
119+ rclcpp::FutureReturnCode::SUCCESS);
120+ auto res = future.get ();
121+ auto command_interfaces = res->command_interfaces ;
122+ auto state_interfaces = res->state_interfaces ;
123+ // check for command-/stateinterfaces but spin_until_future_complete times out...
103124 }
104125 }
105126 }
@@ -168,6 +189,7 @@ class ControllerManagerFixture : public ::testing::Test
168189 const bool pass_urdf_as_parameter_;
169190 std::shared_ptr<rclcpp::Node> urdf_publisher_node_;
170191 rclcpp::Publisher<std_msgs::msg::String>::SharedPtr description_pub_;
192+ std::shared_ptr<rclcpp::Node> service_caller_node_;
171193};
172194
173195class TestControllerManagerSrvs
0 commit comments