Skip to content

Commit cbb5b64

Browse files
authored
Supress deprecated RM API warnings in the tests (#2428)
1 parent 350cbdd commit cbb5b64

File tree

2 files changed

+19
-2
lines changed

2 files changed

+19
-2
lines changed

hardware_interface_testing/test/test_resource_manager.cpp

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -99,14 +99,26 @@ TEST_F(ResourceManagerTest, initialization_with_urdf)
9999
TEST_F(ResourceManagerTest, post_initialization_with_urdf)
100100
{
101101
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"
102105
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));
103111
}
104112

105113
void test_load_and_initialized_components_failure(const std::string & urdf)
106114
{
107115
rclcpp::Node node = rclcpp::Node("TestableResourceManager");
108116
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"
109120
ASSERT_FALSE(rm.load_and_initialize_components(urdf));
121+
#pragma GCC diagnostic pop
110122

111123
ASSERT_FALSE(rm.are_components_initialized());
112124

@@ -269,7 +281,11 @@ TEST_F(ResourceManagerTest, can_load_and_initialize_components_later)
269281
{
270282
TestableResourceManager rm(node_);
271283
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"
272287
rm.load_and_initialize_components(ros2_control_test_assets::minimal_robot_urdf);
288+
#pragma GCC diagnostic pop
273289
ASSERT_TRUE(rm.are_components_initialized());
274290
}
275291

hardware_interface_testing/test/test_resource_manager_prepare_perform_switch.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -430,7 +430,8 @@ TEST_F(
430430
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE);
431431

432432
// Now deactivate with write deactivate value
433-
claimed_actuator_velocity_command_->set_value(test_constants::WRITE_DEACTIVATE_VALUE);
433+
EXPECT_TRUE(
434+
claimed_actuator_velocity_command_->set_value(test_constants::WRITE_DEACTIVATE_VALUE));
434435
rm_->write(node_.now(), rclcpp::Duration(0, 1000000));
435436

436437
status_map = rm_->get_components_status();
@@ -460,7 +461,7 @@ TEST_F(
460461
<< "Start interfaces with inactive should result in no change";
461462

462463
// Now return ERROR with write fail value
463-
claimed_actuator_velocity_command_->set_value(test_constants::WRITE_FAIL_VALUE);
464+
EXPECT_TRUE(claimed_actuator_velocity_command_->set_value(test_constants::WRITE_FAIL_VALUE));
464465
rm_->write(node_.now(), rclcpp::Duration(0, 1000000));
465466

466467
status_map = rm_->get_components_status();

0 commit comments

Comments
 (0)