Skip to content

Commit 9def8aa

Browse files
Silence -Wdeprecated-declarations of legacy wrappers (#2585)
1 parent da0762c commit 9def8aa

File tree

2 files changed

+6
-0
lines changed

2 files changed

+6
-0
lines changed

hardware_interface/include/hardware_interface/hardware_component_interface.hpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -93,7 +93,10 @@ class HardwareComponentInterface : public rclcpp_lifecycle::node_interfaces::Lif
9393
const HardwareInfo & hardware_info, rclcpp::Logger logger,
9494
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
9595
{
96+
#pragma GCC diagnostic push
97+
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
9698
return this->init(hardware_info, logger, clock_interface->get_clock());
99+
#pragma GCC diagnostic pop
97100
}
98101

99102
/// Initialization of the hardware interface from data parsed from the robot's URDF and also the

hardware_interface/src/resource_manager.cpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1513,7 +1513,10 @@ bool ResourceManager::load_and_initialize_components(
15131513
resource_storage_->robot_description_ = params.robot_description;
15141514
resource_storage_->cm_update_rate_ = params.update_rate;
15151515
resource_storage_->executor_ = params.executor;
1516+
#pragma GCC diagnostic push
1517+
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
15161518
return load_and_initialize_components(params.robot_description, params.update_rate);
1519+
#pragma GCC diagnostic pop
15171520
}
15181521

15191522
void ResourceManager::import_joint_limiters(const std::string & urdf)

0 commit comments

Comments
 (0)