Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Migrate std::bind calls to lambda expressions #4041

Merged
merged 20 commits into from
Jan 12, 2024
Merged
Show file tree
Hide file tree
Changes from 16 commits
Commits
Show all changes
20 commits
Select commit Hold shift + click to select a range
78b25fa
:recycle: Simple cpp pub/sub page lambda refactor
FelipeGdM Jun 5, 2023
e1bfe67
:recycle: Callback groups page lambda refactor
FelipeGdM Jun 13, 2023
234b357
:recycle: Fast dds config page lambda refactor
FelipeGdM Jun 13, 2023
b7cf836
:recycle: Custom interfaces lambda refactor
FelipeGdM Jun 13, 2023
fb569eb
:recycle: Params in class lambda refactor
FelipeGdM Jun 13, 2023
5104610
:recycle: tf2 add frame lambda refactor
FelipeGdM Jun 13, 2023
a3e92ba
:recycle: Action server lambda refactor
FelipeGdM Jun 13, 2023
7cc424f
:recycle: Tf2 broadcaster lambda refactor
FelipeGdM Jun 13, 2023
a146841
♻️ Action server/client lambda refactor
FelipeGdM Nov 30, 2023
5d1a349
♻️ Read/record bagfile cpp lambda refactor
FelipeGdM Nov 30, 2023
7e724a5
♻️ tf2 listener lambda refactor
FelipeGdM Nov 30, 2023
4b307ba
♻️ Custom ROS 2 interfaces lambda refactor
FelipeGdM Nov 30, 2023
1b9cc67
♻️ Cpp parameters class lambda refactor
FelipeGdM Nov 30, 2023
e48cb71
Update source/Tutorials/Advanced/Reading-From-A-Bag-File-CPP.rst
FelipeGdM Dec 9, 2023
6be1538
Remove unused comment
FelipeGdM Dec 9, 2023
ef5a721
Update reading from a bag file cpp
FelipeGdM Dec 9, 2023
93b8bc5
♻️ Webots basic tutorial lambda refactor
FelipeGdM Dec 14, 2023
a818545
♻️ Webots advanced tutorial lambda refactor
FelipeGdM Dec 14, 2023
6de3929
Update source/Tutorials/Intermediate/Writing-an-Action-Server-Client/…
FelipeGdM Jan 5, 2024
7ab5310
Update source/Tutorials/Intermediate/Tf2/Adding-A-Frame-Cpp.rst
FelipeGdM Jan 5, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
46 changes: 23 additions & 23 deletions source/How-To-Guides/Using-callback-groups.rst
Original file line number Diff line number Diff line change
Expand Up @@ -210,25 +210,25 @@ We have two nodes - one providing a simple service:
public:
ServiceNode() : Node("service_node")
{
auto service_callback = [this](
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<std_srvs::srv::Empty::Request> request,
const std::shared_ptr<std_srvs::srv::Empty::Response> response)
{
(void)request_header;
(void)request;
(void)response;
RCLCPP_INFO(this->get_logger(), "Received request, responding...");
};
service_ptr_ = this->create_service<std_srvs::srv::Empty>(
"test_service",
std::bind(&ServiceNode::service_callback, this, _1, _2, _3)
service_callback
);
}

private:
rclcpp::Service<std_srvs::srv::Empty>::SharedPtr service_ptr_;

void service_callback(
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<std_srvs::srv::Empty::Request> request,
const std::shared_ptr<std_srvs::srv::Empty::Response> response)
{
(void)request_header;
(void)request;
(void)response;
RCLCPP_INFO(this->get_logger(), "Received request, responding...");
}
}; // class ServiceNode
} // namespace cb_group_demo

Expand Down Expand Up @@ -306,8 +306,18 @@ service calls:
timer_cb_group_ = nullptr;
client_ptr_ = this->create_client<std_srvs::srv::Empty>("test_service", rmw_qos_profile_services_default,
client_cb_group_);
timer_ptr_ = this->create_wall_timer(1s, std::bind(&DemoNode::timer_callback, this),
timer_cb_group_);

auto timer_callback = [this](){
RCLCPP_INFO(this->get_logger(), "Sending request");
auto request = std::make_shared<std_srvs::srv::Empty::Request>();
auto result_future = client_ptr_->async_send_request(request);
std::future_status status = result_future.wait_for(10s); // timeout to guarantee a graceful finish
if (status == std::future_status::ready) {
RCLCPP_INFO(this->get_logger(), "Received response");
}
};

timer_ptr_ = this->create_wall_timer(1s, timer_callback, timer_cb_group_);
}

private:
Expand All @@ -316,16 +326,6 @@ service calls:
rclcpp::Client<std_srvs::srv::Empty>::SharedPtr client_ptr_;
rclcpp::TimerBase::SharedPtr timer_ptr_;

void timer_callback()
{
RCLCPP_INFO(this->get_logger(), "Sending request");
auto request = std::make_shared<std_srvs::srv::Empty::Request>();
auto result_future = client_ptr_->async_send_request(request);
std::future_status status = result_future.wait_for(10s); // timeout to guarantee a graceful finish
if (status == std::future_status::ready) {
RCLCPP_INFO(this->get_logger(), "Received response");
}
}
}; // class DemoNode
} // namespace cb_group_demo

Expand Down
69 changes: 30 additions & 39 deletions source/Tutorials/Advanced/FastDDS-Configuration.rst
Original file line number Diff line number Diff line change
Expand Up @@ -112,41 +112,38 @@ Note that the synchronous publisher will be publishing on topic ``sync_topic``,
// Create the asynchronous publisher on topic 'async_topic'
async_publisher_ = this->create_publisher<std_msgs::msg::String>("async_topic", 10);

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

private:
/**
* Actions to run every time the timer expires
*/
void timer_callback()
{
// Create a new message to be sent
auto sync_message = std_msgs::msg::String();
sync_message.data = "SYNC: Hello, world! " + std::to_string(count_);
// Create a new message to be sent
auto sync_message = std_msgs::msg::String();
sync_message.data = "SYNC: Hello, world! " + std::to_string(count_);

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

// Publish the message using the synchronous publisher
sync_publisher_->publish(sync_message);
// Publish the message using the synchronous publisher
sync_publisher_->publish(sync_message);

// Create a new message to be sent
auto async_message = std_msgs::msg::String();
async_message.data = "ASYNC: Hello, world! " + std::to_string(count_);
// Create a new message to be sent
auto async_message = std_msgs::msg::String();
async_message.data = "ASYNC: Hello, world! " + std::to_string(count_);

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

// Publish the message using the asynchronous publisher
async_publisher_->publish(async_message);
// Publish the message using the asynchronous publisher
async_publisher_->publish(async_message);

// Prepare the count for the next message
count_++;
// Prepare the count for the next message
count_++;
};

// This timer will trigger the publication of new data every half a second
timer_ = this->create_wall_timer(500ms, timer_callback);
}

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

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

.. code-block:: C++

#include <functional>
#include <memory>

#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"

using std::placeholders::_1;

class SyncAsyncSubscriber : public rclcpp::Node
{
public:

SyncAsyncSubscriber()
: Node("sync_async_subscriber")
{
// Lambda function to run every time a new message is received
auto topic_callback = [this](const std_msgs::msg::String & msg){
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg.data.c_str());
};

// Create the synchronous subscriber on topic 'sync_topic'
// and tie it to the topic_callback
sync_subscription_ = this->create_subscription<std_msgs::msg::String>(
"sync_topic", 10, std::bind(&SyncAsyncSubscriber::topic_callback, this, _1));
"sync_topic", 10, topic_callback);

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

private:

/**
* Actions to run every time a new message is received
*/
void topic_callback(const std_msgs::msg::String & msg) const
{
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg.data.c_str());
}

// A subscriber that listens to topic 'sync_topic'
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr sync_subscription_;

Expand Down
12 changes: 8 additions & 4 deletions source/Tutorials/Advanced/Reading-From-A-Bag-File-CPP.rst
Original file line number Diff line number Diff line change
Expand Up @@ -86,8 +86,10 @@ Inside your package's ``src`` directory, create a new file called ``simple_bag_r
: Node("playback_node")
{
publisher_ = this->create_publisher<turtlesim::msg::Pose>("/turtle1/pose", 10);
timer_ = this->create_wall_timer(
100ms, std::bind(&PlaybackNode::timer_callback, this));

timer_ = this->create_wall_timer(100ms,
[this](){return this->timer_callback();}
);

reader_.open(bag_filename);
}
Expand Down Expand Up @@ -158,8 +160,10 @@ Note the constructor takes a path to the bag file as a parameter.
: Node("playback_node")
{
publisher_ = this->create_publisher<turtlesim::msg::Pose>("/turtle1/pose", 10);
timer_ = this->create_wall_timer(
100ms, std::bind(&PlaybackNode::timer_callback, this));

timer_ = this->create_wall_timer(100ms,
[this](){return this->timer_callback();}
);

We also open the bag in the constructor.

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -84,8 +84,6 @@ Inside the ``ros2_ws/src/bag_recorder_nodes/src`` directory, create a new file c

#include <rosbag2_cpp/writer.hpp>

using std::placeholders::_1;

class SimpleBagRecorder : public rclcpp::Node
{
public:
Expand All @@ -96,17 +94,17 @@ Inside the ``ros2_ws/src/bag_recorder_nodes/src`` directory, create a new file c

writer_->open("my_bag");

auto subscription_callback_lambda = [this](std::shared_ptr<rclcpp::SerializedMessage> msg){
rclcpp::Time time_stamp = this->now();

writer_->write(msg, "chatter", "std_msgs/msg/String", time_stamp);
};

subscription_ = create_subscription<std_msgs::msg::String>(
"chatter", 10, std::bind(&SimpleBagRecorder::topic_callback, this, _1));
"chatter", 10, subscription_callback_lambda);
}

private:
void topic_callback(std::shared_ptr<rclcpp::SerializedMessage> msg) const
{
rclcpp::Time time_stamp = this->now();

writer_->write(msg, "chatter", "std_msgs/msg/String", time_stamp);
}

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

.. code-block:: C++

auto subscription_callback_lambda = [this](std::shared_ptr<rclcpp::SerializedMessage> msg){
rclcpp::Time time_stamp = this->now();

writer_->write(msg, "chatter", "std_msgs/msg/String", time_stamp);
};

subscription_ = create_subscription<std_msgs::msg::String>(
"chatter", 10, std::bind(&SimpleBagRecorder::topic_callback, this, _1));
"chatter", 10, subscription_callback_lambda);

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

.. code-block:: C++

void topic_callback(std::shared_ptr<rclcpp::SerializedMessage> msg) const
{
auto subscription_callback_lambda = [this](std::shared_ptr<rclcpp::SerializedMessage> msg){

Within the subscription callback, the first thing to do is determine the time stamp to use for the stored message.
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.
Expand Down Expand Up @@ -349,7 +352,8 @@ Inside the ``ros2_ws/src/bag_recorder_nodes/src`` directory, create a new file c
rmw_get_serialization_format(),
""});

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

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

.. code-block:: C++

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

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.
The important difference between this and the previous sample is that the data is not yet serialised.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -266,18 +266,17 @@ Since you'll be changing the standard string msg to a numerical one, the output
: Node("minimal_publisher"), count_(0)
{
publisher_ = this->create_publisher<tutorial_interfaces::msg::Num>("topic", 10); // CHANGE
timer_ = this->create_wall_timer(
500ms, std::bind(&MinimalPublisher::timer_callback, this));

auto timer_callback = [this](){
auto message = tutorial_interfaces::msg::Num(); // CHANGE
message.num = this->count_++; // CHANGE
RCLCPP_INFO_STREAM(this->get_logger(), "Publishing: '" << message.num << "'"); // CHANGE
publisher_->publish(message);
};
timer_ = this->create_wall_timer(500ms, timer_callback);
}

private:
void timer_callback()
{
auto message = tutorial_interfaces::msg::Num(); // CHANGE
message.num = this->count_++; // CHANGE
RCLCPP_INFO_STREAM(this->get_logger(), "Publishing: '" << message.num << "'"); // CHANGE
publisher_->publish(message);
}
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Publisher<tutorial_interfaces::msg::Num>::SharedPtr publisher_; // CHANGE
size_t count_;
Expand Down Expand Up @@ -355,15 +354,14 @@ Since you'll be changing the standard string msg to a numerical one, the output
MinimalSubscriber()
: Node("minimal_subscriber")
{
auto topic_callback = [this](const tutorial_interfaces::msg::Num & msg){ // CHANGE
RCLCPP_INFO_STREAM(this->get_logger(), "I heard: '" << msg.num << "'"); // CHANGE
};
subscription_ = this->create_subscription<tutorial_interfaces::msg::Num>( // CHANGE
"topic", 10, std::bind(&MinimalSubscriber::topic_callback, this, _1));
"topic", 10, topic_callback);
}

private:
void topic_callback(const tutorial_interfaces::msg::Num & msg) const // CHANGE
{
RCLCPP_INFO_STREAM(this->get_logger(), "I heard: '" << msg.num << "'"); // CHANGE
}
rclcpp::Subscription<tutorial_interfaces::msg::Num>::SharedPtr subscription_; // CHANGE
};

Expand Down