File tree Expand file tree Collapse file tree 2 files changed +17
-3
lines changed Expand file tree Collapse file tree 2 files changed +17
-3
lines changed Original file line number Diff line number Diff line change @@ -124,6 +124,7 @@ class URPositionHardwareInterface : public hardware_interface::SystemInterface
124
124
hardware_interface::CallbackReturn on_configure (const rclcpp_lifecycle::State& previous_state) final ;
125
125
hardware_interface::CallbackReturn on_activate (const rclcpp_lifecycle::State& previous_state) final ;
126
126
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 ;
127
128
128
129
hardware_interface::return_type read (const rclcpp::Time& time, const rclcpp::Duration& period) final ;
129
130
hardware_interface::return_type write (const rclcpp::Time& time, const rclcpp::Duration& period) final ;
@@ -154,6 +155,9 @@ class URPositionHardwareInterface : public hardware_interface::SystemInterface
154
155
void readBitsetData (const std::unique_ptr<urcl::rtde_interface::DataPackage>& data_pkg, const std::string& var_name,
155
156
std::bitset<N>& data);
156
157
158
+ // stop function used by on_shutdown and on_cleanup
159
+ hardware_interface::CallbackReturn stop ();
160
+
157
161
void initAsyncIO ();
158
162
void checkAsyncIO ();
159
163
void updateNonDoubleValues ();
Original file line number Diff line number Diff line change @@ -58,9 +58,6 @@ namespace ur_robot_driver
58
58
59
59
URPositionHardwareInterface::~URPositionHardwareInterface ()
60
60
{
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 ());
64
61
}
65
62
66
63
hardware_interface::CallbackReturn
@@ -592,6 +589,19 @@ URPositionHardwareInterface::on_activate(const rclcpp_lifecycle::State& previous
592
589
593
590
hardware_interface::CallbackReturn
594
591
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 ()
595
605
{
596
606
RCLCPP_INFO (rclcpp::get_logger (" URPositionHardwareInterface" ), " Stopping ...please wait..." );
597
607
You can’t perform that action at this time.
0 commit comments