Skip to content

Commit 6987737

Browse files
committed
Merge remote-tracking branch 'origin/main' into issue_844
2 parents 769f6b5 + 36b5c3d commit 6987737

File tree

2 files changed

+17
-3
lines changed

2 files changed

+17
-3
lines changed

ur_robot_driver/include/ur_robot_driver/hardware_interface.hpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -124,6 +124,7 @@ class URPositionHardwareInterface : public hardware_interface::SystemInterface
124124
hardware_interface::CallbackReturn on_configure(const rclcpp_lifecycle::State& previous_state) final;
125125
hardware_interface::CallbackReturn on_activate(const rclcpp_lifecycle::State& previous_state) final;
126126
hardware_interface::CallbackReturn on_cleanup(const rclcpp_lifecycle::State& previous_state) final;
127+
hardware_interface::CallbackReturn on_shutdown(const rclcpp_lifecycle::State& previous_state) final;
127128

128129
hardware_interface::return_type read(const rclcpp::Time& time, const rclcpp::Duration& period) final;
129130
hardware_interface::return_type write(const rclcpp::Time& time, const rclcpp::Duration& period) final;
@@ -154,6 +155,9 @@ class URPositionHardwareInterface : public hardware_interface::SystemInterface
154155
void readBitsetData(const std::unique_ptr<urcl::rtde_interface::DataPackage>& data_pkg, const std::string& var_name,
155156
std::bitset<N>& data);
156157

158+
// stop function used by on_shutdown and on_cleanup
159+
hardware_interface::CallbackReturn stop();
160+
157161
void initAsyncIO();
158162
void checkAsyncIO();
159163
void updateNonDoubleValues();

ur_robot_driver/src/hardware_interface.cpp

Lines changed: 13 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -58,9 +58,6 @@ namespace ur_robot_driver
5858

5959
URPositionHardwareInterface::~URPositionHardwareInterface()
6060
{
61-
// If the controller manager is shutdown via Ctrl + C the on_deactivate methods won't be called.
62-
// We therefore need to make sure to actually deactivate the communication
63-
on_cleanup(rclcpp_lifecycle::State());
6461
}
6562

6663
hardware_interface::CallbackReturn
@@ -592,6 +589,19 @@ URPositionHardwareInterface::on_activate(const rclcpp_lifecycle::State& previous
592589

593590
hardware_interface::CallbackReturn
594591
URPositionHardwareInterface::on_cleanup(const rclcpp_lifecycle::State& previous_state)
592+
{
593+
RCLCPP_DEBUG(rclcpp::get_logger("URPositionHardwareInterface"), "on_cleanup");
594+
return stop();
595+
}
596+
597+
hardware_interface::CallbackReturn
598+
URPositionHardwareInterface::on_shutdown(const rclcpp_lifecycle::State& previous_state)
599+
{
600+
RCLCPP_DEBUG(rclcpp::get_logger("URPositionHardwareInterface"), "on_shutdown");
601+
return stop();
602+
}
603+
604+
hardware_interface::CallbackReturn URPositionHardwareInterface::stop()
595605
{
596606
RCLCPP_INFO(rclcpp::get_logger("URPositionHardwareInterface"), "Stopping ...please wait...");
597607

0 commit comments

Comments
 (0)