Skip to content

Commit

Permalink
Cleanup in on_cleanup instead on_deactivate
Browse files Browse the repository at this point in the history
  • Loading branch information
fmauch committed Nov 14, 2023
1 parent 86defa7 commit 0ccc16a
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,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_deactivate(const rclcpp_lifecycle::State& previous_state) final;
hardware_interface::CallbackReturn on_cleanup(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;
Expand Down
12 changes: 7 additions & 5 deletions ur_robot_driver/src/hardware_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ 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_deactivate(rclcpp_lifecycle::State());
on_cleanup(rclcpp_lifecycle::State());
}

hardware_interface::CallbackReturn
Expand Down Expand Up @@ -470,13 +470,15 @@ URPositionHardwareInterface::on_activate(const rclcpp_lifecycle::State& previous
}

hardware_interface::CallbackReturn
URPositionHardwareInterface::on_deactivate(const rclcpp_lifecycle::State& previous_state)
URPositionHardwareInterface::on_cleanup(const rclcpp_lifecycle::State& previous_state)
{
RCLCPP_INFO(rclcpp::get_logger("URPositionHardwareInterface"), "Stopping ...please wait...");

async_thread_shutdown_ = true;
async_thread_->join();
async_thread_.reset();
if (async_thread_) {
async_thread_shutdown_ = true;
async_thread_->join();
async_thread_.reset();
}

ur_driver_.reset();

Expand Down

0 comments on commit 0ccc16a

Please sign in to comment.