File tree Expand file tree Collapse file tree 3 files changed +31
-3
lines changed Expand file tree Collapse file tree 3 files changed +31
-3
lines changed Original file line number Diff line number Diff line change @@ -534,6 +534,18 @@ class Client : public ClientBase
534534
535535 virtual ~Client ()
536536 {
537+ if (!use_intra_process_) {
538+ return ;
539+ }
540+ auto ipm = weak_ipm_.lock ();
541+ if (!ipm) {
542+ // TODO(ivanpauno): should this raise an error?
543+ RCLCPP_WARN (
544+ rclcpp::get_logger (" rclcpp" ),
545+ " Intra process manager died before than a client." );
546+ return ;
547+ }
548+ ipm->remove_client (intra_process_client_id_);
537549 }
538550
539551 // / Take the next response for this client.
Original file line number Diff line number Diff line change @@ -304,9 +304,13 @@ class IntraProcessManager
304304
305305 auto service_it = services_.find (service_id);
306306 if (service_it == services_.end ()) {
307- throw std::runtime_error (
308- " There are no services to receive the intra-process request. "
309- " Do Inter process." );
307+ auto cli = get_client_intra_process (intra_process_client_id);
308+ auto warning_msg =
309+ " Intra-process service gone out of scope. "
310+ " Do inter-process requests.\n "
311+ " Client topic name: " + std::string (cli->get_service_name ());
312+ RCLCPP_WARN (rclcpp::get_logger (" rclcpp" ), warning_msg.c_str ());
313+ return ;
310314 }
311315 auto service_intra_process_base = service_it->second .lock ();
312316 if (service_intra_process_base) {
Original file line number Diff line number Diff line change @@ -481,6 +481,18 @@ class Service
481481
482482 virtual ~Service ()
483483 {
484+ if (!use_intra_process_) {
485+ return ;
486+ }
487+ auto ipm = weak_ipm_.lock ();
488+ if (!ipm) {
489+ // TODO(ivanpauno): should this raise an error?
490+ RCLCPP_WARN (
491+ rclcpp::get_logger (" rclcpp" ),
492+ " Intra process manager died before than a service." );
493+ return ;
494+ }
495+ ipm->remove_service (intra_process_service_id_);
484496 }
485497
486498 // / Take the next request from the service.
You can’t perform that action at this time.
0 commit comments