Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Move communication setup to on_configure instead of on_activate (backport #732) #936

Merged
merged 1 commit into from
Feb 26, 2024
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 @@ -96,8 +96,9 @@ class URPositionHardwareInterface : public hardware_interface::SystemInterface

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

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 Expand Up @@ -223,7 +224,7 @@ class URPositionHardwareInterface : public hardware_interface::SystemInterface
std::unique_ptr<urcl::UrDriver> ur_driver_;
std::shared_ptr<std::thread> async_thread_;

bool rtde_comm_has_been_started_ = false;
std::atomic_bool rtde_comm_has_been_started_ = false;
};
} // namespace ur_robot_driver

Expand Down
21 changes: 15 additions & 6 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 @@ -302,7 +302,7 @@ std::vector<hardware_interface::CommandInterface> URPositionHardwareInterface::e
}

hardware_interface::CallbackReturn
URPositionHardwareInterface::on_activate(const rclcpp_lifecycle::State& previous_state)
URPositionHardwareInterface::on_configure(const rclcpp_lifecycle::State& previous_state)
{
RCLCPP_INFO(rclcpp::get_logger("URPositionHardwareInterface"), "Starting ...please wait...");

Expand Down Expand Up @@ -463,13 +463,22 @@ URPositionHardwareInterface::on_activate(const rclcpp_lifecycle::State& previous
}

hardware_interface::CallbackReturn
URPositionHardwareInterface::on_deactivate(const rclcpp_lifecycle::State& previous_state)
URPositionHardwareInterface::on_activate(const rclcpp_lifecycle::State& previous_state)
{
RCLCPP_INFO(rclcpp::get_logger("URPositionHardwareInterface"), "Activating HW interface");
return hardware_interface::CallbackReturn::SUCCESS;
}

hardware_interface::CallbackReturn
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
Loading