Skip to content

Commit 913f2b6

Browse files
FelipeGdMtylerjwclalancette
authored
Migrate std::bind calls to lambda expressions (#4041)
* Simple cpp pub/sub page lambda refactor * Callback groups page lambda refactor * Fast dds config page lambda refactor * Custom interfaces lambda refactor * Params in class lambda refactor * tf2 add frame lambda refactor * Action server lambda refactor * Tf2 broadcaster lambda refactor * Action server/client lambda refactor * Read/record bagfile cpp lambda refactor * tf2 listener lambda refactor * Custom ROS 2 interfaces lambda refactor * Cpp parameters class lambda refactor * Webots basic tutorial lambda refactor * Webots advanced tutorial lambda refactor Signed-off-by: Felipe Gomes de Melo <[email protected]> Co-authored-by: Tyler Weaver <[email protected]> Co-authored-by: Chris Lalancette <[email protected]>
1 parent d412eee commit 913f2b6

18 files changed

+382
-398
lines changed

source/How-To-Guides/Using-callback-groups.rst

Lines changed: 23 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -210,25 +210,25 @@ We have two nodes - one providing a simple service:
210210
public:
211211
ServiceNode() : Node("service_node")
212212
{
213+
auto service_callback = [this](
214+
const std::shared_ptr<rmw_request_id_t> request_header,
215+
const std::shared_ptr<std_srvs::srv::Empty::Request> request,
216+
const std::shared_ptr<std_srvs::srv::Empty::Response> response)
217+
{
218+
(void)request_header;
219+
(void)request;
220+
(void)response;
221+
RCLCPP_INFO(this->get_logger(), "Received request, responding...");
222+
};
213223
service_ptr_ = this->create_service<std_srvs::srv::Empty>(
214224
"test_service",
215-
std::bind(&ServiceNode::service_callback, this, _1, _2, _3)
225+
service_callback
216226
);
217227
}
218228
219229
private:
220230
rclcpp::Service<std_srvs::srv::Empty>::SharedPtr service_ptr_;
221231
222-
void service_callback(
223-
const std::shared_ptr<rmw_request_id_t> request_header,
224-
const std::shared_ptr<std_srvs::srv::Empty::Request> request,
225-
const std::shared_ptr<std_srvs::srv::Empty::Response> response)
226-
{
227-
(void)request_header;
228-
(void)request;
229-
(void)response;
230-
RCLCPP_INFO(this->get_logger(), "Received request, responding...");
231-
}
232232
}; // class ServiceNode
233233
} // namespace cb_group_demo
234234
@@ -306,8 +306,18 @@ service calls:
306306
timer_cb_group_ = nullptr;
307307
client_ptr_ = this->create_client<std_srvs::srv::Empty>("test_service", rmw_qos_profile_services_default,
308308
client_cb_group_);
309-
timer_ptr_ = this->create_wall_timer(1s, std::bind(&DemoNode::timer_callback, this),
310-
timer_cb_group_);
309+
310+
auto timer_callback = [this](){
311+
RCLCPP_INFO(this->get_logger(), "Sending request");
312+
auto request = std::make_shared<std_srvs::srv::Empty::Request>();
313+
auto result_future = client_ptr_->async_send_request(request);
314+
std::future_status status = result_future.wait_for(10s); // timeout to guarantee a graceful finish
315+
if (status == std::future_status::ready) {
316+
RCLCPP_INFO(this->get_logger(), "Received response");
317+
}
318+
};
319+
320+
timer_ptr_ = this->create_wall_timer(1s, timer_callback, timer_cb_group_);
311321
}
312322
313323
private:
@@ -316,16 +326,6 @@ service calls:
316326
rclcpp::Client<std_srvs::srv::Empty>::SharedPtr client_ptr_;
317327
rclcpp::TimerBase::SharedPtr timer_ptr_;
318328
319-
void timer_callback()
320-
{
321-
RCLCPP_INFO(this->get_logger(), "Sending request");
322-
auto request = std::make_shared<std_srvs::srv::Empty::Request>();
323-
auto result_future = client_ptr_->async_send_request(request);
324-
std::future_status status = result_future.wait_for(10s); // timeout to guarantee a graceful finish
325-
if (status == std::future_status::ready) {
326-
RCLCPP_INFO(this->get_logger(), "Received response");
327-
}
328-
}
329329
}; // class DemoNode
330330
} // namespace cb_group_demo
331331

source/Tutorials/Advanced/FastDDS-Configuration.rst

Lines changed: 30 additions & 39 deletions
Original file line numberDiff line numberDiff line change
@@ -112,41 +112,38 @@ Note that the synchronous publisher will be publishing on topic ``sync_topic``,
112112
// Create the asynchronous publisher on topic 'async_topic'
113113
async_publisher_ = this->create_publisher<std_msgs::msg::String>("async_topic", 10);
114114

115-
// This timer will trigger the publication of new data every half a second
116-
timer_ = this->create_wall_timer(
117-
500ms, std::bind(&SyncAsyncPublisher::timer_callback, this));
118-
}
115+
// Actions to run every time the timer expires
116+
auto timer_callback = [this](){
119117

120-
private:
121-
/**
122-
* Actions to run every time the timer expires
123-
*/
124-
void timer_callback()
125-
{
126-
// Create a new message to be sent
127-
auto sync_message = std_msgs::msg::String();
128-
sync_message.data = "SYNC: Hello, world! " + std::to_string(count_);
118+
// Create a new message to be sent
119+
auto sync_message = std_msgs::msg::String();
120+
sync_message.data = "SYNC: Hello, world! " + std::to_string(count_);
129121

130-
// Log the message to the console to show progress
131-
RCLCPP_INFO(this->get_logger(), "Synchronously publishing: '%s'", sync_message.data.c_str());
122+
// Log the message to the console to show progress
123+
RCLCPP_INFO(this->get_logger(), "Synchronously publishing: '%s'", sync_message.data.c_str());
132124

133-
// Publish the message using the synchronous publisher
134-
sync_publisher_->publish(sync_message);
125+
// Publish the message using the synchronous publisher
126+
sync_publisher_->publish(sync_message);
135127

136-
// Create a new message to be sent
137-
auto async_message = std_msgs::msg::String();
138-
async_message.data = "ASYNC: Hello, world! " + std::to_string(count_);
128+
// Create a new message to be sent
129+
auto async_message = std_msgs::msg::String();
130+
async_message.data = "ASYNC: Hello, world! " + std::to_string(count_);
139131

140-
// Log the message to the console to show progress
141-
RCLCPP_INFO(this->get_logger(), "Asynchronously publishing: '%s'", async_message.data.c_str());
132+
// Log the message to the console to show progress
133+
RCLCPP_INFO(this->get_logger(), "Asynchronously publishing: '%s'", async_message.data.c_str());
142134

143-
// Publish the message using the asynchronous publisher
144-
async_publisher_->publish(async_message);
135+
// Publish the message using the asynchronous publisher
136+
async_publisher_->publish(async_message);
145137

146-
// Prepare the count for the next message
147-
count_++;
138+
// Prepare the count for the next message
139+
count_++;
140+
};
141+
142+
// This timer will trigger the publication of new data every half a second
143+
timer_ = this->create_wall_timer(500ms, timer_callback);
148144
}
149145

146+
private:
150147
// This timer will trigger the publication of new data every half a second
151148
rclcpp::TimerBase::SharedPtr timer_;
152149

@@ -322,42 +319,36 @@ In a new source file named ``src/sync_async_reader.cpp`` write the following con
322319

323320
.. code-block:: C++
324321

325-
#include <functional>
326322
#include <memory>
327323

328324
#include "rclcpp/rclcpp.hpp"
329325
#include "std_msgs/msg/string.hpp"
330326

331-
using std::placeholders::_1;
332-
333327
class SyncAsyncSubscriber : public rclcpp::Node
334328
{
335329
public:
336330

337331
SyncAsyncSubscriber()
338332
: Node("sync_async_subscriber")
339333
{
334+
// Lambda function to run every time a new message is received
335+
auto topic_callback = [this](const std_msgs::msg::String & msg){
336+
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg.data.c_str());
337+
};
338+
340339
// Create the synchronous subscriber on topic 'sync_topic'
341340
// and tie it to the topic_callback
342341
sync_subscription_ = this->create_subscription<std_msgs::msg::String>(
343-
"sync_topic", 10, std::bind(&SyncAsyncSubscriber::topic_callback, this, _1));
342+
"sync_topic", 10, topic_callback);
344343

345344
// Create the asynchronous subscriber on topic 'async_topic'
346345
// and tie it to the topic_callback
347346
async_subscription_ = this->create_subscription<std_msgs::msg::String>(
348-
"async_topic", 10, std::bind(&SyncAsyncSubscriber::topic_callback, this, _1));
347+
"async_topic", 10, topic_callback);
349348
}
350349

351350
private:
352351

353-
/**
354-
* Actions to run every time a new message is received
355-
*/
356-
void topic_callback(const std_msgs::msg::String & msg) const
357-
{
358-
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg.data.c_str());
359-
}
360-
361352
// A subscriber that listens to topic 'sync_topic'
362353
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr sync_subscription_;
363354

source/Tutorials/Advanced/Reading-From-A-Bag-File-CPP.rst

Lines changed: 8 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -86,8 +86,10 @@ Inside your package's ``src`` directory, create a new file called ``simple_bag_r
8686
: Node("playback_node")
8787
{
8888
publisher_ = this->create_publisher<turtlesim::msg::Pose>("/turtle1/pose", 10);
89-
timer_ = this->create_wall_timer(
90-
100ms, std::bind(&PlaybackNode::timer_callback, this));
89+
90+
timer_ = this->create_wall_timer(100ms,
91+
[this](){return this->timer_callback();}
92+
);
9193

9294
reader_.open(bag_filename);
9395
}
@@ -158,8 +160,10 @@ Note the constructor takes a path to the bag file as a parameter.
158160
: Node("playback_node")
159161
{
160162
publisher_ = this->create_publisher<turtlesim::msg::Pose>("/turtle1/pose", 10);
161-
timer_ = this->create_wall_timer(
162-
100ms, std::bind(&PlaybackNode::timer_callback, this));
163+
164+
timer_ = this->create_wall_timer(100ms,
165+
[this](){return this->timer_callback();}
166+
);
163167

164168
We also open the bag in the constructor.
165169

source/Tutorials/Advanced/Recording-A-Bag-From-Your-Own-Node-CPP.rst

Lines changed: 19 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -84,8 +84,6 @@ Inside the ``ros2_ws/src/bag_recorder_nodes/src`` directory, create a new file c
8484

8585
#include <rosbag2_cpp/writer.hpp>
8686

87-
using std::placeholders::_1;
88-
8987
class SimpleBagRecorder : public rclcpp::Node
9088
{
9189
public:
@@ -96,17 +94,17 @@ Inside the ``ros2_ws/src/bag_recorder_nodes/src`` directory, create a new file c
9694

9795
writer_->open("my_bag");
9896

97+
auto subscription_callback_lambda = [this](std::shared_ptr<rclcpp::SerializedMessage> msg){
98+
rclcpp::Time time_stamp = this->now();
99+
100+
writer_->write(msg, "chatter", "std_msgs/msg/String", time_stamp);
101+
};
102+
99103
subscription_ = create_subscription<std_msgs::msg::String>(
100-
"chatter", 10, std::bind(&SimpleBagRecorder::topic_callback, this, _1));
104+
"chatter", 10, subscription_callback_lambda);
101105
}
102106

103107
private:
104-
void topic_callback(std::shared_ptr<rclcpp::SerializedMessage> msg) const
105-
{
106-
rclcpp::Time time_stamp = this->now();
107-
108-
writer_->write(msg, "chatter", "std_msgs/msg/String", time_stamp);
109-
}
110108

111109
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_;
112110
std::unique_ptr<rosbag2_cpp::Writer> writer_;
@@ -146,8 +144,14 @@ We will write data to the bag in the callback.
146144

147145
.. code-block:: C++
148146

147+
auto subscription_callback_lambda = [this](std::shared_ptr<rclcpp::SerializedMessage> msg){
148+
rclcpp::Time time_stamp = this->now();
149+
150+
writer_->write(msg, "chatter", "std_msgs/msg/String", time_stamp);
151+
};
152+
149153
subscription_ = create_subscription<std_msgs::msg::String>(
150-
"chatter", 10, std::bind(&SimpleBagRecorder::topic_callback, this, _1));
154+
"chatter", 10, subscription_callback_lambda);
151155

152156
The callback itself is different from a typical callback.
153157
Rather than receiving an instance of the data type of the topic, we instead receive a ``rclcpp::SerializedMessage``.
@@ -158,8 +162,7 @@ We do this for two reasons.
158162

159163
.. code-block:: C++
160164

161-
void topic_callback(std::shared_ptr<rclcpp::SerializedMessage> msg) const
162-
{
165+
auto subscription_callback_lambda = [this](std::shared_ptr<rclcpp::SerializedMessage> msg){
163166

164167
Within the subscription callback, the first thing to do is determine the time stamp to use for the stored message.
165168
This can be anything appropriate to your data, but two common values are the time at which the data was produced, if known, and the time it is received.
@@ -349,7 +352,8 @@ Inside the ``ros2_ws/src/bag_recorder_nodes/src`` directory, create a new file c
349352
rmw_get_serialization_format(),
350353
""});
351354

352-
timer_ = create_wall_timer(1s, std::bind(&DataGenerator::timer_callback, this));
355+
auto timer_callback_lambda = [this](){return this->timer_callback();};
356+
timer_ = create_wall_timer(1s, timer_callback_lambda);
353357
}
354358

355359
private:
@@ -401,7 +405,8 @@ The timer fires with a one-second period, and calls the given member function wh
401405

402406
.. code-block:: C++
403407

404-
timer_ = create_wall_timer(1s, std::bind(&DataGenerator::timer_callback, this));
408+
auto timer_callback_lambda = [this](){return this->timer_callback();};
409+
timer_ = create_wall_timer(1s, timer_callback_lambda);
405410

406411
Within the timer callback, we generate (or otherwise obtain, e.g. read from a serial port connected to some hardware) the data we wish to store in the bag.
407412
The important difference between this and the previous sample is that the data is not yet serialised.

source/Tutorials/Advanced/Simulators/Webots/Code/MyRobotDriver.cpp

Lines changed: 5 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -25,13 +25,11 @@ void MyRobotDriver::init(
2525

2626
cmd_vel_subscription_ = node->create_subscription<geometry_msgs::msg::Twist>(
2727
"/cmd_vel", rclcpp::SensorDataQoS().reliable(),
28-
std::bind(&MyRobotDriver::cmdVelCallback, this, std::placeholders::_1));
29-
}
30-
31-
void MyRobotDriver::cmdVelCallback(
32-
const geometry_msgs::msg::Twist::SharedPtr msg) {
33-
cmd_vel_msg.linear = msg->linear;
34-
cmd_vel_msg.angular = msg->angular;
28+
[this](const geometry_msgs::msg::Twist::SharedPtr msg){
29+
this->cmd_vel_msg.linear = msg->linear;
30+
this->cmd_vel_msg.angular = msg->angular;
31+
}
32+
);
3533
}
3634

3735
void MyRobotDriver::step() {

source/Tutorials/Advanced/Simulators/Webots/Code/MyRobotDriver.hpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,6 @@ class MyRobotDriver : public webots_ros2_driver::PluginInterface {
1616
std::unordered_map<std::string, std::string> &parameters) override;
1717

1818
private:
19-
void cmdVelCallback(const geometry_msgs::msg::Twist::SharedPtr msg);
2019

2120
rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr
2221
cmd_vel_subscription_;

source/Tutorials/Advanced/Simulators/Webots/Code/ObstacleAvoider.cpp

Lines changed: 8 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -7,13 +7,17 @@ ObstacleAvoider::ObstacleAvoider() : Node("obstacle_avoider") {
77

88
left_sensor_sub_ = create_subscription<sensor_msgs::msg::Range>(
99
"/left_sensor", 1,
10-
std::bind(&ObstacleAvoider::leftSensorCallback, this,
11-
std::placeholders::_1));
10+
[this](const sensor_msgs::msg::Range::SharedPtr msg){
11+
return this->leftSensorCallback(msg);
12+
}
13+
);
1214

1315
right_sensor_sub_ = create_subscription<sensor_msgs::msg::Range>(
1416
"/right_sensor", 1,
15-
std::bind(&ObstacleAvoider::rightSensorCallback, this,
16-
std::placeholders::_1));
17+
[this](const sensor_msgs::msg::Range::SharedPtr msg){
18+
return this->rightSensorCallback(msg);
19+
}
20+
);
1721
}
1822

1923
void ObstacleAvoider::leftSensorCallback(

source/Tutorials/Advanced/Simulators/Webots/Setting-Up-Simulation-Webots-Advanced.rst

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -108,21 +108,21 @@ In addition to your custom plugin, the ``webots_ros2_driver`` will parse the ``<
108108

109109
.. literalinclude:: Code/ObstacleAvoider.cpp
110110
:language: cpp
111-
:lines: 6-16
111+
:lines: 6-20
112112

113113
When a measurement is received from the left sensor it will be copied to a member field:
114114

115115
.. literalinclude:: Code/ObstacleAvoider.cpp
116116
:language: cpp
117-
:lines: 19-22
117+
:lines: 23-26
118118

119119
Finally, a message will be sent to the ``/cmd_vel`` topic when a measurement from the right sensor is received.
120120
The ``command_message`` will register at least a forward speed in ``linear.x`` in order to make the robot move when no obstacle is detected.
121121
If any of the two sensors detect an obstacle, ``command_message`` will also register a rotational speed in ``angular.z`` in order to make the robot turn right.
122122

123123
.. literalinclude:: Code/ObstacleAvoider.cpp
124124
:language: cpp
125-
:lines: 24-38
125+
:lines: 28-42
126126

127127

128128
3 Updating additional files

0 commit comments

Comments
 (0)