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

Create wall timer using callback with parameters - ROS2, C++

asked 2021-04-06 15:39:26 -0500

mirella melo gravatar image

updated 2021-04-06 15:41:02 -0500

Hi. I have two image msg synchronized as follows:

 message_filters::TimeSynchronizer<Image, Image>  sync(image_1, image_2, 10);
 sync.registerCallback(boost::bind(&callback, _1, _2));

It works until here. Now I'd want to define an interval between triggers of the callback using create_wall_timer. I tried:

 node->create_wall_timer(500ms, boost::bind(&callback, _1, _2));

But I'm getting errors when using it

 error: no matching function for call to ‘rclcpp::Node::create_wall_timer(std::chrono::milliseconds, boost::_bi::bind_t<void, void (*)(const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&, const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&), boost::_bi::list2<boost::arg<1>, boost::arg<2> > >)

What would be the proper way to use it? Thanks in advance.

obs: I tried with a callback without parameters node->create_wall_timer(500ms, &callback_test) and it works fine...

obs: alternatives to create_wall_timer are also welcome!

edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
2

answered 2021-04-07 05:38:20 -0500

sgvandijk gravatar image

From your question it seems that you expect that create_wall_timer can be used to specify how often the TimeSynchronizer calls its callback, but that's not the case. The synchronizer will just call its callback as soon as it has two synchronized messages to pass on.

create_wall_timer sets a completely unrelated timer that just calls its callback after the set time. It doesn't know about any topics or events that you may have used the same callback function for. And it does not have any of such information to pass to its callback, so it expects the callback function that you give to take 0 arguments. You pass it one that takes 2, which causes the error: 'there is no matching version of create_wall_timer that can deal with a callback that takes 2 arguments'.

That's why your test with callback_test does work, it takes no arguments, which is what the timer expects.

Side notes:

  • When you only use placeholders, you shouldn't need bind, you should be able to just use sync.registerCallback(&callback). bind is used if you want to use a class method as callback and you have to bind it to this.
  • You can also use lambda's instead of either boost::bind or std::bind, which I personally like better so you don't have to use function pointers or library methods:

    node->create_wall_timer(500ms, []() -> void { callback(); });
    

    Again here wrapping into a lambda is not strictly necessary and you could just use &callback; you could instead put the logic inside capture() directly into the lambda function, or capture any local variables that can be used at the time the callback is called. For instance as alternative to binding this if callback is a method on your node class:

    node->create_wall_timer(500ms, [this]() -> void { callback(); });
    
edit flag offensive delete link more

Comments

Hi @sgvandijk . I just stumbled upon this answer and I have two little questions about it: 1. I didn't understand the difference between the two lambda examples you gave. What does it change to capture or not capture this? 2. You are saying it's not necessary to wrap in a lamba. If I don't wrap, compiler complains: "vehicle.cpp:21:20: error: no matching member function for call to 'create_wall_timer' node_impl.hpp:109:7: note: candidate template ignored: substitution failure [with DurationRepT = long, DurationT = std::ratio<1, 1000>, CallbackT = void (Vehicle::*)()]". Am I doing something wrong or did they change something?

max11gen gravatar image max11gen  ( 2021-09-23 08:08:31 -0500 )edit

The difference is whether the callback is a free function or a class method. In OP's question it appears that callback is a free function, i.e. you can just call it as callback() and not as this->callback(). In your case I guess your callback is a member function, so you could call it as this->callback(), and as callback() because C++ allows you to omit this-> if this is in scope.

So that brings us to the difference between the lambdas: if your callback() is a class method on your node, this needs to be in scope to be able to call it, so it needs to be captured. Basically any time you use a method (or other member) of the current class you're in, you need [this].

Secondly, create_wall_timer expects a callable more akin to a free function, which is why passing it a method as I ...(more)

sgvandijk gravatar image sgvandijk  ( 2021-09-24 09:03:48 -0500 )edit
1

answered 2021-04-06 20:01:27 -0500

ROS2 uses std for bind and most other things that used to use Boost in ROS1. So that line would work as you expect with std::bind.

A practical example in ROS2 can be seen in Nav2's lifecycle manager https://github.com/ros-planning/navig...

edit flag offensive delete link more

Question Tools

3 followers

Stats

Asked: 2021-04-06 15:39:26 -0500

Seen: 7,709 times

Last updated: Apr 07 '21