diff --git a/hardware_interface/include/hardware_interface/hardware_component.hpp b/hardware_interface/include/hardware_interface/hardware_component.hpp index 2d506f8bd1..c7b2cd2e98 100644 --- a/hardware_interface/include/hardware_interface/hardware_component.hpp +++ b/hardware_interface/include/hardware_interface/hardware_component.hpp @@ -51,19 +51,6 @@ class HardwareComponent final HardwareComponent & operator=(HardwareComponent && other) = delete; - [[deprecated( - "Replaced by const rclcpp_lifecycle::State & initialize(const " - "hardware_interface::HardwareComponentParams & params).")]] - const rclcpp_lifecycle::State & initialize( - const HardwareInfo & component_info, rclcpp::Logger logger, - rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface); - - [[deprecated( - "Replaced by const rclcpp_lifecycle::State & initialize(const " - "hardware_interface::HardwareComponentParams & params).")]] - const rclcpp_lifecycle::State & initialize( - const HardwareInfo & component_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock); - const rclcpp_lifecycle::State & initialize( const hardware_interface::HardwareComponentParams & params); diff --git a/hardware_interface/include/hardware_interface/hardware_component_interface.hpp b/hardware_interface/include/hardware_interface/hardware_component_interface.hpp index 097c4708bf..3bf4fb849a 100644 --- a/hardware_interface/include/hardware_interface/hardware_component_interface.hpp +++ b/hardware_interface/include/hardware_interface/hardware_component_interface.hpp @@ -93,27 +93,6 @@ class HardwareComponentInterface : public rclcpp_lifecycle::node_interfaces::Lif virtual ~HardwareComponentInterface() = default; - /// Initialization of the hardware interface from data parsed from the robot's URDF and also the - /// clock and logger interfaces. - /** - * \param[in] hardware_info structure with data from URDF. - * \param[in] clock pointer to the resource manager clock. - * \param[in] logger Logger for the hardware component. - * \returns CallbackReturn::SUCCESS if required data are provided and can be parsed. - * \returns CallbackReturn::ERROR if any error happens or data are missing. - */ - [[deprecated( - "Replaced by CallbackReturn init(const hardware_interface::HardwareComponentParams & " - "params). Initialization is handled by the Framework.")]] CallbackReturn - init(const HardwareInfo & hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock) - { - hardware_interface::HardwareComponentParams params; - params.hardware_info = hardware_info; - params.clock = clock; - params.logger = logger; - return init(params); - }; - /// Initialization of the hardware interface from data parsed from the robot's URDF and also the /// clock and logger interfaces. /** @@ -335,16 +314,18 @@ class HardwareComponentInterface : public rclcpp_lifecycle::node_interfaces::Lif /// Initialization of the hardware interface from data parsed from the robot's URDF. /** - * \param[in] hardware_info structure with data from URDF. + * \param[in] params A struct of type hardware_interface::HardwareComponentInterfaceParams + * containing all necessary parameters for initializing this specific hardware component, + * specifically its HardwareInfo, and a weak_ptr to the executor. + * \warning The parsed executor should not be used to call `cancel()` or use blocking callbacks + * such as `spin()`. * \returns CallbackReturn::SUCCESS if required data are provided and can be parsed. * \returns CallbackReturn::ERROR if any error happens or data are missing. */ - [[deprecated( - "Use on_init(const HardwareComponentInterfaceParams & params) " - "instead.")]] virtual CallbackReturn - on_init(const HardwareInfo & hardware_info) + virtual CallbackReturn on_init( + const hardware_interface::HardwareComponentInterfaceParams & params) { - info_ = hardware_info; + info_ = params.hardware_info; if (info_.type == "actuator") { parse_state_interface_descriptions(info_.joints, joint_state_interfaces_); @@ -366,26 +347,6 @@ class HardwareComponentInterface : public rclcpp_lifecycle::node_interfaces::Lif return CallbackReturn::SUCCESS; }; - /// Initialization of the hardware interface from data parsed from the robot's URDF. - /** - * \param[in] params A struct of type hardware_interface::HardwareComponentInterfaceParams - * containing all necessary parameters for initializing this specific hardware component, - * specifically its HardwareInfo, and a weak_ptr to the executor. - * \warning The parsed executor should not be used to call `cancel()` or use blocking callbacks - * such as `spin()`. - * \returns CallbackReturn::SUCCESS if required data are provided and can be parsed. - * \returns CallbackReturn::ERROR if any error happens or data are missing. - */ - virtual CallbackReturn on_init( - const hardware_interface::HardwareComponentInterfaceParams & params) - { - // This is done for backward compatibility with the old on_init method. -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - return on_init(params.hardware_info); -#pragma GCC diagnostic pop - }; - /// Exports all state interfaces for this hardware interface. /** * Old way of exporting the StateInterfaces. If a empty vector is returned then diff --git a/hardware_interface/include/hardware_interface/loaned_command_interface.hpp b/hardware_interface/include/hardware_interface/loaned_command_interface.hpp index 58c6facc26..08ae5d0d1f 100644 --- a/hardware_interface/include/hardware_interface/loaned_command_interface.hpp +++ b/hardware_interface/include/hardware_interface/loaned_command_interface.hpp @@ -114,22 +114,6 @@ class LoanedCommandInterface return true; } - [[deprecated( - "Use std::optional get_optional() instead to retrieve the value. This method will be " - "removed by the ROS 2 Lyrical Luth release.")]] - double get_value() const - { - std::optional opt_value = get_optional(); - if (opt_value.has_value()) - { - return opt_value.value(); - } - else - { - return std::numeric_limits::quiet_NaN(); - } - } - /** * @brief Get the value of the command interface. * @tparam T The type of the value to be retrieved. diff --git a/hardware_interface/include/hardware_interface/loaned_state_interface.hpp b/hardware_interface/include/hardware_interface/loaned_state_interface.hpp index 46b087ad75..ab2720af37 100644 --- a/hardware_interface/include/hardware_interface/loaned_state_interface.hpp +++ b/hardware_interface/include/hardware_interface/loaned_state_interface.hpp @@ -69,22 +69,6 @@ class LoanedStateInterface const std::string & get_prefix_name() const { return state_interface_.get_prefix_name(); } - [[deprecated( - "Use std::optional get_optional() instead to retrieve the value. This method will be " - "removed by the ROS 2 Lyrical Luth release.")]] - double get_value() const - { - std::optional opt_value = get_optional(); - if (opt_value.has_value()) - { - return opt_value.value(); - } - else - { - return std::numeric_limits::quiet_NaN(); - } - } - /** * @brief Get the value of the state interface. * @tparam T The type of the value to be retrieved. diff --git a/hardware_interface/src/hardware_component.cpp b/hardware_interface/src/hardware_component.cpp index 24a166ce05..9d7a937e36 100644 --- a/hardware_interface/src/hardware_component.cpp +++ b/hardware_interface/src/hardware_component.cpp @@ -46,27 +46,6 @@ HardwareComponent::HardwareComponent(HardwareComponent && other) noexcept last_write_cycle_time_ = rclcpp::Time(0, 0, RCL_CLOCK_UNINITIALIZED); } -const rclcpp_lifecycle::State & HardwareComponent::initialize( - const HardwareInfo & hardware_info, rclcpp::Logger logger, - rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface) -{ - // This is done for backward compatibility with the old initialize method. -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - return this->initialize(hardware_info, logger, clock_interface->get_clock()); -#pragma GCC diagnostic pop -} - -const rclcpp_lifecycle::State & HardwareComponent::initialize( - const HardwareInfo & hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock) -{ - hardware_interface::HardwareComponentParams params; - params.hardware_info = hardware_info; - params.logger = logger; - params.clock = clock; - return initialize(params); -} - const rclcpp_lifecycle::State & HardwareComponent::initialize( const hardware_interface::HardwareComponentParams & params) {