Skip to content

Commit

Permalink
Fixes from review.
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Lalancette <clalancette@gmail.com>
  • Loading branch information
clalancette committed Feb 26, 2023
1 parent d46e57e commit 1279cf8
Show file tree
Hide file tree
Showing 3 changed files with 15 additions and 19 deletions.
12 changes: 5 additions & 7 deletions rclcpp/include/rclcpp/client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -470,15 +470,13 @@ class Client : public ClientBase
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph,
const std::string & service_name,
rcl_client_options_t & client_options)
: ClientBase(node_base, node_graph)
: ClientBase(node_base, node_graph),
srv_type_support_handle_(rosidl_typesupport_cpp::get_service_type_support_handle<ServiceT>())
{
using rosidl_typesupport_cpp::get_service_type_support_handle;
service_type_support_handle_ =
get_service_type_support_handle<ServiceT>();
rcl_ret_t ret = rcl_client_init(
this->get_client_handle().get(),
this->get_rcl_node_handle(),
service_type_support_handle_,
srv_type_support_handle_,
service_name.c_str(),
&client_options);
if (ret != RCL_RET_OK) {
Expand Down Expand Up @@ -802,7 +800,7 @@ class Client : public ClientBase
client_handle_.get(),
node_handle_.get(),
clock->get_clock_handle(),
service_type_support_handle_,
srv_type_support_handle_,
pub_opts,
introspection_state);

Expand Down Expand Up @@ -863,7 +861,7 @@ class Client : public ClientBase
std::mutex pending_requests_mutex_;

private:
const rosidl_service_type_support_t * service_type_support_handle_;
const rosidl_service_type_support_t * srv_type_support_handle_;
};

} // namespace rclcpp
Expand Down
20 changes: 9 additions & 11 deletions rclcpp/include/rclcpp/service.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -310,11 +310,9 @@ class Service
const std::string & service_name,
AnyServiceCallback<ServiceT> any_callback,
rcl_service_options_t & service_options)
: ServiceBase(node_handle), any_callback_(any_callback)
: ServiceBase(node_handle), any_callback_(any_callback),
srv_type_support_handle_(rosidl_typesupport_cpp::get_service_type_support_handle<ServiceT>())
{
using rosidl_typesupport_cpp::get_service_type_support_handle;
service_type_support_handle_ = get_service_type_support_handle<ServiceT>();

// rcl does the static memory allocation here
service_handle_ = std::shared_ptr<rcl_service_t>(
new rcl_service_t, [handle = node_handle_, service_name](rcl_service_t * service)
Expand All @@ -333,7 +331,7 @@ class Service
rcl_ret_t ret = rcl_service_init(
service_handle_.get(),
node_handle.get(),
service_type_support_handle_,
srv_type_support_handle_,
service_name.c_str(),
&service_options);
if (ret != RCL_RET_OK) {
Expand Down Expand Up @@ -373,8 +371,8 @@ class Service
std::shared_ptr<rcl_node_t> node_handle,
std::shared_ptr<rcl_service_t> service_handle,
AnyServiceCallback<ServiceT> any_callback)
: ServiceBase(node_handle),
any_callback_(any_callback)
: ServiceBase(node_handle), any_callback_(any_callback),
srv_type_support_handle_(rosidl_typesupport_cpp::get_service_type_support_handle<ServiceT>())
{
// check if service handle was initialized
if (!rcl_service_is_valid(service_handle.get())) {
Expand Down Expand Up @@ -408,8 +406,8 @@ class Service
std::shared_ptr<rcl_node_t> node_handle,
rcl_service_t * service_handle,
AnyServiceCallback<ServiceT> any_callback)
: ServiceBase(node_handle),
any_callback_(any_callback)
: ServiceBase(node_handle), any_callback_(any_callback),
srv_type_support_handle_(rosidl_typesupport_cpp::get_service_type_support_handle<ServiceT>())
{
// check if service handle was initialized
if (!rcl_service_is_valid(service_handle)) {
Expand Down Expand Up @@ -507,7 +505,7 @@ class Service
service_handle_.get(),
node_handle_.get(),
clock->get_clock_handle(),
service_type_support_handle_,
srv_type_support_handle_,
pub_opts,
introspection_state);

Expand All @@ -521,7 +519,7 @@ class Service

AnyServiceCallback<ServiceT> any_callback_;

const rosidl_service_type_support_t * service_type_support_handle_;
const rosidl_service_type_support_t * srv_type_support_handle_;
};

} // namespace rclcpp
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/test/rclcpp/test_service_introspection.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2017 Open Source Robotics Foundation, Inc.
// Copyright 2022 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down

0 comments on commit 1279cf8

Please sign in to comment.