Merge pull request #147 from ros2/perfect-forwarding
Pass callbacks as universal references
This commit is contained in:
commit
f4a094afc8
4 changed files with 20 additions and 19 deletions
|
@ -125,7 +125,7 @@ public:
|
||||||
|
|
||||||
SharedFuture async_send_request(
|
SharedFuture async_send_request(
|
||||||
typename ServiceT::Request::SharedPtr request,
|
typename ServiceT::Request::SharedPtr request,
|
||||||
CallbackType cb)
|
CallbackType && cb)
|
||||||
{
|
{
|
||||||
int64_t sequence_number;
|
int64_t sequence_number;
|
||||||
if (RMW_RET_OK != rmw_send_request(get_client_handle(), request.get(), &sequence_number)) {
|
if (RMW_RET_OK != rmw_send_request(get_client_handle(), request.get(), &sequence_number)) {
|
||||||
|
@ -137,7 +137,8 @@ public:
|
||||||
|
|
||||||
SharedPromise call_promise = std::make_shared<Promise>();
|
SharedPromise call_promise = std::make_shared<Promise>();
|
||||||
SharedFuture f(call_promise->get_future());
|
SharedFuture f(call_promise->get_future());
|
||||||
pending_requests_[sequence_number] = std::make_tuple(call_promise, cb, f);
|
pending_requests_[sequence_number] =
|
||||||
|
std::make_tuple(call_promise, std::forward<CallbackType>(cb), f);
|
||||||
return f;
|
return f;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -131,7 +131,7 @@ public:
|
||||||
typename rclcpp::subscription::Subscription<MessageT, Alloc>::SharedPtr
|
typename rclcpp::subscription::Subscription<MessageT, Alloc>::SharedPtr
|
||||||
create_subscription(
|
create_subscription(
|
||||||
const std::string & topic_name,
|
const std::string & topic_name,
|
||||||
CallbackT callback,
|
CallbackT && callback,
|
||||||
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default,
|
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default,
|
||||||
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr,
|
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr,
|
||||||
bool ignore_local_publications = false,
|
bool ignore_local_publications = false,
|
||||||
|
@ -158,7 +158,7 @@ public:
|
||||||
create_subscription(
|
create_subscription(
|
||||||
const std::string & topic_name,
|
const std::string & topic_name,
|
||||||
size_t qos_history_depth,
|
size_t qos_history_depth,
|
||||||
CallbackT callback,
|
CallbackT && callback,
|
||||||
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr,
|
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr,
|
||||||
bool ignore_local_publications = false,
|
bool ignore_local_publications = false,
|
||||||
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr
|
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr
|
||||||
|
@ -203,11 +203,11 @@ public:
|
||||||
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
|
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
|
||||||
|
|
||||||
/* Create and return a Service. */
|
/* Create and return a Service. */
|
||||||
template<typename ServiceT, typename FunctorT>
|
template<typename ServiceT, typename CallbackT>
|
||||||
typename rclcpp::service::Service<ServiceT>::SharedPtr
|
typename rclcpp::service::Service<ServiceT>::SharedPtr
|
||||||
create_service(
|
create_service(
|
||||||
const std::string & service_name,
|
const std::string & service_name,
|
||||||
FunctorT callback,
|
CallbackT && callback,
|
||||||
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
|
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
|
||||||
|
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
|
|
|
@ -141,7 +141,7 @@ template<typename MessageT, typename CallbackT, typename Alloc>
|
||||||
typename rclcpp::subscription::Subscription<MessageT, Alloc>::SharedPtr
|
typename rclcpp::subscription::Subscription<MessageT, Alloc>::SharedPtr
|
||||||
Node::create_subscription(
|
Node::create_subscription(
|
||||||
const std::string & topic_name,
|
const std::string & topic_name,
|
||||||
CallbackT callback,
|
CallbackT && callback,
|
||||||
const rmw_qos_profile_t & qos_profile,
|
const rmw_qos_profile_t & qos_profile,
|
||||||
rclcpp::callback_group::CallbackGroup::SharedPtr group,
|
rclcpp::callback_group::CallbackGroup::SharedPtr group,
|
||||||
bool ignore_local_publications,
|
bool ignore_local_publications,
|
||||||
|
@ -155,7 +155,7 @@ Node::create_subscription(
|
||||||
|
|
||||||
rclcpp::subscription::AnySubscriptionCallback<MessageT,
|
rclcpp::subscription::AnySubscriptionCallback<MessageT,
|
||||||
Alloc> any_subscription_callback(allocator);
|
Alloc> any_subscription_callback(allocator);
|
||||||
any_subscription_callback.set(callback);
|
any_subscription_callback.set(std::forward<CallbackT>(callback));
|
||||||
|
|
||||||
using rosidl_generator_cpp::get_message_type_support_handle;
|
using rosidl_generator_cpp::get_message_type_support_handle;
|
||||||
|
|
||||||
|
@ -251,7 +251,7 @@ typename rclcpp::subscription::Subscription<MessageT, Alloc>::SharedPtr
|
||||||
Node::create_subscription(
|
Node::create_subscription(
|
||||||
const std::string & topic_name,
|
const std::string & topic_name,
|
||||||
size_t qos_history_depth,
|
size_t qos_history_depth,
|
||||||
CallbackT callback,
|
CallbackT && callback,
|
||||||
rclcpp::callback_group::CallbackGroup::SharedPtr group,
|
rclcpp::callback_group::CallbackGroup::SharedPtr group,
|
||||||
bool ignore_local_publications,
|
bool ignore_local_publications,
|
||||||
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr
|
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr
|
||||||
|
@ -262,7 +262,7 @@ Node::create_subscription(
|
||||||
qos.depth = qos_history_depth;
|
qos.depth = qos_history_depth;
|
||||||
return this->create_subscription<MessageT, CallbackT, Alloc>(
|
return this->create_subscription<MessageT, CallbackT, Alloc>(
|
||||||
topic_name,
|
topic_name,
|
||||||
callback,
|
std::forward<CallbackT>(callback),
|
||||||
qos,
|
qos,
|
||||||
group,
|
group,
|
||||||
ignore_local_publications,
|
ignore_local_publications,
|
||||||
|
@ -313,11 +313,11 @@ Node::create_client(
|
||||||
return cli;
|
return cli;
|
||||||
}
|
}
|
||||||
|
|
||||||
template<typename ServiceT, typename FunctorT>
|
template<typename ServiceT, typename CallbackT>
|
||||||
typename rclcpp::service::Service<ServiceT>::SharedPtr
|
typename rclcpp::service::Service<ServiceT>::SharedPtr
|
||||||
Node::create_service(
|
Node::create_service(
|
||||||
const std::string & service_name,
|
const std::string & service_name,
|
||||||
FunctorT callback,
|
CallbackT && callback,
|
||||||
rclcpp::callback_group::CallbackGroup::SharedPtr group)
|
rclcpp::callback_group::CallbackGroup::SharedPtr group)
|
||||||
{
|
{
|
||||||
using rosidl_generator_cpp::get_service_type_support_handle;
|
using rosidl_generator_cpp::get_service_type_support_handle;
|
||||||
|
@ -325,7 +325,7 @@ Node::create_service(
|
||||||
get_service_type_support_handle<ServiceT>();
|
get_service_type_support_handle<ServiceT>();
|
||||||
|
|
||||||
rclcpp::service::AnyServiceCallback<ServiceT> any_service_callback;
|
rclcpp::service::AnyServiceCallback<ServiceT> any_service_callback;
|
||||||
any_service_callback.set(callback);
|
any_service_callback.set(std::forward<CallbackT>(callback));
|
||||||
|
|
||||||
rmw_service_t * service_handle = rmw_create_service(
|
rmw_service_t * service_handle = rmw_create_service(
|
||||||
node_handle_.get(), service_type_support_handle, service_name.c_str());
|
node_handle_.get(), service_type_support_handle, service_name.c_str());
|
||||||
|
|
|
@ -91,12 +91,12 @@ public:
|
||||||
void(std::shared_future<rcl_interfaces::msg::ListParametersResult>)
|
void(std::shared_future<rcl_interfaces::msg::ListParametersResult>)
|
||||||
> callback = nullptr);
|
> callback = nullptr);
|
||||||
|
|
||||||
template<typename FunctorT>
|
template<typename CallbackT>
|
||||||
typename rclcpp::subscription::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr
|
typename rclcpp::subscription::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr
|
||||||
on_parameter_event(FunctorT callback)
|
on_parameter_event(CallbackT && callback)
|
||||||
{
|
{
|
||||||
return node_->create_subscription<rcl_interfaces::msg::ParameterEvent>(
|
return node_->create_subscription<rcl_interfaces::msg::ParameterEvent>(
|
||||||
"parameter_events", callback, rmw_qos_profile_parameter_events);
|
"parameter_events", std::forward<CallbackT>(callback), rmw_qos_profile_parameter_events);
|
||||||
}
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
@ -149,11 +149,11 @@ public:
|
||||||
const std::vector<std::string> & parameter_prefixes,
|
const std::vector<std::string> & parameter_prefixes,
|
||||||
uint64_t depth);
|
uint64_t depth);
|
||||||
|
|
||||||
template<typename FunctorT>
|
template<typename CallbackT>
|
||||||
typename rclcpp::subscription::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr
|
typename rclcpp::subscription::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr
|
||||||
on_parameter_event(FunctorT callback)
|
on_parameter_event(CallbackT && callback)
|
||||||
{
|
{
|
||||||
return async_parameters_client_->on_parameter_event(callback);
|
return async_parameters_client_->on_parameter_event(std::forward<CallbackT>(callback));
|
||||||
}
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue