Skip to content

Commit 8c6e2e9

Browse files
Cleanup deprecations (#2589)
1 parent e8f8c01 commit 8c6e2e9

File tree

5 files changed

+8
-113
lines changed

5 files changed

+8
-113
lines changed

hardware_interface/include/hardware_interface/hardware_component.hpp

Lines changed: 0 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -51,19 +51,6 @@ class HardwareComponent final
5151

5252
HardwareComponent & operator=(HardwareComponent && other) = delete;
5353

54-
[[deprecated(
55-
"Replaced by const rclcpp_lifecycle::State & initialize(const "
56-
"hardware_interface::HardwareComponentParams & params).")]]
57-
const rclcpp_lifecycle::State & initialize(
58-
const HardwareInfo & component_info, rclcpp::Logger logger,
59-
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface);
60-
61-
[[deprecated(
62-
"Replaced by const rclcpp_lifecycle::State & initialize(const "
63-
"hardware_interface::HardwareComponentParams & params).")]]
64-
const rclcpp_lifecycle::State & initialize(
65-
const HardwareInfo & component_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock);
66-
6754
const rclcpp_lifecycle::State & initialize(
6855
const hardware_interface::HardwareComponentParams & params);
6956

hardware_interface/include/hardware_interface/hardware_component_interface.hpp

Lines changed: 8 additions & 47 deletions
Original file line numberDiff line numberDiff line change
@@ -93,27 +93,6 @@ class HardwareComponentInterface : public rclcpp_lifecycle::node_interfaces::Lif
9393

9494
virtual ~HardwareComponentInterface() = default;
9595

96-
/// Initialization of the hardware interface from data parsed from the robot's URDF and also the
97-
/// clock and logger interfaces.
98-
/**
99-
* \param[in] hardware_info structure with data from URDF.
100-
* \param[in] clock pointer to the resource manager clock.
101-
* \param[in] logger Logger for the hardware component.
102-
* \returns CallbackReturn::SUCCESS if required data are provided and can be parsed.
103-
* \returns CallbackReturn::ERROR if any error happens or data are missing.
104-
*/
105-
[[deprecated(
106-
"Replaced by CallbackReturn init(const hardware_interface::HardwareComponentParams & "
107-
"params). Initialization is handled by the Framework.")]] CallbackReturn
108-
init(const HardwareInfo & hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock)
109-
{
110-
hardware_interface::HardwareComponentParams params;
111-
params.hardware_info = hardware_info;
112-
params.clock = clock;
113-
params.logger = logger;
114-
return init(params);
115-
};
116-
11796
/// Initialization of the hardware interface from data parsed from the robot's URDF and also the
11897
/// clock and logger interfaces.
11998
/**
@@ -332,16 +311,18 @@ class HardwareComponentInterface : public rclcpp_lifecycle::node_interfaces::Lif
332311

333312
/// Initialization of the hardware interface from data parsed from the robot's URDF.
334313
/**
335-
* \param[in] hardware_info structure with data from URDF.
314+
* \param[in] params A struct of type hardware_interface::HardwareComponentInterfaceParams
315+
* containing all necessary parameters for initializing this specific hardware component,
316+
* specifically its HardwareInfo, and a weak_ptr to the executor.
317+
* \warning The parsed executor should not be used to call `cancel()` or use blocking callbacks
318+
* such as `spin()`.
336319
* \returns CallbackReturn::SUCCESS if required data are provided and can be parsed.
337320
* \returns CallbackReturn::ERROR if any error happens or data are missing.
338321
*/
339-
[[deprecated(
340-
"Use on_init(const HardwareComponentInterfaceParams & params) "
341-
"instead.")]] virtual CallbackReturn
342-
on_init(const HardwareInfo & hardware_info)
322+
virtual CallbackReturn on_init(
323+
const hardware_interface::HardwareComponentInterfaceParams & params)
343324
{
344-
info_ = hardware_info;
325+
info_ = params.hardware_info;
345326
if (info_.type == "actuator")
346327
{
347328
parse_state_interface_descriptions(info_.joints, joint_state_interfaces_);
@@ -363,26 +344,6 @@ class HardwareComponentInterface : public rclcpp_lifecycle::node_interfaces::Lif
363344
return CallbackReturn::SUCCESS;
364345
};
365346

366-
/// Initialization of the hardware interface from data parsed from the robot's URDF.
367-
/**
368-
* \param[in] params A struct of type hardware_interface::HardwareComponentInterfaceParams
369-
* containing all necessary parameters for initializing this specific hardware component,
370-
* specifically its HardwareInfo, and a weak_ptr to the executor.
371-
* \warning The parsed executor should not be used to call `cancel()` or use blocking callbacks
372-
* such as `spin()`.
373-
* \returns CallbackReturn::SUCCESS if required data are provided and can be parsed.
374-
* \returns CallbackReturn::ERROR if any error happens or data are missing.
375-
*/
376-
virtual CallbackReturn on_init(
377-
const hardware_interface::HardwareComponentInterfaceParams & params)
378-
{
379-
// This is done for backward compatibility with the old on_init method.
380-
#pragma GCC diagnostic push
381-
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
382-
return on_init(params.hardware_info);
383-
#pragma GCC diagnostic pop
384-
};
385-
386347
/// Exports all state interfaces for this hardware interface.
387348
/**
388349
* Old way of exporting the StateInterfaces. If a empty vector is returned then

hardware_interface/include/hardware_interface/loaned_command_interface.hpp

Lines changed: 0 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -114,22 +114,6 @@ class LoanedCommandInterface
114114
return true;
115115
}
116116

117-
[[deprecated(
118-
"Use std::optional<T> get_optional() instead to retrieve the value. This method will be "
119-
"removed by the ROS 2 Lyrical Luth release.")]]
120-
double get_value() const
121-
{
122-
std::optional<double> opt_value = get_optional();
123-
if (opt_value.has_value())
124-
{
125-
return opt_value.value();
126-
}
127-
else
128-
{
129-
return std::numeric_limits<double>::quiet_NaN();
130-
}
131-
}
132-
133117
/**
134118
* @brief Get the value of the command interface.
135119
* @tparam T The type of the value to be retrieved.

hardware_interface/include/hardware_interface/loaned_state_interface.hpp

Lines changed: 0 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -69,22 +69,6 @@ class LoanedStateInterface
6969

7070
const std::string & get_prefix_name() const { return state_interface_.get_prefix_name(); }
7171

72-
[[deprecated(
73-
"Use std::optional<T> get_optional() instead to retrieve the value. This method will be "
74-
"removed by the ROS 2 Lyrical Luth release.")]]
75-
double get_value() const
76-
{
77-
std::optional<double> opt_value = get_optional();
78-
if (opt_value.has_value())
79-
{
80-
return opt_value.value();
81-
}
82-
else
83-
{
84-
return std::numeric_limits<double>::quiet_NaN();
85-
}
86-
}
87-
8872
/**
8973
* @brief Get the value of the state interface.
9074
* @tparam T The type of the value to be retrieved.

hardware_interface/src/hardware_component.cpp

Lines changed: 0 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -46,27 +46,6 @@ HardwareComponent::HardwareComponent(HardwareComponent && other) noexcept
4646
last_write_cycle_time_ = rclcpp::Time(0, 0, RCL_CLOCK_UNINITIALIZED);
4747
}
4848

49-
const rclcpp_lifecycle::State & HardwareComponent::initialize(
50-
const HardwareInfo & hardware_info, rclcpp::Logger logger,
51-
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
52-
{
53-
// This is done for backward compatibility with the old initialize method.
54-
#pragma GCC diagnostic push
55-
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
56-
return this->initialize(hardware_info, logger, clock_interface->get_clock());
57-
#pragma GCC diagnostic pop
58-
}
59-
60-
const rclcpp_lifecycle::State & HardwareComponent::initialize(
61-
const HardwareInfo & hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock)
62-
{
63-
hardware_interface::HardwareComponentParams params;
64-
params.hardware_info = hardware_info;
65-
params.logger = logger;
66-
params.clock = clock;
67-
return initialize(params);
68-
}
69-
7049
const rclcpp_lifecycle::State & HardwareComponent::initialize(
7150
const hardware_interface::HardwareComponentParams & params)
7251
{

0 commit comments

Comments
 (0)