Skip to content

Commit

Permalink
IPC Client/Service to match Subscription approach
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 May 26, 2022
1 parent fa5d140 commit b6245f2
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 8 deletions.
10 changes: 5 additions & 5 deletions rclcpp/include/rclcpp/client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -379,6 +379,9 @@ class ClientBase
uint64_t intra_process_client_id,
IntraProcessManagerWeakPtr weak_ipm);

std::shared_ptr<rclcpp::experimental::ClientIntraProcessBase> client_intra_process_;
std::atomic_uint ipc_sequence_number_{1};

rclcpp::node_interfaces::NodeGraphInterface::WeakPtr node_graph_;
std::shared_ptr<rcl_node_t> node_handle_;
std::shared_ptr<rclcpp::Context> context_;
Expand Down Expand Up @@ -898,6 +901,8 @@ class Client : public ClientBase
}

// Create a ClientIntraProcess which will be given to the intra-process manager.
using ClientIntraProcessT = rclcpp::experimental::ClientIntraProcess<ServiceT>;

client_intra_process_ = std::make_shared<ClientIntraProcessT>(
context_,
this->get_service_name(),
Expand All @@ -919,11 +924,6 @@ class Client : public ClientBase
CallbackInfoVariant>>
pending_requests_;
std::mutex pending_requests_mutex_;

private:
using ClientIntraProcessT = rclcpp::experimental::ClientIntraProcess<ServiceT>;
std::shared_ptr<ClientIntraProcessT> client_intra_process_;
std::atomic_uint ipc_sequence_number_{1};
};

} // namespace rclcpp
Expand Down
7 changes: 4 additions & 3 deletions rclcpp/include/rclcpp/service.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -289,6 +289,8 @@ class ServiceBase
uint64_t intra_process_service_id,
IntraProcessManagerWeakPtr weak_ipm);

std::shared_ptr<rclcpp::experimental::ServiceIntraProcessBase> service_intra_process_;

std::shared_ptr<rcl_node_t> node_handle_;
std::shared_ptr<rclcpp::Context> context_;

Expand Down Expand Up @@ -552,6 +554,8 @@ class Service
}

// Create a ServiceIntraProcess which will be given to the intra-process manager.
using ServiceIntraProcessT = rclcpp::experimental::ServiceIntraProcess<ServiceT>;

service_intra_process_ = std::make_shared<ServiceIntraProcessT>(
any_callback_,
context_,
Expand All @@ -568,9 +572,6 @@ class Service
RCLCPP_DISABLE_COPY(Service)

AnyServiceCallback<ServiceT> any_callback_;

using ServiceIntraProcessT = rclcpp::experimental::ServiceIntraProcess<ServiceT>;
std::shared_ptr<ServiceIntraProcessT> service_intra_process_;
};

} // namespace rclcpp
Expand Down

0 comments on commit b6245f2

Please sign in to comment.