Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -154,6 +155,9 @@ class URPositionHardwareInterface : public hardware_interface::SystemInterface
void readBitsetData(const std::unique_ptr<urcl::rtde_interface::DataPackage>& data_pkg, const std::string& var_name,
std::bitset<N>& data);

// stop function used by on_shutdown and on_cleanup
hardware_interface::CallbackReturn stop();

void initAsyncIO();
void checkAsyncIO();
void updateNonDoubleValues();
Expand Down
16 changes: 13 additions & 3 deletions ur_robot_driver/src/hardware_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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...");

Expand Down