1+ #include " test_controller_manager_with_resource_manager.hpp"
2+
3+ std::shared_ptr<rclcpp::Node> ControllerManagerTest::node_ = nullptr ;
4+ std::unique_ptr<hardware_interface::ResourceManager> ControllerManagerTest::test_resource_manager_ = nullptr ;
5+ std::shared_ptr<rclcpp::executors::SingleThreadedExecutor> ControllerManagerTest::executor_ = nullptr ;
6+
7+ using LifecycleCallbackReturn =
8+ rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
9+
10+ void ControllerManagerTest::SetUp ()
11+ {
12+ if (!rclcpp::ok ()) {
13+ rclcpp::init (0 , nullptr );
14+ }
15+
16+ node_ = std::make_shared<rclcpp::Node>(" controller_manager_test_node" );
17+ auto clock = node_->get_clock ();
18+ auto logger = node_->get_logger ();
19+
20+ test_resource_manager_ = std::make_unique<hardware_interface::ResourceManager>(clock, logger);
21+ executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
22+ }
23+
24+ void ControllerManagerTest::TearDown ()
25+ {
26+ node_.reset ();
27+ test_resource_manager_.reset ();
28+ executor_.reset ();
29+ if (rclcpp::ok ()) {
30+ rclcpp::shutdown ();
31+ }
32+ }
33+
34+ TEST_F (ControllerManagerTest, robot_description_callback_handles_urdf_without_hardware_plugin)
35+ {
36+ TestControllerManager cm (std::move (test_resource_manager_), executor_);
37+
38+ std_msgs::msg::String invalid_urdf_msg;
39+ invalid_urdf_msg.data = ros2_control_test_assets::invalid_urdf_without_hardware_plugin;
40+
41+ cm.robot_description_callback (invalid_urdf_msg);
42+
43+ EXPECT_FALSE (cm.is_resource_manager_initialized ());
44+
45+ EXPECT_FALSE (cm.get_robot_description_timer ()->is_canceled ());
46+
47+ }
48+
49+ TEST_F (ControllerManagerTest, robot_description_callback_handles_invalid_urdf)
50+ {
51+ TestControllerManager cm (std::move (test_resource_manager_), executor_);
52+
53+ std_msgs::msg::String invalid_urdf_msg;
54+ invalid_urdf_msg.data = R"( <robot malformed></robot>)" ;
55+
56+ cm.robot_description_callback (invalid_urdf_msg);
57+
58+ EXPECT_FALSE (cm.is_resource_manager_initialized ());
59+
60+ EXPECT_FALSE (cm.get_robot_description_timer ()->is_canceled ());
61+
62+ }
63+
64+ TEST_F (ControllerManagerTest, robot_description_callback_handles_empty_urdf)
65+ {
66+ TestControllerManager cm (std::move (test_resource_manager_), executor_);
67+
68+ std_msgs::msg::String invalid_urdf_msg;
69+ invalid_urdf_msg.data = " " ;
70+
71+ cm.robot_description_callback (invalid_urdf_msg);
72+
73+ EXPECT_FALSE (cm.is_resource_manager_initialized ());
74+
75+ EXPECT_FALSE (cm.get_robot_description_timer ()->is_canceled ());
76+ }
77+
78+ TEST_F (ControllerManagerTest, robot_description_callback_handles_wrong_plugins)
79+ {
80+ TestControllerManager cm (std::move (test_resource_manager_), executor_);
81+
82+ std_msgs::msg::String invalid_urdf_msg;
83+ invalid_urdf_msg.data = ros2_control_test_assets::invalid_urdf_with_wrong_plugin;
84+
85+ cm.robot_description_callback (invalid_urdf_msg);
86+
87+ EXPECT_FALSE (cm.is_resource_manager_initialized ());
88+
89+ EXPECT_FALSE (cm.get_robot_description_timer ()->is_canceled ());
90+ }
91+
92+ TEST_F (ControllerManagerTest, robot_description_callback_handles_no_geometry)
93+ {
94+ TestControllerManager cm (std::move (test_resource_manager_), executor_);
95+
96+ std_msgs::msg::String invalid_urdf_msg;
97+ invalid_urdf_msg.data = ros2_control_test_assets::invalid_urdf_no_geometry;
98+
99+ cm.robot_description_callback (invalid_urdf_msg);
100+
101+ EXPECT_FALSE (cm.is_resource_manager_initialized ());
102+
103+ EXPECT_FALSE (cm.get_robot_description_timer ()->is_canceled ());
104+ }
105+
106+ TEST_F (ControllerManagerTest, init_controller_manager_with_invalid_urdf)
107+ {
108+ const std::string invalid_urdf = ros2_control_test_assets::invalid_urdf_with_wrong_plugin;
109+
110+ TestControllerManager cm (executor_, invalid_urdf, false , " test_controller_manager" , " " , rclcpp::NodeOptions{});
111+
112+ EXPECT_FALSE (cm.is_resource_manager_initialized ());
113+
114+ EXPECT_FALSE (cm.get_robot_description_timer ()->is_canceled ());
115+ }
116+
117+ int main (int argc, char ** argv)
118+ {
119+ ::testing::InitGoogleTest (&argc, argv);
120+ int result = RUN_ALL_TESTS ();
121+ return result;
122+ }
0 commit comments