diff --git a/ur_robot_driver/include/ur_robot_driver/hardware_interface.hpp b/ur_robot_driver/include/ur_robot_driver/hardware_interface.hpp index 14bdd29ea..c9f23e4f5 100644 --- a/ur_robot_driver/include/ur_robot_driver/hardware_interface.hpp +++ b/ur_robot_driver/include/ur_robot_driver/hardware_interface.hpp @@ -124,6 +124,7 @@ class URPositionHardwareInterface : public hardware_interface::SystemInterface hardware_interface::CallbackReturn on_configure(const rclcpp_lifecycle::State& previous_state) final; hardware_interface::CallbackReturn on_activate(const rclcpp_lifecycle::State& previous_state) final; hardware_interface::CallbackReturn on_cleanup(const rclcpp_lifecycle::State& previous_state) final; + hardware_interface::CallbackReturn on_shutdown(const rclcpp_lifecycle::State& previous_state) final; hardware_interface::return_type read(const rclcpp::Time& time, const rclcpp::Duration& period) final; hardware_interface::return_type write(const rclcpp::Time& time, const rclcpp::Duration& period) final; @@ -154,6 +155,9 @@ class URPositionHardwareInterface : public hardware_interface::SystemInterface void readBitsetData(const std::unique_ptr& data_pkg, const std::string& var_name, std::bitset& data); + // stop function used by on_shutdown and on_cleanup + hardware_interface::CallbackReturn stop(); + void initAsyncIO(); void checkAsyncIO(); void updateNonDoubleValues(); diff --git a/ur_robot_driver/src/hardware_interface.cpp b/ur_robot_driver/src/hardware_interface.cpp index 216d7d462..83cb87b2e 100644 --- a/ur_robot_driver/src/hardware_interface.cpp +++ b/ur_robot_driver/src/hardware_interface.cpp @@ -58,9 +58,6 @@ namespace ur_robot_driver URPositionHardwareInterface::~URPositionHardwareInterface() { - // If the controller manager is shutdown via Ctrl + C the on_deactivate methods won't be called. - // We therefore need to make sure to actually deactivate the communication - on_cleanup(rclcpp_lifecycle::State()); } hardware_interface::CallbackReturn @@ -592,6 +589,19 @@ URPositionHardwareInterface::on_activate(const rclcpp_lifecycle::State& previous hardware_interface::CallbackReturn URPositionHardwareInterface::on_cleanup(const rclcpp_lifecycle::State& previous_state) +{ + RCLCPP_DEBUG(rclcpp::get_logger("URPositionHardwareInterface"), "on_cleanup"); + return stop(); +} + +hardware_interface::CallbackReturn +URPositionHardwareInterface::on_shutdown(const rclcpp_lifecycle::State& previous_state) +{ + RCLCPP_DEBUG(rclcpp::get_logger("URPositionHardwareInterface"), "on_shutdown"); + return stop(); +} + +hardware_interface::CallbackReturn URPositionHardwareInterface::stop() { RCLCPP_INFO(rclcpp::get_logger("URPositionHardwareInterface"), "Stopping ...please wait...");