Skip to content

Commit da7b09f

Browse files
author
Felix Exner (fexner)
authored
Move communication setup to on_configure instead of on_activate (#732)
* Move communication setup to on_configure instead of on_activate * Cleanup in on_cleanup instead on_deactivate * Use std::atomic_bool for rtde_comm_has_been_started_
1 parent 95dc22e commit da7b09f

File tree

2 files changed

+18
-8
lines changed

2 files changed

+18
-8
lines changed

ur_robot_driver/include/ur_robot_driver/hardware_interface.hpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -96,8 +96,9 @@ class URPositionHardwareInterface : public hardware_interface::SystemInterface
9696

9797
std::vector<hardware_interface::CommandInterface> export_command_interfaces() final;
9898

99+
hardware_interface::CallbackReturn on_configure(const rclcpp_lifecycle::State& previous_state) final;
99100
hardware_interface::CallbackReturn on_activate(const rclcpp_lifecycle::State& previous_state) final;
100-
hardware_interface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State& previous_state) final;
101+
hardware_interface::CallbackReturn on_cleanup(const rclcpp_lifecycle::State& previous_state) final;
101102

102103
hardware_interface::return_type read(const rclcpp::Time& time, const rclcpp::Duration& period) final;
103104
hardware_interface::return_type write(const rclcpp::Time& time, const rclcpp::Duration& period) final;
@@ -223,7 +224,7 @@ class URPositionHardwareInterface : public hardware_interface::SystemInterface
223224
std::unique_ptr<urcl::UrDriver> ur_driver_;
224225
std::shared_ptr<std::thread> async_thread_;
225226

226-
bool rtde_comm_has_been_started_ = false;
227+
std::atomic_bool rtde_comm_has_been_started_ = false;
227228
};
228229
} // namespace ur_robot_driver
229230

ur_robot_driver/src/hardware_interface.cpp

Lines changed: 15 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -59,7 +59,7 @@ URPositionHardwareInterface::~URPositionHardwareInterface()
5959
{
6060
// If the controller manager is shutdown via Ctrl + C the on_deactivate methods won't be called.
6161
// We therefore need to make sure to actually deactivate the communication
62-
on_deactivate(rclcpp_lifecycle::State());
62+
on_cleanup(rclcpp_lifecycle::State());
6363
}
6464

6565
hardware_interface::CallbackReturn
@@ -302,7 +302,7 @@ std::vector<hardware_interface::CommandInterface> URPositionHardwareInterface::e
302302
}
303303

304304
hardware_interface::CallbackReturn
305-
URPositionHardwareInterface::on_activate(const rclcpp_lifecycle::State& previous_state)
305+
URPositionHardwareInterface::on_configure(const rclcpp_lifecycle::State& previous_state)
306306
{
307307
RCLCPP_INFO(rclcpp::get_logger("URPositionHardwareInterface"), "Starting ...please wait...");
308308

@@ -463,13 +463,22 @@ URPositionHardwareInterface::on_activate(const rclcpp_lifecycle::State& previous
463463
}
464464

465465
hardware_interface::CallbackReturn
466-
URPositionHardwareInterface::on_deactivate(const rclcpp_lifecycle::State& previous_state)
466+
URPositionHardwareInterface::on_activate(const rclcpp_lifecycle::State& previous_state)
467+
{
468+
RCLCPP_INFO(rclcpp::get_logger("URPositionHardwareInterface"), "Activating HW interface");
469+
return hardware_interface::CallbackReturn::SUCCESS;
470+
}
471+
472+
hardware_interface::CallbackReturn
473+
URPositionHardwareInterface::on_cleanup(const rclcpp_lifecycle::State& previous_state)
467474
{
468475
RCLCPP_INFO(rclcpp::get_logger("URPositionHardwareInterface"), "Stopping ...please wait...");
469476

470-
async_thread_shutdown_ = true;
471-
async_thread_->join();
472-
async_thread_.reset();
477+
if (async_thread_) {
478+
async_thread_shutdown_ = true;
479+
async_thread_->join();
480+
async_thread_.reset();
481+
}
473482

474483
ur_driver_.reset();
475484

0 commit comments

Comments
 (0)