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

ROS2 error creating a service server as a member function?

asked 2018-07-31 05:04:49 -0600

ahlyder gravatar image

I am trying to create a service server with a callback as a member function:

class FirstNode : public rclcpp::Node
  {
    public:
      explicit FirstNode(const std::string & node_name) : Node(node_name)
      {
        RCLCPP_INFO(this->get_logger(), "%s started", node_name.c_str());

        server_ = this->create_service<std_srvs::srv::Trigger>("first_service", std::bind(&FirstNode::handle_service, this, _3, _2, _1));
      }

    private:
      void handle_service(
        const std::shared_ptr<rmw_request_id_t> request_header,
        const std::shared_ptr<std_srvs::srv::Trigger::Request> request,
        std::shared_ptr<std_srvs::srv::Trigger::Response> response)
      {
        (void)request_header;
        RCLCPP_INFO(this->get_logger(), "Service Triggered");
      }

      rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr server_;
  };

However, I get the following error:

In file included from /Users/ahl/happtec_ws/src/first_node_cpp/src/first_node.cpp:15:
In file included from /Users/ahl/ros2_ws/install/rclcpp/include/rclcpp/rclcpp.hpp:144:
In file included from /Users/ahl/ros2_ws/install/rclcpp/include/rclcpp/executors.hpp:21:
In file included from /Users/ahl/ros2_ws/install/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp:24:
In file included from /Users/ahl/ros2_ws/install/rclcpp/include/rclcpp/executor.hpp:31:
In file included from /Users/ahl/ros2_ws/install/rclcpp/include/rclcpp/node_interfaces/node_base_interface.hpp:25:
In file included from /Users/ahl/ros2_ws/install/rclcpp/include/rclcpp/callback_group.hpp:24:
In file included from /Users/ahl/ros2_ws/install/rclcpp/include/rclcpp/service.hpp:27:
/Users/ahl/ros2_ws/install/rclcpp/include/rclcpp/any_service_callback.hpp:81:46: error: no viable overloaded '='
    shared_ptr_with_request_header_callback_ = callback;
    ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ ^ ~~~~~~~~
/Users/ahl/ros2_ws/install/rclcpp/include/rclcpp/create_service.hpp:43:24: note: in instantiation of function template specialization 'rclcpp::AnyServiceCallback<std_srvs::srv::Trigger>::set<std::__1::__bind<void (FirstNode::*)(std::__1::shared_ptr<rmw_request_id_t>, std::__1::shared_ptr<std_srvs::srv::Trigger_Request_<std::__1::allocator<void> > >, std::__1::shared_ptr<std_srvs::srv::Trigger_Response_<std::__1::allocator<void> > >), FirstNode *, const std::__1::placeholders::__ph<3> &, const std::__1::placeholders::__ph<2> &, const std::__1::placeholders::__ph<1> &>, nullptr>' requested here
  any_service_callback.set(std::forward<CallbackT>(callback));
                       ^
/Users/ahl/ros2_ws/install/rclcpp/include/rclcpp/node_impl.hpp:200:18: note: in instantiation of function template specialization 'rclcpp::create_service<std_srvs::srv::Trigger, std::__1::__bind<void (FirstNode::*)(std::__1::shared_ptr<rmw_request_id_t>, std::__1::shared_ptr<std_srvs::srv::Trigger_Request_<std::__1::allocator<void> > >, std::__1::shared_ptr<std_srvs::srv::Trigger_Response_<std::__1::allocator<void> > >), FirstNode *, const std::__1::placeholders::__ph<3> &, const std::__1::placeholders::__ph<2> &, const std::__1::placeholders::__ph<1> &> >' requested here
  return rclcpp::create_service<ServiceT, CallbackT>(
                 ^
/Users/ahl/happtec_ws/src/first_node_cpp/src/first_node.cpp:43:21: note: in instantiation of function template specialization 'rclcpp::Node::create_service<std_srvs::srv::Trigger, std::__1::__bind<void (FirstNode::*)(std::__1::shared_ptr<rmw_request_id_t>, std::__1::shared_ptr<std_srvs::srv::Trigger_Request_<std::__1::allocator<void> > >, std::__1::shared_ptr<std_srvs::srv::Trigger_Response_<std::__1::allocator<void> > >), FirstNode *, const std::__1::placeholders::__ph<3> &, const std::__1::placeholders::__ph<2> &, const std::__1::placeholders::__ph<1> &> >' requested here
    server_ = this->create_service<std_srvs::srv::Trigger>("first_service", std::bind(&FirstNode::handle_service, this, _3, _2, _1));
                    ^
/Library/Developer/CommandLineTools/usr/include/c++/v1/functional:1645:15: note: candidate function not viable: no known conversion from 'std::__1::__bind<void (FirstNode::*)(std::__1::shared_ptr<rmw_request_id_t>, std ...
(more)
edit retag flag offensive close merge delete

Comments

You might be interested in the discussion on this stack overflow post https://stackoverflow.com/questions/1... . Some people prefer lambda's instead of std::bind since C++14.

sloretz gravatar image sloretz  ( 2018-07-31 10:31:22 -0600 )edit

2 Answers

Sort by » oldest newest most voted
2

answered 2018-07-31 10:30:58 -0600

sloretz gravatar image

It looks like the arguments to bind are out of order. I think it should be

std::bind(&FirstNode::handle_service, this, _1, _2, _3));

edit flag offensive delete link more

Comments

You're right! I got the order from an example, so I thought that the arguments where passed in the order they appeared and not by number. But is a nice feature.

ahlyder gravatar image ahlyder  ( 2018-08-09 23:40:42 -0600 )edit
-2

answered 2019-04-16 09:54:00 -0600

JanOr gravatar image

updated 2019-04-16 09:59:25 -0600

Hi, I have a similar problem with a service as a member in ROS2 crystal, but have issues to use std::bind :

in test_class.hpp:

#include "rclcpp/rclcpp.hpp"
#include "std_srvs/srv/trigger.hpp"
class TestClass{
    rclcpp::Node::SharedPtr ros_node_;
    rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr server_srv_test;

public:
    TestClass();
    void handleTest(
          const std::shared_ptr<rmw_request_id_t> request_header,
          const std::shared_ptr<std_srvs::srv::Trigger::Request> request,
          std::shared_ptr<std_srvs::srv::Trigger::Response> response);
};

in test_class.cpp:

#include "test_project/test_class.hpp"
void TestClass::handleTest(
          const std::shared_ptr<rmw_request_id_t> request_header,
          const std::shared_ptr<std_srvs::srv::Trigger::Request> request,
          std::shared_ptr<std_srvs::srv::Trigger::Response> response)
        {
          (void)request_header;
          //do sth here
        }

TestClass::TestClass()
        {
          ros_node_ = rclcpp::Node::make_shared("robot_manager");
          server_srv_test_=ros_node_->create_service<std_srvs::srv::Trigger>("test service",\
          std::bind(&TestClass::handleTest,this,_1,_2,_3));
        }

With the solution that you propose, I get the errors e.g.

error: ‘_1’ was not declared in this scope

without binding e.g.

server_srv_test_=ros_node_->create_service<std_srvs::srv::Trigger>("test service",&TestClass::handleTest);

I get errors like:

error: ‘operator()’ is not a member of ‘void (TestClass::*)(std::shared_ptr<rmw_request_id_t>, std::shared_ptr<std_srvs::srv::test_request_<std::allocator<void>

, std::shared_ptr<std_srvs::srv::trigger_response_<std::allocator<void> )’ typename function_traits<decltype( &amp;functiont::operator())&gt;::arguments="">::type;

Do you have any idea, what I am missing here? Thanks a lot!

edit flag offensive delete link more

Comments

just making sure: _1 is defined in std::placeholders. So you either have to use the namespace or explicitly state std::placeholders::_1.

Karsten gravatar image Karsten  ( 2019-04-16 11:12:41 -0600 )edit
1

Please don't use an answer to ask a question. This isn't a forum. Please create a new question and reference this one instead.

jayess gravatar image jayess  ( 2019-04-16 14:35:39 -0600 )edit

Thanks! That's it!

JanOr gravatar image JanOr  ( 2019-04-17 00:54:09 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2018-07-31 05:04:49 -0600

Seen: 3,775 times

Last updated: Apr 16 '19