@@ -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
0 commit comments