@@ -99,14 +99,26 @@ TEST_F(ResourceManagerTest, initialization_with_urdf)
99
99
TEST_F (ResourceManagerTest, post_initialization_with_urdf)
100
100
{
101
101
TestableResourceManager rm (node_);
102
+ // TODO(saikishor) : remove after the cleanup of deprecated API
103
+ #pragma GCC diagnostic push
104
+ #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
102
105
ASSERT_NO_THROW (rm.load_and_initialize_components (ros2_control_test_assets::minimal_robot_urdf));
106
+ #pragma GCC diagnostic pop
107
+ hardware_interface::ResourceManagerParams rm_params;
108
+ rm_params.robot_description = ros2_control_test_assets::minimal_robot_urdf;
109
+ rm_params.update_rate = 100 ;
110
+ ASSERT_NO_THROW (rm.load_and_initialize_components (rm_params));
103
111
}
104
112
105
113
void test_load_and_initialized_components_failure (const std::string & urdf)
106
114
{
107
115
rclcpp::Node node = rclcpp::Node (" TestableResourceManager" );
108
116
TestableResourceManager rm (node);
117
+ // TODO(saikishor) : remove after the cleanup of deprecated API
118
+ #pragma GCC diagnostic push
119
+ #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
109
120
ASSERT_FALSE (rm.load_and_initialize_components (urdf));
121
+ #pragma GCC diagnostic pop
110
122
111
123
ASSERT_FALSE (rm.are_components_initialized ());
112
124
@@ -269,7 +281,11 @@ TEST_F(ResourceManagerTest, can_load_and_initialize_components_later)
269
281
{
270
282
TestableResourceManager rm (node_);
271
283
ASSERT_FALSE (rm.are_components_initialized ());
284
+ // TODO(saikishor) : remove after the cleanup of deprecated API
285
+ #pragma GCC diagnostic push
286
+ #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
272
287
rm.load_and_initialize_components (ros2_control_test_assets::minimal_robot_urdf);
288
+ #pragma GCC diagnostic pop
273
289
ASSERT_TRUE (rm.are_components_initialized ());
274
290
}
275
291
0 commit comments