Skip to content

Commit

Permalink
Clear intra-process manager from destroyed cli/srv
Browse files Browse the repository at this point in the history
Signed-off-by: Mauro Passerino <mpasserino@irobot.com>
  • Loading branch information
Mauro Passerino committed Oct 3, 2022
1 parent 0a98fda commit b995963
Show file tree
Hide file tree
Showing 3 changed files with 31 additions and 3 deletions.
12 changes: 12 additions & 0 deletions rclcpp/include/rclcpp/client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -534,6 +534,18 @@ class Client : public ClientBase

virtual ~Client()
{
if (!use_intra_process_) {
return;
}
auto ipm = weak_ipm_.lock();
if (!ipm) {
// TODO(ivanpauno): should this raise an error?
RCLCPP_WARN(
rclcpp::get_logger("rclcpp"),
"Intra process manager died before than a client.");
return;
}
ipm->remove_client(intra_process_client_id_);
}

/// Take the next response for this client.
Expand Down
10 changes: 7 additions & 3 deletions rclcpp/include/rclcpp/experimental/intra_process_manager.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -304,9 +304,13 @@ class IntraProcessManager

auto service_it = services_.find(service_id);
if (service_it == services_.end()) {
throw std::runtime_error(
"There are no services to receive the intra-process request. "
"Do Inter process.");
auto cli = get_client_intra_process(intra_process_client_id);
auto warning_msg =
"Intra-process service gone out of scope. "
"Do inter-process requests.\n"
"Client topic name: " + std::string(cli->get_service_name());
RCLCPP_WARN(rclcpp::get_logger("rclcpp"), warning_msg.c_str());
return;
}
auto service_intra_process_base = service_it->second.lock();
if (service_intra_process_base) {
Expand Down
12 changes: 12 additions & 0 deletions rclcpp/include/rclcpp/service.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -481,6 +481,18 @@ class Service

virtual ~Service()
{
if (!use_intra_process_) {
return;
}
auto ipm = weak_ipm_.lock();
if (!ipm) {
// TODO(ivanpauno): should this raise an error?
RCLCPP_WARN(
rclcpp::get_logger("rclcpp"),
"Intra process manager died before than a service.");
return;
}
ipm->remove_service(intra_process_service_id_);
}

/// Take the next request from the service.
Expand Down

0 comments on commit b995963

Please sign in to comment.