ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

std::bind in function callback for subscription or service on ros 2

asked 2019-04-02 03:11:29 -0500

Amel--E gravatar image

updated 2019-04-03 03:25:14 -0500

gvdhoorn gravatar image

Edit:

Ok so I tried adding this request_header variable and add a std::placeholders but it's not working either. This time I get the same kind of error :

In file included from /opt/ros/crystal/include/rclcpp/node_impl.hpp:42:0,
                 from /opt/ros/crystal/include/rclcpp/node.hpp:524,
                 from /opt/ros/crystal/include/rclcpp/executors/single_threaded_executor.hpp:28,
                 from /opt/ros/crystal/include/rclcpp/executors.hpp:22,
                 from /opt/ros/crystal/include/rclcpp/rclcpp.hpp:144,
                 from /home/innovation/ros2_ws/src/balyo_utils_ros/src/ping.cpp:1: /opt/ros/crystal/include/rclcpp/create_service.hpp: In instantiation of ‘typename rclcpp::Service<ServiceT>::SharedPtr rclcpp::create_service(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface>, const string&, CallbackT&&, const rmw_qos_profile_t&, rclcpp::callback_group::CallbackGroup::SharedPtr) [with ServiceT = balyo_msgs::srv::GetBool; CallbackT = std::_Bind<bool (Ping::*(Ping*, std::_Placeholder<1>, std::_Placeholder<2>, std::_Placeholder<3>))(std::shared_ptr<rmw_request_id_t>, balyo_msgs::srv::GetBool_Request_<std::allocator<void>
>&, balyo_msgs::srv::GetBool_Response_<std::allocator<void>
>&)>; typename rclcpp::Service<ServiceT>::SharedPtr = std::shared_ptr<rclcpp::Service<balyo_msgs::srv::GetBool>
>; std::__cxx11::string = std::__cxx11::basic_string<char>; rmw_qos_profile_t = rmw_qos_profile_t; rclcpp::callback_group::CallbackGroup::SharedPtr
= std::shared_ptr<rclcpp::callback_group::CallbackGroup>]’: /opt/ros/crystal/include/rclcpp/node_impl.hpp:201:53: required from ‘typename rclcpp::Service<ServiceT>::SharedPtr rclcpp::Node::create_service(const string&, CallbackT&&, const rmw_qos_profile_t&, rclcpp::callback_group::CallbackGroup::SharedPtr) [with ServiceT = balyo_msgs::srv::GetBool; CallbackT = std::_Bind<bool (Ping::*(Ping*, std::_Placeholder<1>, std::_Placeholder<2>, std::_Placeholder<3>))(std::shared_ptr<rmw_request_id_t>, balyo_msgs::srv::GetBool_Request_<std::allocator<void>
>&, balyo_msgs::srv::GetBool_Response_<std::allocator<void>
>&)>; typename rclcpp::Service<ServiceT>::SharedPtr = std::shared_ptr<rclcpp::Service<balyo_msgs::srv::GetBool>
>; std::__cxx11::string = std::__cxx11::basic_string<char>; rmw_qos_profile_t = rmw_qos_profile_t; rclcpp::callback_group::CallbackGroup::SharedPtr
= std::shared_ptr<rclcpp::callback_group::CallbackGroup>]’ /home/innovation/ros2_ws/src/balyo_utils_ros/src/ping.cpp:97:182: required from here /opt/ros/crystal/include/rclcpp/create_service.hpp:43:3: error: no matching function for call to ‘rclcpp::AnyServiceCallback<balyo_msgs::srv::GetBool>::set(std::_Bind<bool (Ping::*(Ping*, std::_Placeholder<1>, std::_Placeholder<2>, std::_Placeholder<3>))(std::shared_ptr<rmw_request_id_t>, balyo_msgs::srv::GetBool_Request_<std::allocator<void>
>&, balyo_msgs::srv::GetBool_Response_<std::allocator<void>
>&)>)’    any_service_callback.set(std::forward<CallbackT>(callback)); ^~~~~~~~~~~~~~~~~~~~ In file included from /opt/ros/crystal/include/rclcpp/service.hpp:27:0,
                 from /opt/ros/crystal/include/rclcpp/callback_group.hpp:24,
                 from /opt/ros/crystal/include/rclcpp/any_executable.hpp:20,
                 from /opt/ros/crystal/include/rclcpp/memory_strategy.hpp:24,
                 from /opt/ros/crystal/include/rclcpp/memory_strategies.hpp:18,
                 from /opt/ros/crystal/include/rclcpp/executor.hpp:32,
                 from /opt/ros/crystal/include/rclcpp/executors/multi_threaded_executor.hpp:24,
                 from /opt/ros/crystal/include/rclcpp/executors.hpp:21,
                 from /opt/ros/crystal/include/rclcpp/rclcpp.hpp:144,
                 from /home/innovation/ros2_ws/src/balyo_utils_ros/src/ping.cpp:1: /opt/ros/crystal/include/rclcpp/any_service_callback.hpp:65:8: note: candidate: template<class CallbackT, typename std::enable_if<rclcpp::function_traits::same_arguments<CallbackT, std::function<void(std::shared_ptr<balyo_msgs::srv::GetBool_Request_<std::allocator<void>
> >, std::shared_ptr<balyo_msgs::srv::GetBool_Response_<std::allocator<void>
> >)> >::value, void>::type* <anonymous> > void rclcpp::AnyServiceCallback<ServiceT>::set(CallbackT) [with ...
(more)
edit retag flag offensive close merge delete

Comments

@Amel--E: please don't post answers to provide more information. Only post answers to actually answer your own question. For everything else: short -> comments. More code or error messages: edit your original post (add a section).

gvdhoorn gravatar image gvdhoorn  ( 2019-04-03 03:26:31 -0500 )edit

2 Answers

Sort by » oldest newest most voted
0

answered 2021-01-17 19:18:51 -0500

M@t gravatar image

updated 2021-01-17 19:32:58 -0500

What I believe you are trying to do is create a ROS2 subscriber or service callback using std::bind on a class function. I think I've figured this out but barely understand it myself, so anyone else please correct me if any of the following is wrong.

Following the ROS2 tutorials:

You will see that using std::bind is the intended way of giving the create_service or create_subscription call a function to run. But what the tutorials don't clearly explain, is what parameters each callback requires, and how that affects your std::bind call.

Subscriber Callbacks

A subscriber takes in (typically) only one input - the topic message being passed to the subscriber. So your callback must have only one parameter, and your std::bind call must have one placeholder:

#include "std_msgs/msg/u_int64.hpp"

class MyNode : rclcpp::Node
{
    void SubscriberCallback(const std_msgs::msg::UInt64::SharedPtr msg)
    {
        /* Do something cool with your UInt64 msg */
    } 

    void CreateSubscriber()
    {
        MySubscriber = this->create_subscription<std_msgs::msg::UInt64>(
            "my_uint64_topic_name",
            10,
            std::bind(
                &MyNode::SubscriberCallback, 
                this, 
                std::placeholders::_1               // Corresponds to the 'msg' input
            )
        );
    }

    // Create your subscriber pointer as a class member so that it persists 
    // between class functions
    rclcpp::Subscription<std_msgs::msg::UInt64>::SharedPtr MySubscriber;
};

Service Callbacks

Service callbacks are slightly different in that they appear to take a minimum of two parameters, possibly three. Because the service/client model is built on the idea of issuing a request and then receiving a response, your callback needs a request and a response parameter. This means that your std::bind call now needs two placeholder parameters. E.g.

#include "std_srvs/srv/empty.hpp"

class MyNode : rclcpp::Node
{
    void ServiceCallback(
        const std::shared_ptr<std_srvs::srv::Empty::Request> request,
        std::shared_ptr<std_srvs::srv::Empty::Response>      response)
    {
        /* Do something cool with your request, and fill in the response */
    } 

    void MyService()
    {
        MySubscriber = this->create_service<std_msgs::msg::UInt64>(
            "my_empty_service_name",
            10,
            std::bind(
                &MyNode::SubscriberCallback, 
                this, 
                std::placeholders::_1,              // Corresponds to the 'request' input
                std::placeholders::_2,              // Corresponds to the 'response' output
            )
        );
    }

    // Create your service pointer as a class member so that it persists 
    // between class functions
    rclcpp::Service<std_srvs::srv::Empty>::SharedPtr MyService;
};

Now as per @Karsten's answer, some example code does have a third service parameter for the service request header/id. You can include this, which appears to be optional. It does obviously requires you to add a third placeholder. E.g. the callback declaration becomes:

    void ServiceCallback(
        const std::shared_ptr<rmw_request_id_t>              request_header,
        const std::shared_ptr<std_srvs::srv::Empty::Request> request,
        std::shared_ptr<std_srvs::srv::Empty::Response>      response)

And the bind call becomes:

            std::bind(
                &MyNode::SubscriberCallback, 
                this, 
                std::placeholders::_1,              // Corresponds to the 'header' input
                std::placeholders::_2,              // Corresponds to the 'request' input
                std::placeholders::_3,              // Corresponds to the 'response' output
edit flag offensive delete link more
0

answered 2019-04-02 10:57:50 -0500

Karsten gravatar image

You might want to double check your callback signature. I believe two placeholders are not enough, you'd need three. See the examples here: https://github.com/ros2/examples/blob...

void handle_service( const std::shared_ptr<rmw_request_id_t> request_header, const std::shared_ptr<AddTwoInts::Request> request, const std::shared_ptr<AddTwoInts::Response> response)

edit flag offensive delete link more

Comments

The hyperlink above results in a dead end FYI. I believe the new link is this one: rclcpp/services/minimal_service/main.cpp.

M@t gravatar image M@t  ( 2021-01-17 18:29:38 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2019-04-02 03:11:29 -0500

Seen: 2,590 times

Last updated: Jan 17 '21