Skip to content

Commit 9918a14

Browse files
authored
Migrate std::bind calls to lambda expressions (#659)
* ♻️ Actions tutorial lambda refactor Signed-off-by: Felipe Gomes de Melo <[email protected]> * ♻️ Composition nodes lambda refactor Signed-off-by: Felipe Gomes de Melo <[email protected]> * ♻️ Lifecycle nodes lambda refactor Signed-off-by: Felipe Gomes de Melo <[email protected]> * ♻️ Logging demo lambda refactor Signed-off-by: Felipe Gomes de Melo <[email protected]> * ♻️ Image tools lambda refactor Signed-off-by: Felipe Gomes de Melo <[email protected]> * ♻️ Intra process lambda refactor Signed-off-by: Felipe Gomes de Melo <[email protected]> * 🎨 Format code Signed-off-by: Felipe Gomes de Melo <[email protected]> --------- Signed-off-by: Felipe Gomes de Melo <[email protected]>
1 parent 2864e1d commit 9918a14

File tree

12 files changed

+130
-121
lines changed

12 files changed

+130
-121
lines changed

action_tutorials/action_tutorials_cpp/README.md

Lines changed: 18 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -4,16 +4,17 @@ In the constructor for `FibonacciActionServer`, an action server is created with
44

55
```cpp
66
this->action_server_ = rclcpp_action::create_server<Fibonacci>(
7-
...
7+
this,
88
"fibonacci",
9-
std::bind(&FibonacciActionServer::handle_goal, this, _1, _2),
10-
std::bind(&FibonacciActionServer::handle_cancel, this, _1),
11-
std::bind(&FibonacciActionServer::handle_accepted, this, _1));
9+
handle_goal,
10+
handle_cancel,
11+
handle_accepted);
1212
```
1313

1414
The `handle_goal` callback is called whenever a goal is sent to the action server by an action client.
1515
In the example code, the goal is accepted as long as the order is less than or equal to 46, otherwise it is rejected.
1616
This is to prevent potential [integer overflow](https://en.wikipedia.org/wiki/Integer_overflow):
17+
1718
```cpp
1819
if (goal->order > 46) {
1920
return rclcpp_action::GoalResponse::REJECT;
@@ -25,8 +26,10 @@ The `handle_cancelled` callback is called whenever an action client requests to
2526
In this case, the goal cancel request is always accepted.
2627

2728
The `handle_accepted` callback is called following the action server's acceptance of a goal. In this example, a thread is started to execute the goal:
29+
2830
```cpp
29-
std::thread{std::bind(&FibonacciActionServer::execute, this, _1), goal_handle}.detach();
31+
auto execute_in_thread = [this, goal_handle](){return this->execute(goal_handle);};
32+
std::thread{execute_in_thread}.detach();
3033
```
3134
3235
The execution thread calculates the Fibonacci sequence up to *order* and publishes partial sequences as feedback as each item is added to the sequence.
@@ -51,12 +54,16 @@ The goal is sent asynchronously with callbacks registered for the goal response,
5154

5255
```cpp
5356
auto send_goal_options = rclcpp_action::Client<Fibonacci>::SendGoalOptions();
54-
send_goal_options.goal_response_callback =
55-
std::bind(&FibonacciActionClient::goal_response_callback, this, _1);
56-
send_goal_options.feedback_callback =
57-
std::bind(&FibonacciActionClient::feedback_callback, this, _1, _2);
58-
send_goal_options.result_callback =
59-
std::bind(&FibonacciActionClient::result_callback, this, _1);
57+
send_goal_options.goal_response_callback = [this](
58+
const GoalHandleFibonacci::SharedPtr & goal_handle)
59+
{...};
60+
send_goal_options.feedback_callback = [this](
61+
GoalHandleFibonacci::SharedPtr,
62+
const std::shared_ptr<const Fibonacci::Feedback> feedback)
63+
{...};
64+
send_goal_options.result_callback = [this](
65+
const GoalHandleFibonacci::WrappedResult & result)
66+
{...};
6067
this->client_ptr_->async_send_goal(goal_msg, send_goal_options);
6168
```
6269

action_tutorials/action_tutorials_cpp/src/fibonacci_action_client.cpp

Lines changed: 48 additions & 56 deletions
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ class FibonacciActionClient : public rclcpp::Node
4545

4646
this->timer_ = this->create_wall_timer(
4747
std::chrono::milliseconds(500),
48-
std::bind(&FibonacciActionClient::send_goal, this));
48+
[this]() {return this->send_goal();});
4949
}
5050

5151
ACTION_TUTORIALS_CPP_PUBLIC
@@ -67,67 +67,59 @@ class FibonacciActionClient : public rclcpp::Node
6767
RCLCPP_INFO(this->get_logger(), "Sending goal");
6868

6969
auto send_goal_options = rclcpp_action::Client<Fibonacci>::SendGoalOptions();
70-
send_goal_options.goal_response_callback =
71-
std::bind(&FibonacciActionClient::goal_response_callback, this, _1);
72-
send_goal_options.feedback_callback =
73-
std::bind(&FibonacciActionClient::feedback_callback, this, _1, _2);
74-
send_goal_options.result_callback =
75-
std::bind(&FibonacciActionClient::result_callback, this, _1);
70+
send_goal_options.goal_response_callback = [this](
71+
const GoalHandleFibonacci::SharedPtr & goal_handle)
72+
{
73+
if (!goal_handle) {
74+
RCLCPP_ERROR(this->get_logger(), "Goal was rejected by server");
75+
} else {
76+
RCLCPP_INFO(this->get_logger(), "Goal accepted by server, waiting for result");
77+
}
78+
};
79+
80+
send_goal_options.feedback_callback = [this](
81+
GoalHandleFibonacci::SharedPtr,
82+
const std::shared_ptr<const Fibonacci::Feedback> feedback)
83+
{
84+
std::stringstream ss;
85+
ss << "Next number in sequence received: ";
86+
for (auto number : feedback->partial_sequence) {
87+
ss << number << " ";
88+
}
89+
RCLCPP_INFO(this->get_logger(), ss.str().c_str());
90+
};
91+
92+
send_goal_options.result_callback = [this](
93+
const GoalHandleFibonacci::WrappedResult & result)
94+
{
95+
switch (result.code) {
96+
case rclcpp_action::ResultCode::SUCCEEDED:
97+
break;
98+
case rclcpp_action::ResultCode::ABORTED:
99+
RCLCPP_ERROR(this->get_logger(), "Goal was aborted");
100+
return;
101+
case rclcpp_action::ResultCode::CANCELED:
102+
RCLCPP_ERROR(this->get_logger(), "Goal was canceled");
103+
return;
104+
default:
105+
RCLCPP_ERROR(this->get_logger(), "Unknown result code");
106+
return;
107+
}
108+
std::stringstream ss;
109+
ss << "Result received: ";
110+
for (auto number : result.result->sequence) {
111+
ss << number << " ";
112+
}
113+
RCLCPP_INFO(this->get_logger(), ss.str().c_str());
114+
rclcpp::shutdown();
115+
};
116+
76117
this->client_ptr_->async_send_goal(goal_msg, send_goal_options);
77118
}
78119

79120
private:
80121
rclcpp_action::Client<Fibonacci>::SharedPtr client_ptr_;
81122
rclcpp::TimerBase::SharedPtr timer_;
82-
83-
ACTION_TUTORIALS_CPP_LOCAL
84-
void goal_response_callback(GoalHandleFibonacci::SharedPtr goal_handle)
85-
{
86-
if (!goal_handle) {
87-
RCLCPP_ERROR(this->get_logger(), "Goal was rejected by server");
88-
rclcpp::shutdown();
89-
} else {
90-
RCLCPP_INFO(this->get_logger(), "Goal accepted by server, waiting for result");
91-
}
92-
}
93-
94-
ACTION_TUTORIALS_CPP_LOCAL
95-
void feedback_callback(
96-
GoalHandleFibonacci::SharedPtr,
97-
const std::shared_ptr<const Fibonacci::Feedback> feedback)
98-
{
99-
std::stringstream ss;
100-
ss << "Next number in sequence received: ";
101-
for (auto number : feedback->partial_sequence) {
102-
ss << number << " ";
103-
}
104-
RCLCPP_INFO(this->get_logger(), "%s", ss.str().c_str());
105-
}
106-
107-
ACTION_TUTORIALS_CPP_LOCAL
108-
void result_callback(const GoalHandleFibonacci::WrappedResult & result)
109-
{
110-
switch (result.code) {
111-
case rclcpp_action::ResultCode::SUCCEEDED:
112-
break;
113-
case rclcpp_action::ResultCode::ABORTED:
114-
RCLCPP_ERROR(this->get_logger(), "Goal was aborted");
115-
return;
116-
case rclcpp_action::ResultCode::CANCELED:
117-
RCLCPP_ERROR(this->get_logger(), "Goal was canceled");
118-
return;
119-
default:
120-
RCLCPP_ERROR(this->get_logger(), "Unknown result code");
121-
return;
122-
}
123-
std::stringstream ss;
124-
ss << "Result received: ";
125-
for (auto number : result.result->sequence) {
126-
ss << number << " ";
127-
}
128-
RCLCPP_INFO(this->get_logger(), "%s", ss.str().c_str());
129-
rclcpp::shutdown();
130-
}
131123
}; // class FibonacciActionClient
132124

133125
} // namespace action_tutorials_cpp

action_tutorials/action_tutorials_cpp/src/fibonacci_action_server.cpp

Lines changed: 36 additions & 40 deletions
Original file line numberDiff line numberDiff line change
@@ -36,53 +36,49 @@ class FibonacciActionServer : public rclcpp::Node
3636
{
3737
using namespace std::placeholders;
3838

39+
auto handle_goal = [this](
40+
const rclcpp_action::GoalUUID & uuid,
41+
std::shared_ptr<const Fibonacci::Goal> goal)
42+
{
43+
(void)uuid;
44+
RCLCPP_INFO(this->get_logger(), "Received goal request with order %d", goal->order);
45+
// The Fibonacci action uses int32 for the return of sequences, which means it can only hold
46+
// 2^31-1 (2147483647) before wrapping negative in two's complement. Based on empirical
47+
// tests, that means that an order of > 46 will cause wrapping, so we don't allow that here.
48+
if (goal->order > 46) {
49+
return rclcpp_action::GoalResponse::REJECT;
50+
}
51+
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
52+
};
53+
54+
auto handle_cancel = [this](
55+
const std::shared_ptr<GoalHandleFibonacci> goal_handle)
56+
{
57+
RCLCPP_INFO(this->get_logger(), "Received request to cancel goal");
58+
(void)goal_handle;
59+
return rclcpp_action::CancelResponse::ACCEPT;
60+
};
61+
62+
auto handle_accepted = [this](
63+
const std::shared_ptr<GoalHandleFibonacci> goal_handle)
64+
{
65+
// this needs to return quickly to avoid blocking the executor,
66+
// so we declare a lambda function to be called inside a new thread
67+
auto execute_in_thread = [this, goal_handle]() {return this->execute(goal_handle);};
68+
std::thread{execute_in_thread}.detach();
69+
};
70+
3971
this->action_server_ = rclcpp_action::create_server<Fibonacci>(
40-
this->get_node_base_interface(),
41-
this->get_node_clock_interface(),
42-
this->get_node_logging_interface(),
43-
this->get_node_waitables_interface(),
72+
this,
4473
"fibonacci",
45-
std::bind(&FibonacciActionServer::handle_goal, this, _1, _2),
46-
std::bind(&FibonacciActionServer::handle_cancel, this, _1),
47-
std::bind(&FibonacciActionServer::handle_accepted, this, _1));
74+
handle_goal,
75+
handle_cancel,
76+
handle_accepted);
4877
}
4978

5079
private:
5180
rclcpp_action::Server<Fibonacci>::SharedPtr action_server_;
5281

53-
ACTION_TUTORIALS_CPP_LOCAL
54-
rclcpp_action::GoalResponse handle_goal(
55-
const rclcpp_action::GoalUUID & uuid,
56-
std::shared_ptr<const Fibonacci::Goal> goal)
57-
{
58-
(void)uuid;
59-
RCLCPP_INFO(this->get_logger(), "Received goal request with order %d", goal->order);
60-
// The Fibonacci action uses int32 for the return of sequences, which means it can only
61-
// hold 2^31-1 (2147483647) before wrapping negative in two's complement. Based on empirical
62-
// tests, that means that an order of > 46 will cause wrapping, so we don't allow that here.
63-
if (goal->order > 46) {
64-
return rclcpp_action::GoalResponse::REJECT;
65-
}
66-
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
67-
}
68-
69-
ACTION_TUTORIALS_CPP_LOCAL
70-
rclcpp_action::CancelResponse handle_cancel(
71-
const std::shared_ptr<GoalHandleFibonacci> goal_handle)
72-
{
73-
RCLCPP_INFO(this->get_logger(), "Received request to cancel goal");
74-
(void)goal_handle;
75-
return rclcpp_action::CancelResponse::ACCEPT;
76-
}
77-
78-
ACTION_TUTORIALS_CPP_LOCAL
79-
void handle_accepted(const std::shared_ptr<GoalHandleFibonacci> goal_handle)
80-
{
81-
using namespace std::placeholders;
82-
// this needs to return quickly to avoid blocking the executor, so spin up a new thread
83-
std::thread{std::bind(&FibonacciActionServer::execute, this, _1), goal_handle}.detach();
84-
}
85-
8682
ACTION_TUTORIALS_CPP_LOCAL
8783
void execute(const std::shared_ptr<GoalHandleFibonacci> goal_handle)
8884
{

composition/src/client_component.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,7 @@ Client::Client(const rclcpp::NodeOptions & options)
3333
// Note(dhood): The timer period must be greater than the duration of the timer callback.
3434
// Otherwise, the timer can starve a single-threaded executor.
3535
// See https://github.com/ros2/rclcpp/issues/392 for updates.
36-
timer_ = create_wall_timer(2s, std::bind(&Client::on_timer, this));
36+
timer_ = create_wall_timer(2s, [this]() {return this->on_timer();});
3737
}
3838

3939
void Client::on_timer()

composition/src/talker_component.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,7 @@ Talker::Talker(const rclcpp::NodeOptions & options)
3737
pub_ = create_publisher<std_msgs::msg::String>("chatter", 10);
3838

3939
// Use a timer to schedule periodic message publishing.
40-
timer_ = create_wall_timer(1s, std::bind(&Talker::on_timer, this));
40+
timer_ = create_wall_timer(1s, [this]() {return this->on_timer();});
4141
}
4242

4343
void Talker::on_timer()

image_tools/src/cam2image.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -110,7 +110,7 @@ class Cam2Image : public rclcpp::Node
110110
// Start main timer loop
111111
timer_ = this->create_wall_timer(
112112
std::chrono::milliseconds(static_cast<int>(1000.0 / freq_)),
113-
std::bind(&Cam2Image::timerCallback, this));
113+
[this]() {return this->timerCallback();});
114114
}
115115

116116
/// Publish camera, or burger, image.

intra_process_demo/include/image_pipeline/camera_node.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,7 @@ class CameraNode final : public rclcpp::Node
6161
// Create a publisher on the output topic.
6262
pub_ = this->create_publisher<sensor_msgs::msg::Image>(output, rclcpp::SensorDataQoS());
6363
// Create the camera reading loop.
64-
thread_ = std::thread(std::bind(&CameraNode::loop, this));
64+
thread_ = std::thread([this]() {return this->loop();});
6565
}
6666

6767
~CameraNode()

lifecycle/src/lifecycle_listener.cpp

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -39,15 +39,18 @@ class LifecycleListener : public rclcpp::Node
3939
// Data topic from the lc_talker node
4040
sub_data_ = this->create_subscription<std_msgs::msg::String>(
4141
"lifecycle_chatter", 10,
42-
std::bind(&LifecycleListener::data_callback, this, std::placeholders::_1));
42+
[this](std_msgs::msg::String::ConstSharedPtr msg) {return this->data_callback(msg);});
4343

4444
// Notification event topic. All state changes
4545
// are published here as TransitionEvents with
4646
// a start and goal state indicating the transition
4747
sub_notification_ = this->create_subscription<lifecycle_msgs::msg::TransitionEvent>(
4848
"/lc_talker/transition_event",
4949
10,
50-
std::bind(&LifecycleListener::notification_callback, this, std::placeholders::_1));
50+
[this](lifecycle_msgs::msg::TransitionEvent::ConstSharedPtr msg) {
51+
return this->notification_callback(msg);
52+
}
53+
);
5154
}
5255

5356
void data_callback(std_msgs::msg::String::ConstSharedPtr msg)

lifecycle/src/lifecycle_service_client.cpp

Lines changed: 8 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -328,10 +328,16 @@ int main(int argc, char ** argv)
328328

329329
std::shared_future<void> script = std::async(
330330
std::launch::async,
331-
std::bind(callee_script, lc_client));
331+
callee_script,
332+
lc_client
333+
);
334+
332335
auto wake_exec = std::async(
333336
std::launch::async,
334-
std::bind(wake_executor, script, std::ref(exe)));
337+
wake_executor,
338+
script,
339+
std::ref(exe)
340+
);
335341

336342
exe.spin_until_future_complete(script);
337343

lifecycle/src/lifecycle_talker.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -116,7 +116,7 @@ class LifecycleTalker : public rclcpp_lifecycle::LifecycleNode
116116
// available.
117117
pub_ = this->create_publisher<std_msgs::msg::String>("lifecycle_chatter", 10);
118118
timer_ = this->create_wall_timer(
119-
1s, std::bind(&LifecycleTalker::publish, this));
119+
1s, [this]() {return this->publish();});
120120

121121
RCLCPP_INFO(get_logger(), "on_configure() is called.");
122122

0 commit comments

Comments
 (0)