From 2131301e4af88d9bcf4924166a9ff2abf92ec8cb Mon Sep 17 00:00:00 2001 From: ohsawa1204 Date: Wed, 17 Apr 2024 18:25:27 +0900 Subject: [PATCH 001/225] doc:change 1 Signed-off-by: ohsawa1204 --- .../coding-guidelines/ros-nodes/.pages | 1 + .../enhanced-topic-message-handling.md | 165 ++++++++++++++++++ 2 files changed, 166 insertions(+) create mode 100644 docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-message-handling.md diff --git a/docs/contributing/coding-guidelines/ros-nodes/.pages b/docs/contributing/coding-guidelines/ros-nodes/.pages index e446c5224d5..3e448deb76d 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/.pages +++ b/docs/contributing/coding-guidelines/ros-nodes/.pages @@ -8,3 +8,4 @@ nav: - parameters.md - task-scheduling.md - topic-namespaces.md + - enhanced-topic-message-handling.md \ No newline at end of file diff --git a/docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-message-handling.md b/docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-message-handling.md new file mode 100644 index 00000000000..1382b8a0d5e --- /dev/null +++ b/docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-message-handling.md @@ -0,0 +1,165 @@ +# Enhanced topic message handling guidelines + +## Introduction + +Here is coding guideline for an enhanced topic message handling method which is roughly explained in [Discussions page](https://github.com/orgs/autowarefoundation/discussions/4612). Refer to the page to understand the basic concept of the method. +There is sample source code in [ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples) referred from this document. + +## What is Subscription->take() + +### subscription callback function +As you know, ROS 2 is used as a basis of Autoware to communicate between nodes by publishing and subscription. A topic message which is received by Subscription is referred to and processed by a dedicated callback function in typical implementation using ROS 2. + +```c++ + steer_sub_ = create_subscription( + "input/steering", 1, + [this](SteeringReport::SharedPtr msg) { current_steer_ = msg->steering_tire_angle; }); +``` + +In code above, when a topic message whose name is `input/steering` is received, an anonymous function whose description is `{current_steer_ = msg->steering_tier_angle;}` is executed as a callback in a thread. The callback function is always executed when the message is received, which leads to waste computing resource if the message data is not always necessary. + +### to avoid the waste +There is an effective way to take a message using `Subscription->take()` method when it is needed. +A callback function is used to receive topic message in many of ROS 2 applications as if it is a rule or a habit. You can use `Subscription->take()` method to get a topic message without executing a callback function. +As described in [Template Class Subscription — rclcpp 16.0.8 documentation](https://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1Subscription.html#_CPPv4N6rclcpp12Subscription4takeER14ROSMessageTypeRN6rclcpp11MessageInfoE), you can use `take()` method to obtain a received message through DDS as an inter-process communication. It is no need to call a callback function when using `take() method`. +Many of ROS 2 users may feel anxious to use `take()` method because it is not used so often, but it is widely used in Executor implementation as in [rclcpp/executor.cpp](https://github.com/ros2/rclcpp/blob/47c977d1bc82fc76dd21f870bcd3ea473eca2f59/rclcpp/src/rclcpp/executor.cpp#L643-L648). Therefore you use `take()` method indirectly whether you know it or not. + +```c++ + std::shared_ptr message = subscription->create_message(); + take_and_do_error_handling( + "taking a message from topic", + subscription->get_topic_name(), + [&]() {return subscription->take_type_erased(message.get(), message_info);}, + [&]() {subscription->handle_message(message, message_info);}); +``` + +Note: Strictly speaking, `take_type_erased()` method is called in Executor implementation instead of `take()`. `take_type_erased()` is called inside of `take()`. +The body of obtaining a message from Subscription in Executor is `take_type_erased()` strictly, but we use `take()` instead for easy exaplanation. + +When Executor calls `take()` method and then a callback function, Executor itself determines when to do it. Because Executor calls a callback function with best-effort basis basically, it can occur that a message is not referred to or processed when it is needed in a node. Therefore it is desirable to call `take()` method directly **to ensue that a message is referred to or processed at the intended time.** + +Note: you can use `take()` method to obtain a message through DDS as an inter-process communication. As for an intra-process communication, you can not use it. Refer to xxx in case of intra-process communication. + +## typical scenario to use `Subscription->take()` method + +1. obtain data by calling `Subscription->take()` +2. obtain multiple data stored in Subscription Queue by multiple calls of `Subscription->take()` +3. obtain data by calling `Subscription->take` and then call a callback function which is registered at creation of subscripition +4. obtain Serialized Message from Subscription + +We will explain four scenarios above in order. + +### obtain data by calling `Subscription->take()` + +To obtain a received message of Subscription at the intended time using `take()` method of Subscription object, you need two changes below basically. + +1. prevent calling of a callback function which is registered to Subscription object when a topic message is received +2. call `take()` method of Subscription object when a topic message is needed + +You can see an example of the typical usage of `take()` method in [ros2_subscription_examples/simple_examples/src +/timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp). + +#### prevent calling a callback function + +It is needed to register a callback function to Subscription object when it is created using `create_subscritpion` even if the function will not be called. If you register `nullptr` instead of a callback function, it can not be built. +You need to use a callback group to prevent calling a callback function. +Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp). + +```c++ + rclcpp::CallbackGroup::SharedPtr cb_group_noexec = this->create_callback_group( + rclcpp::CallbackGroupType::MutuallyExclusive, false); // create callback group for not executing callback automatically + auto subscription_options = rclcpp::SubscriptionOptions(); + subscription_options.callback_group = cb_group_noexec; + rclcpp::QoS qos(rclcpp::KeepLast(10)); + if (use_transient_local) { + qos = qos.transient_local(); + } + sub_ = create_subscription("chatter", qos, not_executed_callback, subscription_options); +``` + +In code above, `cb_group_noexec` is created by calling `create_callback_group` with its second argument `false`. A callback function which belongs to the callback group will not be called by Executor. +If `callback_group` of `subscription_options` is set to `cb_group_noexec`, `not_executed_callback` which is registered to Subscription object will not be called when a corresponded topic message `chatter` is received. +The second argument of `create_callback_group` is defined as below. + +```c++ +rclcpp::CallbackGroup::SharedPtr create_callback_group(rclcpp::CallbackGroupType group_type, \ + bool automatically_add_to_executor_with_node = true) +``` + +If `automatically_add_to_executor_with_node` is set to `true`, callback functions included in a node which is added to Executor will be called automatically by Executor. + +#### call `take()` method of Subscription object + +Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp) in which `take()` method is used. + +```c++ + std_msgs::msg::String msg; + rclcpp::MessageInfo msg_info; + if (sub_->take(msg, msg_info)) { + RCLCPP_INFO(this->get_logger(), "Catch message"); + RCLCPP_INFO(this->get_logger(), "I heard: [%s]", msg.data.c_str()); +``` + +In code above, `take(msg, msg_info)` is called in a timer driven callback function by `sub_` instance which is created from Subscription class. `msg` and `msg_info` indicate a message body and meta data of it respectively. When `take(msg, msg_info)` is called, if there is a message in Subscription Queue, then the oldest message in the queue is copied to `msg`. +`take(msg, msg_info)` returns `true` if a message is received from Subscription successfully. If this is the case, a content of the message is outputted by `RCLCPP_INFO`. +`take(msg, msg_info)` returns `false` if a mesage is not received from Subscription. +When `take(msg, msg_info)` is called, if size of Subscription Queue is larger than one and there are two or more message in the queue, then the oldest message is copied to `msg`. If size of Queue is one, the latest message is always obtained. + +Note: `take()` method is irreversible in terms that a obtained message by `take()` method can not be returned to Subscription Queue. **You can determine whether a message is in Subscription Queue or not by the return alue of `take()` method, but it changes Subscription queue state.** If you want to know whether there is a message in Subscription Queue or not, you can use `rclcpp::WaitSet`. +As for `WaitSet`, refer to xxx for more detail. + +### obtain multiple data stored in Subscription Queue + +Subscription can hold multiple messages in its queue. Such messages can be obtained by consecutive calls of `take()` method from a callback function at a time. Note that in a normal manner, if there are one or more messages in Subscription Queue, the oldest one is taken and a thread is assigned to execute a callback function. If you use `take()` method, you can obtain multiple messages at a time. + +Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_batch_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_batch_listener.cpp) in which `take()` method is called consecutively. + +```c++ + std_msgs::msg::String msg; + rclcpp::MessageInfo msg_info; + while (sub_->take(msg, msg_info)) + { + RCLCPP_INFO(this->get_logger(), "Catch message"); + RCLCPP_INFO(this->get_logger(), "I heard: [%s]", msg.data.c_str()); +``` + +In code above, `while(sub->take(msg, msg_info))` continues to take messages from Subscription Queue until the queue becomes empty. While a message is taken, the message is processed each by each. +Note that you need to determine Subscription Queue size considering frequency of an invocation of a callback function and that of a reception of messages. For example, if frequency of an invocation of a callback function is 10Hz and that of a reception of messages is 50Hz, Subscription Queue size needs to be at least 5 for messages not to be lost. + +To assign a thread and let it execute a callback function each time a message is received leads to increase overhead in terms of performance. You can use the manner introduced in this section to avoid the overhead. +It is effective to use the manner if a reception of messages occurs very frequently but they need not to be processed with so high frequency. For example, if a message is received with more than 100 Hz such as CAN message, it is desirable to obtain multiple messages in a callback function at a time with one thread invocation. + +### obtain data by calling `Subscription->take` and then call a callback function + +If you want to use the manner introduced in this guideline, you may feel it is needed to implement a new funcation in which a message is taken by `take()` method and processed. But there is a way to make a callback function be called indirectly which is registered to Subscription object. +Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener_using_callback.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener_using_callback.cpp). + +```c++ + auto msg = sub_->create_message(); // auto means shared_ptr + rclcpp::MessageInfo msg_info; + if (sub_->take_type_erased(msg.get(), msg_info)) { + sub_->handle_message(msg, msg_info); + +``` + +In code above, a message is taken by `take_type_erased()` method before calling registered callback function. Note that you need to use `take_type_erased()` instead of `take()` and `take_type_erased()` needs `void` type data as its first argument. You need to use `get()` method to convert `msg` whose type is `shared_ptr` to `void` type. Then `handle_message()` method is called with the obtained message given. Registered callback function is called inside of `handle_message()`. +You need not take special care of message type which is passed to `take_type_erased()`, the same as `take_type_erased()` and `handle_message()` are not based on any specific types. You can define message variable as `auto msg = sub_->create_message();`. +You can also refer to [API document](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1SubscriptionBase.html#_CPPv4N6rclcpp16SubscriptionBase16take_type_erasedEPvRN6rclcpp11MessageInfoE) as for `create_message()`, `take_type_erased()` and `handle_message()`. + +### obtain Serialized Message from Subscription + +ROS 2 provides Serialized Message functon which supports communication with arbitrary message types as explained in [Class SerializedMessage](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1SerializedMessage.html). It is used from `topic_state_monitor` in Autoware. +You need to use `take_serialized()` method instead of `take()` method to obtain a message of Serialized Message type from Subscription object. + +Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener_serialized_message.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener_serialized_message.cpp). + +```c++ + // receive the serialized message. + rclcpp::MessageInfo msg_info; + auto msg = sub_->create_serialized_message(); // std::shared_ptr + if (sub_->take_serialized(*msg, msg_info) == false) { + return; + } +``` + +In code above, `msg` is created by `create_serialized_message()` to store a received message, whose type is `std::shared_ptr`. You can obtain a message by `take_serialized()` method. Note that `take_serialized()` method needs reference type data as its first argument therefore you need to convert `msg` type using `*`. From 093bfa73d79e988ff50500459edd470f55982801 Mon Sep 17 00:00:00 2001 From: ohsawa1204 Date: Wed, 17 Apr 2024 22:31:26 +0900 Subject: [PATCH 002/225] doc:change 2 Signed-off-by: ohsawa1204 --- .../coding-guidelines/ros-nodes/.pages | 1 - .../enhanced-topic-message-handling.md | 26 +++++++++---------- .../supp-1-intra-process-comm.md | 1 + .../enhanced-topic-handling/supp-2-waitset.md | 1 + .../supp-3-sample-code.md | 1 + 5 files changed, 16 insertions(+), 14 deletions(-) rename docs/contributing/coding-guidelines/ros-nodes/{ => enhanced-topic-handling}/enhanced-topic-message-handling.md (85%) create mode 100644 docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/supp-1-intra-process-comm.md create mode 100644 docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/supp-2-waitset.md create mode 100644 docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/supp-3-sample-code.md diff --git a/docs/contributing/coding-guidelines/ros-nodes/.pages b/docs/contributing/coding-guidelines/ros-nodes/.pages index 3e448deb76d..e446c5224d5 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/.pages +++ b/docs/contributing/coding-guidelines/ros-nodes/.pages @@ -8,4 +8,3 @@ nav: - parameters.md - task-scheduling.md - topic-namespaces.md - - enhanced-topic-message-handling.md \ No newline at end of file diff --git a/docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-message-handling.md b/docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/enhanced-topic-message-handling.md similarity index 85% rename from docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-message-handling.md rename to docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/enhanced-topic-message-handling.md index 1382b8a0d5e..95c406e9d34 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-message-handling.md +++ b/docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/enhanced-topic-message-handling.md @@ -1,14 +1,14 @@ -# Enhanced topic message handling guidelines +# Enhanced topic message handling guideline ## Introduction Here is coding guideline for an enhanced topic message handling method which is roughly explained in [Discussions page](https://github.com/orgs/autowarefoundation/discussions/4612). Refer to the page to understand the basic concept of the method. -There is sample source code in [ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples) referred from this document. +You can find sample source code in [ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples) referred from this document, which is concisely explained in [[supplement] Sample code overview](./supp-3-sample-code.md). ## What is Subscription->take() ### subscription callback function -As you know, ROS 2 is used as a basis of Autoware to communicate between nodes by publishing and subscription. A topic message which is received by Subscription is referred to and processed by a dedicated callback function in typical implementation using ROS 2. +As you know, ROS 2 is used as a basis of Autoware for communication between nodes by publishing and subscription. In a typical ROS 2 application, a topic message which is received by Subscription is referred to and processed by a dedicated callback function. ```c++ steer_sub_ = create_subscription( @@ -16,13 +16,13 @@ As you know, ROS 2 is used as a basis of Autoware to communicate between nodes b [this](SteeringReport::SharedPtr msg) { current_steer_ = msg->steering_tire_angle; }); ``` -In code above, when a topic message whose name is `input/steering` is received, an anonymous function whose description is `{current_steer_ = msg->steering_tier_angle;}` is executed as a callback in a thread. The callback function is always executed when the message is received, which leads to waste computing resource if the message data is not always necessary. +In code above, when a topic message whose name is `input/steering` is received, an anonymous function whose description is `{current_steer_ = msg->steering_tier_angle;}` is executed as a callback in a thread. The callback function is always executed when the message is received, which leads to waste computing resource if the message is not always necessary. ### to avoid the waste -There is an effective way to take a message using `Subscription->take()` method when it is needed. -A callback function is used to receive topic message in many of ROS 2 applications as if it is a rule or a habit. You can use `Subscription->take()` method to get a topic message without executing a callback function. -As described in [Template Class Subscription — rclcpp 16.0.8 documentation](https://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1Subscription.html#_CPPv4N6rclcpp12Subscription4takeER14ROSMessageTypeRN6rclcpp11MessageInfoE), you can use `take()` method to obtain a received message through DDS as an inter-process communication. It is no need to call a callback function when using `take() method`. -Many of ROS 2 users may feel anxious to use `take()` method because it is not used so often, but it is widely used in Executor implementation as in [rclcpp/executor.cpp](https://github.com/ros2/rclcpp/blob/47c977d1bc82fc76dd21f870bcd3ea473eca2f59/rclcpp/src/rclcpp/executor.cpp#L643-L648). Therefore you use `take()` method indirectly whether you know it or not. +There is an effective way to take a message using `Subscription->take()` method only when it is needed. +A callback function is used to receive a topic message in many of ROS 2 applications as if it is a rule or a habit. You can use `Subscription->take()` method to get a topic message without calling a callback function. +As described in [Template Class Subscription — rclcpp 16.0.8 documentation](https://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1Subscription.html#_CPPv4N6rclcpp12Subscription4takeER14ROSMessageTypeRN6rclcpp11MessageInfoE), you can use `take()` method to obtain a received message through DDS as an inter-process communication. It is no need to call a callback function when `take() method` is used. +Many of ROS 2 users may feel anxious to use `take()` method because they are not so familiar with it, but it is widely used in Executor implementation as in [rclcpp/executor.cpp](https://github.com/ros2/rclcpp/blob/47c977d1bc82fc76dd21f870bcd3ea473eca2f59/rclcpp/src/rclcpp/executor.cpp#L643-L648) shown below. Therefore it turns out that you use `take()` method indirectly whether you know it or not. ```c++ std::shared_ptr message = subscription->create_message(); @@ -33,14 +33,14 @@ Many of ROS 2 users may feel anxious to use `take()` method because it is not us [&]() {subscription->handle_message(message, message_info);}); ``` -Note: Strictly speaking, `take_type_erased()` method is called in Executor implementation instead of `take()`. `take_type_erased()` is called inside of `take()`. +Note: Strictly speaking, `take_type_erased()` method is called in Executor implementation instead of `take()`. The body of obtaining a message from Subscription in Executor is `take_type_erased()` strictly, but we use `take()` instead for easy exaplanation. -When Executor calls `take()` method and then a callback function, Executor itself determines when to do it. Because Executor calls a callback function with best-effort basis basically, it can occur that a message is not referred to or processed when it is needed in a node. Therefore it is desirable to call `take()` method directly **to ensue that a message is referred to or processed at the intended time.** +If Executor is programmed to call `take()` method and then a callback function, Executor itself determines when to do it. Because Executor calls a callback function with best-effort basis basically, it can occur that a message is not referred to or processed when it is needed in a node. Therefore it is desirable to call `take()` method directly **to ensue that a message is referred to or processed at the intended time.** -Note: you can use `take()` method to obtain a message through DDS as an inter-process communication. As for an intra-process communication, you can not use it. Refer to xxx in case of intra-process communication. +Note: you can use `take()` method to obtain a message through DDS as an inter-process communication. You can not use it for an intra-process communication. Refer to [[supplement] Obtain a received message through intra-process communication](./supp-1-intra-process-comm.md) in case of intra-process communication. -## typical scenario to use `Subscription->take()` method +## Typical scenario to use `Subscription->take()` method 1. obtain data by calling `Subscription->take()` 2. obtain multiple data stored in Subscription Queue by multiple calls of `Subscription->take()` @@ -106,7 +106,7 @@ In code above, `take(msg, msg_info)` is called in a timer driven callback funct When `take(msg, msg_info)` is called, if size of Subscription Queue is larger than one and there are two or more message in the queue, then the oldest message is copied to `msg`. If size of Queue is one, the latest message is always obtained. Note: `take()` method is irreversible in terms that a obtained message by `take()` method can not be returned to Subscription Queue. **You can determine whether a message is in Subscription Queue or not by the return alue of `take()` method, but it changes Subscription queue state.** If you want to know whether there is a message in Subscription Queue or not, you can use `rclcpp::WaitSet`. -As for `WaitSet`, refer to xxx for more detail. +As for `WaitSet`, refer to [[supplement] Use rclcpp::WaitSet](./supp-2-waitset.md) for more detail. ### obtain multiple data stored in Subscription Queue diff --git a/docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/supp-1-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/supp-1-intra-process-comm.md new file mode 100644 index 00000000000..18b9a56f7f8 --- /dev/null +++ b/docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/supp-1-intra-process-comm.md @@ -0,0 +1 @@ +# [supplement] Obtain a received message through intra-process communication \ No newline at end of file diff --git a/docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/supp-2-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/supp-2-waitset.md new file mode 100644 index 00000000000..8a86edf53b0 --- /dev/null +++ b/docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/supp-2-waitset.md @@ -0,0 +1 @@ +# [supplement] Use rclcpp::WaitSet diff --git a/docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/supp-3-sample-code.md b/docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/supp-3-sample-code.md new file mode 100644 index 00000000000..4b57568f6c5 --- /dev/null +++ b/docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/supp-3-sample-code.md @@ -0,0 +1 @@ +# [supplement] Sample code overview \ No newline at end of file From 6e0f248566cf00bff48f1d6a8a9205d103cb312b Mon Sep 17 00:00:00 2001 From: ohsawa1204 Date: Fri, 26 Apr 2024 13:03:42 +0900 Subject: [PATCH 003/225] doc:change 3 Signed-off-by: ohsawa1204 --- .../enhanced-topic-message-handling.md | 165 ---------------- .../supp-1-intra-process-comm.md | 1 - .../enhanced-topic-handling/supp-2-waitset.md | 1 - .../supp-3-sample-code.md | 1 - .../00-topic-message-handling.md | 184 ++++++++++++++++++ .../01-supp-intra-process-comm.md | 61 ++++++ .../topic-message-handling/02-supp-waitset.md | 130 +++++++++++++ 7 files changed, 375 insertions(+), 168 deletions(-) delete mode 100644 docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/enhanced-topic-message-handling.md delete mode 100644 docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/supp-1-intra-process-comm.md delete mode 100644 docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/supp-2-waitset.md delete mode 100644 docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/supp-3-sample-code.md create mode 100644 docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/00-topic-message-handling.md create mode 100644 docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md create mode 100644 docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md diff --git a/docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/enhanced-topic-message-handling.md b/docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/enhanced-topic-message-handling.md deleted file mode 100644 index 95c406e9d34..00000000000 --- a/docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/enhanced-topic-message-handling.md +++ /dev/null @@ -1,165 +0,0 @@ -# Enhanced topic message handling guideline - -## Introduction - -Here is coding guideline for an enhanced topic message handling method which is roughly explained in [Discussions page](https://github.com/orgs/autowarefoundation/discussions/4612). Refer to the page to understand the basic concept of the method. -You can find sample source code in [ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples) referred from this document, which is concisely explained in [[supplement] Sample code overview](./supp-3-sample-code.md). - -## What is Subscription->take() - -### subscription callback function -As you know, ROS 2 is used as a basis of Autoware for communication between nodes by publishing and subscription. In a typical ROS 2 application, a topic message which is received by Subscription is referred to and processed by a dedicated callback function. - -```c++ - steer_sub_ = create_subscription( - "input/steering", 1, - [this](SteeringReport::SharedPtr msg) { current_steer_ = msg->steering_tire_angle; }); -``` - -In code above, when a topic message whose name is `input/steering` is received, an anonymous function whose description is `{current_steer_ = msg->steering_tier_angle;}` is executed as a callback in a thread. The callback function is always executed when the message is received, which leads to waste computing resource if the message is not always necessary. - -### to avoid the waste -There is an effective way to take a message using `Subscription->take()` method only when it is needed. -A callback function is used to receive a topic message in many of ROS 2 applications as if it is a rule or a habit. You can use `Subscription->take()` method to get a topic message without calling a callback function. -As described in [Template Class Subscription — rclcpp 16.0.8 documentation](https://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1Subscription.html#_CPPv4N6rclcpp12Subscription4takeER14ROSMessageTypeRN6rclcpp11MessageInfoE), you can use `take()` method to obtain a received message through DDS as an inter-process communication. It is no need to call a callback function when `take() method` is used. -Many of ROS 2 users may feel anxious to use `take()` method because they are not so familiar with it, but it is widely used in Executor implementation as in [rclcpp/executor.cpp](https://github.com/ros2/rclcpp/blob/47c977d1bc82fc76dd21f870bcd3ea473eca2f59/rclcpp/src/rclcpp/executor.cpp#L643-L648) shown below. Therefore it turns out that you use `take()` method indirectly whether you know it or not. - -```c++ - std::shared_ptr message = subscription->create_message(); - take_and_do_error_handling( - "taking a message from topic", - subscription->get_topic_name(), - [&]() {return subscription->take_type_erased(message.get(), message_info);}, - [&]() {subscription->handle_message(message, message_info);}); -``` - -Note: Strictly speaking, `take_type_erased()` method is called in Executor implementation instead of `take()`. -The body of obtaining a message from Subscription in Executor is `take_type_erased()` strictly, but we use `take()` instead for easy exaplanation. - -If Executor is programmed to call `take()` method and then a callback function, Executor itself determines when to do it. Because Executor calls a callback function with best-effort basis basically, it can occur that a message is not referred to or processed when it is needed in a node. Therefore it is desirable to call `take()` method directly **to ensue that a message is referred to or processed at the intended time.** - -Note: you can use `take()` method to obtain a message through DDS as an inter-process communication. You can not use it for an intra-process communication. Refer to [[supplement] Obtain a received message through intra-process communication](./supp-1-intra-process-comm.md) in case of intra-process communication. - -## Typical scenario to use `Subscription->take()` method - -1. obtain data by calling `Subscription->take()` -2. obtain multiple data stored in Subscription Queue by multiple calls of `Subscription->take()` -3. obtain data by calling `Subscription->take` and then call a callback function which is registered at creation of subscripition -4. obtain Serialized Message from Subscription - -We will explain four scenarios above in order. - -### obtain data by calling `Subscription->take()` - -To obtain a received message of Subscription at the intended time using `take()` method of Subscription object, you need two changes below basically. - -1. prevent calling of a callback function which is registered to Subscription object when a topic message is received -2. call `take()` method of Subscription object when a topic message is needed - -You can see an example of the typical usage of `take()` method in [ros2_subscription_examples/simple_examples/src -/timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp). - -#### prevent calling a callback function - -It is needed to register a callback function to Subscription object when it is created using `create_subscritpion` even if the function will not be called. If you register `nullptr` instead of a callback function, it can not be built. -You need to use a callback group to prevent calling a callback function. -Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp). - -```c++ - rclcpp::CallbackGroup::SharedPtr cb_group_noexec = this->create_callback_group( - rclcpp::CallbackGroupType::MutuallyExclusive, false); // create callback group for not executing callback automatically - auto subscription_options = rclcpp::SubscriptionOptions(); - subscription_options.callback_group = cb_group_noexec; - rclcpp::QoS qos(rclcpp::KeepLast(10)); - if (use_transient_local) { - qos = qos.transient_local(); - } - sub_ = create_subscription("chatter", qos, not_executed_callback, subscription_options); -``` - -In code above, `cb_group_noexec` is created by calling `create_callback_group` with its second argument `false`. A callback function which belongs to the callback group will not be called by Executor. -If `callback_group` of `subscription_options` is set to `cb_group_noexec`, `not_executed_callback` which is registered to Subscription object will not be called when a corresponded topic message `chatter` is received. -The second argument of `create_callback_group` is defined as below. - -```c++ -rclcpp::CallbackGroup::SharedPtr create_callback_group(rclcpp::CallbackGroupType group_type, \ - bool automatically_add_to_executor_with_node = true) -``` - -If `automatically_add_to_executor_with_node` is set to `true`, callback functions included in a node which is added to Executor will be called automatically by Executor. - -#### call `take()` method of Subscription object - -Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp) in which `take()` method is used. - -```c++ - std_msgs::msg::String msg; - rclcpp::MessageInfo msg_info; - if (sub_->take(msg, msg_info)) { - RCLCPP_INFO(this->get_logger(), "Catch message"); - RCLCPP_INFO(this->get_logger(), "I heard: [%s]", msg.data.c_str()); -``` - -In code above, `take(msg, msg_info)` is called in a timer driven callback function by `sub_` instance which is created from Subscription class. `msg` and `msg_info` indicate a message body and meta data of it respectively. When `take(msg, msg_info)` is called, if there is a message in Subscription Queue, then the oldest message in the queue is copied to `msg`. -`take(msg, msg_info)` returns `true` if a message is received from Subscription successfully. If this is the case, a content of the message is outputted by `RCLCPP_INFO`. -`take(msg, msg_info)` returns `false` if a mesage is not received from Subscription. -When `take(msg, msg_info)` is called, if size of Subscription Queue is larger than one and there are two or more message in the queue, then the oldest message is copied to `msg`. If size of Queue is one, the latest message is always obtained. - -Note: `take()` method is irreversible in terms that a obtained message by `take()` method can not be returned to Subscription Queue. **You can determine whether a message is in Subscription Queue or not by the return alue of `take()` method, but it changes Subscription queue state.** If you want to know whether there is a message in Subscription Queue or not, you can use `rclcpp::WaitSet`. -As for `WaitSet`, refer to [[supplement] Use rclcpp::WaitSet](./supp-2-waitset.md) for more detail. - -### obtain multiple data stored in Subscription Queue - -Subscription can hold multiple messages in its queue. Such messages can be obtained by consecutive calls of `take()` method from a callback function at a time. Note that in a normal manner, if there are one or more messages in Subscription Queue, the oldest one is taken and a thread is assigned to execute a callback function. If you use `take()` method, you can obtain multiple messages at a time. - -Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_batch_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_batch_listener.cpp) in which `take()` method is called consecutively. - -```c++ - std_msgs::msg::String msg; - rclcpp::MessageInfo msg_info; - while (sub_->take(msg, msg_info)) - { - RCLCPP_INFO(this->get_logger(), "Catch message"); - RCLCPP_INFO(this->get_logger(), "I heard: [%s]", msg.data.c_str()); -``` - -In code above, `while(sub->take(msg, msg_info))` continues to take messages from Subscription Queue until the queue becomes empty. While a message is taken, the message is processed each by each. -Note that you need to determine Subscription Queue size considering frequency of an invocation of a callback function and that of a reception of messages. For example, if frequency of an invocation of a callback function is 10Hz and that of a reception of messages is 50Hz, Subscription Queue size needs to be at least 5 for messages not to be lost. - -To assign a thread and let it execute a callback function each time a message is received leads to increase overhead in terms of performance. You can use the manner introduced in this section to avoid the overhead. -It is effective to use the manner if a reception of messages occurs very frequently but they need not to be processed with so high frequency. For example, if a message is received with more than 100 Hz such as CAN message, it is desirable to obtain multiple messages in a callback function at a time with one thread invocation. - -### obtain data by calling `Subscription->take` and then call a callback function - -If you want to use the manner introduced in this guideline, you may feel it is needed to implement a new funcation in which a message is taken by `take()` method and processed. But there is a way to make a callback function be called indirectly which is registered to Subscription object. -Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener_using_callback.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener_using_callback.cpp). - -```c++ - auto msg = sub_->create_message(); // auto means shared_ptr - rclcpp::MessageInfo msg_info; - if (sub_->take_type_erased(msg.get(), msg_info)) { - sub_->handle_message(msg, msg_info); - -``` - -In code above, a message is taken by `take_type_erased()` method before calling registered callback function. Note that you need to use `take_type_erased()` instead of `take()` and `take_type_erased()` needs `void` type data as its first argument. You need to use `get()` method to convert `msg` whose type is `shared_ptr` to `void` type. Then `handle_message()` method is called with the obtained message given. Registered callback function is called inside of `handle_message()`. -You need not take special care of message type which is passed to `take_type_erased()`, the same as `take_type_erased()` and `handle_message()` are not based on any specific types. You can define message variable as `auto msg = sub_->create_message();`. -You can also refer to [API document](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1SubscriptionBase.html#_CPPv4N6rclcpp16SubscriptionBase16take_type_erasedEPvRN6rclcpp11MessageInfoE) as for `create_message()`, `take_type_erased()` and `handle_message()`. - -### obtain Serialized Message from Subscription - -ROS 2 provides Serialized Message functon which supports communication with arbitrary message types as explained in [Class SerializedMessage](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1SerializedMessage.html). It is used from `topic_state_monitor` in Autoware. -You need to use `take_serialized()` method instead of `take()` method to obtain a message of Serialized Message type from Subscription object. - -Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener_serialized_message.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener_serialized_message.cpp). - -```c++ - // receive the serialized message. - rclcpp::MessageInfo msg_info; - auto msg = sub_->create_serialized_message(); // std::shared_ptr - if (sub_->take_serialized(*msg, msg_info) == false) { - return; - } -``` - -In code above, `msg` is created by `create_serialized_message()` to store a received message, whose type is `std::shared_ptr`. You can obtain a message by `take_serialized()` method. Note that `take_serialized()` method needs reference type data as its first argument therefore you need to convert `msg` type using `*`. diff --git a/docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/supp-1-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/supp-1-intra-process-comm.md deleted file mode 100644 index 18b9a56f7f8..00000000000 --- a/docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/supp-1-intra-process-comm.md +++ /dev/null @@ -1 +0,0 @@ -# [supplement] Obtain a received message through intra-process communication \ No newline at end of file diff --git a/docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/supp-2-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/supp-2-waitset.md deleted file mode 100644 index 8a86edf53b0..00000000000 --- a/docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/supp-2-waitset.md +++ /dev/null @@ -1 +0,0 @@ -# [supplement] Use rclcpp::WaitSet diff --git a/docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/supp-3-sample-code.md b/docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/supp-3-sample-code.md deleted file mode 100644 index 4b57568f6c5..00000000000 --- a/docs/contributing/coding-guidelines/ros-nodes/enhanced-topic-handling/supp-3-sample-code.md +++ /dev/null @@ -1 +0,0 @@ -# [supplement] Sample code overview \ No newline at end of file diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/00-topic-message-handling.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/00-topic-message-handling.md new file mode 100644 index 00000000000..e25c84889db --- /dev/null +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/00-topic-message-handling.md @@ -0,0 +1,184 @@ +# Topic message handling guideline + +## Introduction + +Here is coding guideline for a topic message handling method which includes more enhanced method than usually used one, which is roughly explained in [Discussions page](https://github.com/orgs/autowarefoundation/discussions/4612). Refer to the page to understand the basic concept of the enhanced method. +You can find sample source code in [ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples) referred from this document. + +## Typical message handling method usually used + +At first, let us see a typical message handling method usually used currently. +In a typical ROS 2 application, a topic message which is received by Subscription is referred to and processed by a dedicated callback function. + +```c++ + steer_sub_ = create_subscription( + "input/steering", 1, + [this](SteeringReport::SharedPtr msg) { current_steer_ = msg->steering_tire_angle; }); +``` + +In code above, when a topic message whose name is `input/steering` is received, an anonymous function whose description is `{current_steer_ = msg->steering_tier_angle;}` is executed as a callback in a thread. The callback function is always executed when the message is received, which leads to waste computing resource if the message is not always necessary. Besides, it costs thread-wakeup overhread just to take a message. + +## Enhanced method + +There is an enhanced method to take a message using `Subscription->take()` method only when it is needed. +Here is a sample code to use `Subscription->take()` method executed as a timer or subscription callback to perform a main logic. +In this case, a topic message is not taken by a subscription callback. To be exact, you need to program your code so that a callback function is not called automatically. + +```c++ + SteeringReport::SharedPtr msg; + rclcpp::MessageInfo msg_info; + if (sub_->take(msg, msg_info)) { + // processing and publishing after this +``` + +By using this manner, following advantages are achieved. + +* it can reduce invocations of subscription callback functions which is relatively expensive +* there is no need to take topic message data which are not read +* there is no need of exclusive lock between a subscription callback thread and a timer callback thread + +## Methods to handle topic message data + +We will explain four methods including the enhanced method. + +### 1. obtain data by calling `Subscription->take()` + +To use the enhanced method using `Subscription->take()`, you need to do two things below basically. + +1. prevent calling a callback function when a topic message is received +1. call `take()` method of Subscription object when a topic message is needed + +You can see an example of the typical usage of `take()` method in [ros2_subscription_examples/simple_examples/src +/timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp). + +#### prevent calling a callback function + +It is needed to create a Subscription object with a callback group which makes registered callback functions not called automtically. +Note that it is needed to register a callback function to Subscription object even if the function will not be called. If you register `nullptr` instead of a callback function, it can not be built. +Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp). + +```c++ + rclcpp::CallbackGroup::SharedPtr cb_group_noexec = this->create_callback_group( + rclcpp::CallbackGroupType::MutuallyExclusive, false); // create callback group for not executing callback automatically + auto subscription_options = rclcpp::SubscriptionOptions(); + subscription_options.callback_group = cb_group_noexec; + rclcpp::QoS qos(rclcpp::KeepLast(10)); + if (use_transient_local) { + qos = qos.transient_local(); + } + sub_ = create_subscription("chatter", qos, not_executed_callback, subscription_options); +``` + +In code above, `cb_group_noexec` is created by calling `create_callback_group` with its second argument `false`. A callback function which belongs to the callback group will not be called by Executor. +If `callback_group` member of `subscription_options` is set to `cb_group_noexec`, `not_executed_callback` will not be called when a corresponded topic message `chatter` is received. +The second argument of `create_callback_group` is defined as below. + +```c++ +rclcpp::CallbackGroup::SharedPtr create_callback_group(rclcpp::CallbackGroupType group_type, \ + bool automatically_add_to_executor_with_node = true) +``` + +If `automatically_add_to_executor_with_node` is set to `true`, callback functions included in a node which is added to Executor will be called automatically by Executor. + +#### call `take()` method of Subscription object + +Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp) in which `take()` method is used. + +```c++ + std_msgs::msg::String msg; + rclcpp::MessageInfo msg_info; + if (sub_->take(msg, msg_info)) { + RCLCPP_INFO(this->get_logger(), "Catch message"); + RCLCPP_INFO(this->get_logger(), "I heard: [%s]", msg.data.c_str()); +``` + +In code above, `take(msg, msg_info)` is called in a timer driven callback function by `sub_` instance which is created from Subscription class. `msg` and `msg_info` indicate a message body and meta data of it respectively. When `take(msg, msg_info)` is called, if there is a message in Subscription Queue, then the message is copied to `msg`. +`take(msg, msg_info)` returns `true` if a message is received from Subscription successfully. In this case, a content of the message is outputted by `RCLCPP_INFO`. +`take(msg, msg_info)` returns `false` if a mesage is not received from Subscription. +When `take(msg, msg_info)` is called, if the size of Subscription Queue is larger than one and there are two or more messages in the queue, then the oldest message is copied to `msg`. If the size of Queue is one, the latest message is always obtained. + +Note 1. `take()` method is irreversible in terms that a obtained message by `take()` method can not be returned to Subscription Queue. **You can determine whether a message is in Subscription Queue or not by the return value of `take()` method, but it changes Subscription queue state.** If you want to know whether there is a message in Subscription Queue or not, you can use `rclcpp::WaitSet`. +Refer to [[supplement] Use rclcpp::WaitSet](./02-supp-waitset.md) for more detail. + +Note 2. You can use `take()` method to obtain a message which is passed through DDS as an inter-process communication. You can not use it for an intra-process communication. Refer to [[supplement] Obtain a received message through intra-process communication](./01-supp-intra-process-comm.md) in case of intra-process communication. + +#### 1.1 obtain Serialized Message from Subscription + +ROS 2 provides Serialized Message functon which supports communication with arbitrary message types as explained in [Class SerializedMessage](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1SerializedMessage.html). It is used by `topic_state_monitor` in Autoware. +You need to use `take_serialized()` method instead of `take()` method to obtain a message of Serialized Message type from Subscription object. + +Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener_serialized_message.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener_serialized_message.cpp). + +```c++ + // receive the serialized message. + rclcpp::MessageInfo msg_info; + auto msg = sub_->create_serialized_message(); // std::shared_ptr + if (sub_->take_serialized(*msg, msg_info) == false) { + return; + } +``` + +In code above, `msg` is created by `create_serialized_message()` to store a received message, whose type is `std::shared_ptr`. You can obtain a message of Serialized Message type by `take_serialized()` method. Note that `take_serialized()` method needs reference type data as its first argument therefore you need to convert `msg` type using `*`. + +### 2. obtain multiple data stored in Subscription Queue + +Subscription can hold multiple messages in its queue. Such messages can be obtained by consecutive calls of `take()` method from a callback function at a time. Note that in a normal manner in which a callback function is used to take a topic message, if there are one or more messages in Subscription Queue, the oldest one is taken and a thread is assigned to execute a callback function until the queue becomes empty. If you use `take()` method, you can obtain multiple messages at a time. + +Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_batch_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_batch_listener.cpp) in which `take()` method is called consecutively. + +```c++ + std_msgs::msg::String msg; + rclcpp::MessageInfo msg_info; + while (sub_->take(msg, msg_info)) + { + RCLCPP_INFO(this->get_logger(), "Catch message"); + RCLCPP_INFO(this->get_logger(), "I heard: [%s]", msg.data.c_str()); +``` + +In code above, `while(sub->take(msg, msg_info))` continues to take messages from Subscription Queue until the queue becomes empty. While a message is taken, the message is processed each by each. +Note that you need to determine Subscription Queue size considering frequency of an invocation of a callback function and that of a reception of messages. For example, if frequency of an invocation of a callback function is 10Hz and that of a reception of messages is 50Hz, Subscription Queue size needs to be at least 5 for messages not to be lost. + +To assign a thread and let it execute a callback function each time a message is received leads to increase overhead in terms of performance. You can use the method introduced in this section to avoid the overhead. +It is effective to use the method if a reception of messages occurs very frequently but they don't need to be processed with so high frequency. For example, if a message is received with more than 100 Hz such as CAN message, it is desirable to obtain multiple messages in a callback function at a time with one thread invocation. + +### 3. obtain data by calling `Subscription->take` and then call a callback function + +If you want to use the enhanced method introduced in this guideline, you may feel it is needed to implement a new funcation in which a message is taken by `take()` method and then processed. But there is a way to make a callback function be called indirectly which is registered to Subscription object. +Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener_using_callback.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener_using_callback.cpp). + +```c++ + auto msg = sub_->create_message(); // auto means shared_ptr + rclcpp::MessageInfo msg_info; + if (sub_->take_type_erased(msg.get(), msg_info)) { + sub_->handle_message(msg, msg_info); + +``` + +In code above, a message is taken by `take_type_erased()` method before calling registered callback function. Note that you need to use `take_type_erased()` instead of `take()` and `take_type_erased()` needs `void` type data as its first argument. You need to use `get()` method to convert `msg` whose type is `shared_ptr` to `void` type. Then `handle_message()` method is called with the obtained message. Registered callback function is called inside of `handle_message()`. +You don't need to take special care of message type which is passed to `take_type_erased()`, the same as `take_type_erased()` and `handle_message()` are not based on any specific types. You can define message variable as `auto msg = sub_->create_message();`. +You can also refer to [API document](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1SubscriptionBase.html#_CPPv4N6rclcpp16SubscriptionBase16take_type_erasedEPvRN6rclcpp11MessageInfoE) as for `create_message()`, `take_type_erased()` and `handle_message()`. + +### 4. obtain data by a callback function + +A typical method usually used currently is also usable. If you don't use a callback group with `automatically_add_to_executor_with_node = false`, a registered callback function is called automatically by Executor when a topic message is received. +One of advantages of this method is you don't need to take care that a topic message is passed through inter-process or itra-process. Remind that in the enhanced method, `take()` can only be used in case of inter-process communication while `take_type_erased()` needs to be used in case of intra-process communication. + +## Appendix + +A callback function is used to obtain a topic message in many of ROS 2 applications as if it is a rule or a custom. As we have seen, you can use `Subscription->take()` method to obtain a topic message without calling a callback function. +This method is also documented in [Template Class Subscription — rclcpp 16.0.8 documentation](https://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1Subscription.html#_CPPv4N6rclcpp12Subscription4takeER14ROSMessageTypeRN6rclcpp11MessageInfoE). +Many of ROS 2 users may feel anxious to use `take()` method because they may not be so familiar with it, but it is widely used in Executor implementation as in [rclcpp/executor.cpp](https://github.com/ros2/rclcpp/blob/47c977d1bc82fc76dd21f870bcd3ea473eca2f59/rclcpp/src/rclcpp/executor.cpp#L643-L648) shown below. Therefore it turns out that you use `take()` method indirectly whether you know it or not. + +```c++ + std::shared_ptr message = subscription->create_message(); + take_and_do_error_handling( + "taking a message from topic", + subscription->get_topic_name(), + [&]() {return subscription->take_type_erased(message.get(), message_info);}, + [&]() {subscription->handle_message(message, message_info);}); +``` + +Note: Strictly speaking, `take_type_erased()` method is called in Executor implementation instead of `take()`. +But `take_type_erased()` is called inside of `take()`. + +If Executor is programmed to call a callback function, Executor itself determines when to do it. Because Executor calls a callback function with best-effort basis basically, it can occur that a message is not referred to or processed when it is needed in a node. Therefore it is desirable to call `take()` method directly **to ensue that a message is referred to or processed at the intended time.** diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md new file mode 100644 index 00000000000..fbf7bd55106 --- /dev/null +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -0,0 +1,61 @@ +# [supplement] Obtain a received message through intra-process communication + +## Topic message handling in intra-process communication + +rlcpp supports intra-process communication. As explained in [Topic message handling guideline](00-topic-message-handling.md), `take()` method of Subscription can not be used in case of intra-process communication. `take()` can not obtain a topic message which is received through inter-process communication. Besides, even though a method is provided to obtain a received topic message through intra-process communication, a method is not provided to refer to the message. +But a method are provided for intra-process communication similar to a method for inter-process communication described in [obtain data by calling Subscription->take and then call a callback function](./00-topic-message-handling/#3-obtain-data-by-calling-subscription-take-and-then-call-a-callback-function). +`take_data()` method is provided to obtain a received data in case of intra-process communication and the received data must be processed through `execute()` method. +Refer to [Template Class SubscriptionIntraProcess — rclcpp 16.0.8 documentation](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1experimental_1_1SubscriptionIntraProcess.html#_CPPv4N6rclcpp12experimental24SubscriptionIntraProcess9take_dataEv) for `take_data()` and `execute()` for more detail. + +## coding method + +Call `take_data()` method and then `execute()` method as below. + +```c++ +// Execute any entities of the Waitable that may be ready +std::shared_ptr data = waitable.take_data(); +waitable.execute(data); +``` + +Here is a sample program in [ros2_subscription_examples/intra_process_talker_listener/src/timer_listener_intra_process.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/intra_process_talker_listener/src/timer_listener_intra_process.cpp). +You can run the program as below. If you set `false` to `use_intra_process_comms`, inter-process communication is performed. + +``` +ros2 intra_process_talker_listener talker_listener_intra_process.launch.py use_intra_process_comms:=true +``` + +Here is a excerption from [ros2_subscription_examples/intra_process_talker_listener/src/timer_listener_intra_process.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/intra_process_talker_listener/src/timer_listener_intra_process.cpp). + +```c++ + // check if intra-process communication is enabled. + if (this->get_node_options().use_intra_process_comms()){ + // get the intra-process subscription's waitable. + auto intra_process_sub = sub_->get_intra_process_waitable(); + // check if the waitable has data. + if (intra_process_sub->is_ready(nullptr) == true) { + // take the data and execute the callback. + std::shared_ptr data = intra_process_sub->take_data(); + RCLCPP_INFO(this->get_logger(), " Intra-process communication is performed."); + // execute the callback. + intra_process_sub->execute(data); +``` +Below is explanation of above code one line by one. + +* `if (this->get_node_options().use_intra_process_comms()){` + - verify intra-process communication is enabled or not by using NodeOptions + +* `auto intra_process_sub = sub_->get_intra_process_waitable();` + - get an object which is used by Subscription in case of intra-process communication + +* `if (intra_process_sub->is_ready(nullptr) == true) {` + - check if a message has already been received through intra-process communication + - the argument of `is_ready()` is of rcl_wait_set_t type, but because the argument is not used inside `is_ready()`, `nullptr` is used tentatively + - using `nullptr` is a workaround at this point of time, because it is not preferable + +* `std::shared_ptr data = intra_process_sub->take_data();` + - obtain a topic message + - `intra_process_sub->take_data();` does not return Boolean value which indicates a message is received successfully or not, therefore need to verify it by calling `is_ready()` in advance + +* `intra_process_sub->execute(data);` + - a callback function corresponded to the received message is called inside `execute()` + - the callback function is executed by the thread which executes `execute()` without context switch diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md new file mode 100644 index 00000000000..c6c543b5e98 --- /dev/null +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md @@ -0,0 +1,130 @@ +# [supplement] Use rclcpp::WaitSet + +## What is `rclcpp::WaitSet` + +As explained in [call take() method of Subscription object](./00-topic-message-handling/#call-take-method-of-subscription-object), `take()` method is irreversible. Once `take()` method is executed, Subscription object state changes and undo can not be applied, therefore Subscription object can not be restored to previous state. You can use `rclcpp::WaitSet` to call `take()` after verifying there is a received message in Subscription Queue. +Here is a sample code. `wait_set_.wait()` tells you that a message has already been received and can be obtained by `take()`. + +```c++ + auto wait_result = wait_set_.wait(std::chrono::milliseconds(0)); + if (wait_result.kind() == rclcpp::WaitResultKind::Ready && + wait_result.get_wait_set().get_rcl_wait_set().subscriptions[0]) { + sub_->take(msg, msg_info); + RCLCPP_INFO(this->get_logger(), "Catch message"); + RCLCPP_INFO(this->get_logger(), "I heard: [%s]", msg.data.c_str()); +``` + +Also you can verify that there are messages in multiple Subscription Queues in advance. +If your code needs to proceed after several types of messages got together, using `rclcpp::WaitSet` is prefarable. + +```c++ + auto wait_result = wait_set_.wait(std::chrono::milliseconds(0)); + bool received_all_messages = false; + if (wait_result.kind() == rclcpp::WaitResultKind::Ready) { + for (auto wait_set_subs : wait_result.get_wait_set().get_rcl_wait_set().subscriptions) { + if (!wait_set_subs) { + RCLCPP_INFO_THROTTLE(get_logger(), clock, 5000, "Waiting for data..."); + return {}; + } + } + received_all_mesages = true; + } +``` + +In code above, unless `rclcpp::WaitSet` is used, it is difficult to verify that all needed messages got together. + +## Coding method + +We will explain coding method of `rclcpp::WaitSet` using a sample code in [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp). + +* [ros2_subscription_examples/waitset_examples/src/talker_triple.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/talker_triple.cpp) + - it publishes `/chatter` per one second, `/slower_chatter` per two seconds, and `/slowest_chatter` per three seconds periodically +* [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp) + - it queries `WaitSet` per one second and if there is a message available, it obtains the message by `take()` + - it has each subscription for `/chatter` `/slower_chatter`, and `/slower_chatter` + +Following three steps are needed to use `WaitSet`. + +### 1. declare and initialize `WaitSet` + +You need to declare WaitSet variable first to use. +Below is excerption from [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp). + +```c++ +rclcpp::WaitSet wait_set_; +``` + +Note that there are three types of `WaitSet` as below. + +* [Typedef rclcpp::WaitSet](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1ad6fb19c154de27e92430309d2da25ac3.html) + - Subscription, Timer, and so on can be registered to WaitSet at any time +* [Typedef rclcpp::ThreadSafeWaitSet](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1acaec573e71549fd3078644e18e7f7127.html) + - Subscription, Timer, ans so on can be registered to WaitSet only in thread-safe state + - sample code is here: [examples/rclcpp/wait_set/src/thread_safe_wait_set.cpp at rolling · ros2/examples](https://github.com/ros2/examples/blob/rolling/rclcpp/wait_set/src/thread_safe_wait_set.cpp) +* [Typedef rclcpp::StaticWaitSet](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1adb06acf4a5723b1445fa6ed4e8f73374.html) + - Subscription, Timer, and so on can be registered to WaitSet only at initialization + - here are sample codes: + - [ros2_subscription_examples/waitset_examples/src/timer_listener_twin_static.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_twin_static.cpp) + - [examples/rclcpp/wait_set/src/static_wait_set.cpp at rolling · ros2/examples](https://github.com/ros2/examples/blob/rolling/rclcpp/wait_set/src/static_wait_set.cpp) + +### 2. register trigger (Subscription, Timer, and so on) to `WaitSet` + +You need to register a trigger to `WaitSet`. +Below is excerption from [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp) + +```c++ + subscriptions_array_[0] = create_subscription("chatter", qos, not_executed_callback, subscription_options); + subscriptions_array_[1] = create_subscription("slower_chatter", qos, not_executed_callback, subscription_options); + subscriptions_array_[2] = create_subscription("slowest_chatter", qos, not_executed_callback, subscription_options); + // Add subscription to waitset + for (auto & subscription : subscriptions_array_) { + wait_set_.add_subscription(subscription); + } +``` + +In code above, created subscriptions are registered to `WaitSet` by `add_subscription()`. +You can also register another type of trigger to WaitSet by which a callback function registered to Subscription is invoked, such as Timer, Service, or Action. +A sample code to register Timer trigger is here. + +```c++ +wait_set_.add_timer(much_slower_timer_); +``` + +A trigger can be registered at declaration and initialization as [https://github.com/ros2/examples/blob/rolling/rclcpp/wait_set/src/wait_set_topics_and_timer.cpp#L66](https://github.com/ros2/examples/blob/rolling/rclcpp/wait_set/src/wait_set_topics_and_timer.cpp#L66). + +### 3. verify WaitSet result + +You can see WaitSet result by doing 1 below first and then 2 below. + +1. verifying if any trigger has been invoked +2. verifying if specified trigger has been invoked + +As for 1, here is a sample code excerpted from [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp). + +```c++ + auto wait_result = wait_set_.wait(std::chrono::milliseconds(0)); + if (wait_result.kind() == rclcpp::WaitResultKind::Ready) { + RCLCPP_INFO(this->get_logger(), "wait_set tells that some subscription is ready"); + } else { + RCLCPP_INFO(this->get_logger(), "wait_set tells that any subscription is not ready and return"); + return; + } +``` + +In code above, it is verified whether any trigger has been invoked which is registered to `wait_set_` by `auto wait_result = wait_set_.wait(std::chrono::milliseconds(0));`. +if `wait_result.kind() == rclcpp::WaitResultKind::Ready` is `true`, it indicates any trigger has been invoked. + +As for 2, here is a sample code excerpted from [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp). + +```c++ + for (size_t i = 0; i < subscriptions_num; i++) { + if (wait_result.get_wait_set().get_rcl_wait_set().subscriptions[i]) { + std_msgs::msg::String msg; + rclcpp::MessageInfo msg_info; + if (subscriptions_array_[i]->take(msg, msg_info)) { + RCLCPP_INFO(this->get_logger(), "Catch message via subscription[%ld]", i); + RCLCPP_INFO(this->get_logger(), "I heard: [%s]", msg.data.c_str()); +``` + +In code above, `wait_result.get_wait_set().get_rcl_wait_set().subscriptions[i]` indicates whether each individual trigger has been invoked or not. The result was stored to `subscriptions` array. The order in `subscriptions` array is the same as the order in which triggers are registered. + From ff3014d9503cb2c293484c64df551d53508b1975 Mon Sep 17 00:00:00 2001 From: ohsawa1204 Date: Tue, 30 Apr 2024 00:41:51 +0900 Subject: [PATCH 004/225] doc:change 4 Signed-off-by: ohsawa1204 --- .../00-topic-message-handling.md | 33 ++++++++++--------- .../01-supp-intra-process-comm.md | 13 +++++--- .../topic-message-handling/02-supp-waitset.md | 15 +++++---- 3 files changed, 35 insertions(+), 26 deletions(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/00-topic-message-handling.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/00-topic-message-handling.md index e25c84889db..7c76a955c27 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/00-topic-message-handling.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/00-topic-message-handling.md @@ -3,11 +3,11 @@ ## Introduction Here is coding guideline for a topic message handling method which includes more enhanced method than usually used one, which is roughly explained in [Discussions page](https://github.com/orgs/autowarefoundation/discussions/4612). Refer to the page to understand the basic concept of the enhanced method. -You can find sample source code in [ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples) referred from this document. +You can find sample source codes in [ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples) referred from this document. ## Typical message handling method usually used -At first, let us see a typical message handling method usually used currently. +At first, let us see a typical message handling method usually used. In a typical ROS 2 application, a topic message which is received by Subscription is referred to and processed by a dedicated callback function. ```c++ @@ -22,7 +22,7 @@ In code above, when a topic message whose name is `input/steering` is received, There is an enhanced method to take a message using `Subscription->take()` method only when it is needed. Here is a sample code to use `Subscription->take()` method executed as a timer or subscription callback to perform a main logic. -In this case, a topic message is not taken by a subscription callback. To be exact, you need to program your code so that a callback function is not called automatically. +In this case, a topic message is not obtained by a subscription callback. To be exact, you need to program your code so that a callback function is not called automatically. ```c++ SteeringReport::SharedPtr msg; @@ -34,7 +34,7 @@ In this case, a topic message is not taken by a subscription callback. To be exa By using this manner, following advantages are achieved. * it can reduce invocations of subscription callback functions which is relatively expensive -* there is no need to take topic message data which are not read +* there is no need to take a topic message which is not read * there is no need of exclusive lock between a subscription callback thread and a timer callback thread ## Methods to handle topic message data @@ -59,13 +59,15 @@ Here is a sample code excerpted from [ros2_subscription_examples/simple_example ```c++ rclcpp::CallbackGroup::SharedPtr cb_group_noexec = this->create_callback_group( - rclcpp::CallbackGroupType::MutuallyExclusive, false); // create callback group for not executing callback automatically + rclcpp::CallbackGroupType::MutuallyExclusive, false); auto subscription_options = rclcpp::SubscriptionOptions(); subscription_options.callback_group = cb_group_noexec; + rclcpp::QoS qos(rclcpp::KeepLast(10)); if (use_transient_local) { qos = qos.transient_local(); } + sub_ = create_subscription("chatter", qos, not_executed_callback, subscription_options); ``` @@ -93,7 +95,7 @@ Here is a sample code excerpted from [ros2_subscription_examples/simple_example ``` In code above, `take(msg, msg_info)` is called in a timer driven callback function by `sub_` instance which is created from Subscription class. `msg` and `msg_info` indicate a message body and meta data of it respectively. When `take(msg, msg_info)` is called, if there is a message in Subscription Queue, then the message is copied to `msg`. -`take(msg, msg_info)` returns `true` if a message is received from Subscription successfully. In this case, a content of the message is outputted by `RCLCPP_INFO`. +`take(msg, msg_info)` returns `true` if a message is received from Subscription successfully. In this case in code above, a content of the message is outputted by `RCLCPP_INFO`. `take(msg, msg_info)` returns `false` if a mesage is not received from Subscription. When `take(msg, msg_info)` is called, if the size of Subscription Queue is larger than one and there are two or more messages in the queue, then the oldest message is copied to `msg`. If the size of Queue is one, the latest message is always obtained. @@ -112,7 +114,8 @@ Here is a sample code excerpted from [ros2_subscription_examples/simple_examples ```c++ // receive the serialized message. rclcpp::MessageInfo msg_info; - auto msg = sub_->create_serialized_message(); // std::shared_ptr + auto msg = sub_->create_serialized_message(); + if (sub_->take_serialized(*msg, msg_info) == false) { return; } @@ -122,7 +125,7 @@ In code above, `msg` is created by `create_serialized_message()` to store a rece ### 2. obtain multiple data stored in Subscription Queue -Subscription can hold multiple messages in its queue. Such messages can be obtained by consecutive calls of `take()` method from a callback function at a time. Note that in a normal manner in which a callback function is used to take a topic message, if there are one or more messages in Subscription Queue, the oldest one is taken and a thread is assigned to execute a callback function until the queue becomes empty. If you use `take()` method, you can obtain multiple messages at a time. +Subscription can hold multiple messages in its queue. Such messages can be obtained by consecutive calls of `take()` method from a callback function at a time. Note that in a normal manner in which a subscription callback function is used to take a topic message, if there are one or more messages in Subscription Queue, the oldest one is taken and a thread is assigned to execute a callback function, which continues until the queue becomes empty. If you use `take()` method, you can obtain multiple messages at a time. Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_batch_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_batch_listener.cpp) in which `take()` method is called consecutively. @@ -136,10 +139,10 @@ Here is a sample code excerpted from [ros2_subscription_examples/simple_example ``` In code above, `while(sub->take(msg, msg_info))` continues to take messages from Subscription Queue until the queue becomes empty. While a message is taken, the message is processed each by each. -Note that you need to determine Subscription Queue size considering frequency of an invocation of a callback function and that of a reception of messages. For example, if frequency of an invocation of a callback function is 10Hz and that of a reception of messages is 50Hz, Subscription Queue size needs to be at least 5 for messages not to be lost. +Note that you need to determine Subscription Queue size considering frequency of an invocation of a callback function and that of a reception of message. For example, if frequency of an invocation of a callback function is 10Hz and that of a reception of message is 50Hz, Subscription Queue size needs to be at least 5 for messages not to be lost. To assign a thread and let it execute a callback function each time a message is received leads to increase overhead in terms of performance. You can use the method introduced in this section to avoid the overhead. -It is effective to use the method if a reception of messages occurs very frequently but they don't need to be processed with so high frequency. For example, if a message is received with more than 100 Hz such as CAN message, it is desirable to obtain multiple messages in a callback function at a time with one thread invocation. +It is effective to use the method if a reception of message occurs very frequently but it doesn't need to be processed with so high frequency. For example, if a message is received with more than 100 Hz such as CAN message, it is desirable to obtain multiple messages in a callback function at a time with one thread invocation. ### 3. obtain data by calling `Subscription->take` and then call a callback function @@ -147,25 +150,25 @@ If you want to use the enhanced method introduced in this guideline, you may fee Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener_using_callback.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener_using_callback.cpp). ```c++ - auto msg = sub_->create_message(); // auto means shared_ptr + auto msg = sub_->create_message(); rclcpp::MessageInfo msg_info; if (sub_->take_type_erased(msg.get(), msg_info)) { sub_->handle_message(msg, msg_info); ``` -In code above, a message is taken by `take_type_erased()` method before calling registered callback function. Note that you need to use `take_type_erased()` instead of `take()` and `take_type_erased()` needs `void` type data as its first argument. You need to use `get()` method to convert `msg` whose type is `shared_ptr` to `void` type. Then `handle_message()` method is called with the obtained message. Registered callback function is called inside of `handle_message()`. +In code above, a message is taken by `take_type_erased()` method before calling a registered callback function. Note that you need to use `take_type_erased()` instead of `take()` and that `take_type_erased()` needs `void` type data as its first argument. You need to use `get()` method to convert `msg` whose type is `shared_ptr` to `void` type. Then `handle_message()` method is called with the obtained message. A registered callback function is called inside of `handle_message()`. You don't need to take special care of message type which is passed to `take_type_erased()`, the same as `take_type_erased()` and `handle_message()` are not based on any specific types. You can define message variable as `auto msg = sub_->create_message();`. You can also refer to [API document](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1SubscriptionBase.html#_CPPv4N6rclcpp16SubscriptionBase16take_type_erasedEPvRN6rclcpp11MessageInfoE) as for `create_message()`, `take_type_erased()` and `handle_message()`. ### 4. obtain data by a callback function -A typical method usually used currently is also usable. If you don't use a callback group with `automatically_add_to_executor_with_node = false`, a registered callback function is called automatically by Executor when a topic message is received. -One of advantages of this method is you don't need to take care that a topic message is passed through inter-process or itra-process. Remind that in the enhanced method, `take()` can only be used in case of inter-process communication while `take_type_erased()` needs to be used in case of intra-process communication. +A typical method usually used is also usable, by which a message is obtained in subscription callback function . If you don't use a callback group with `automatically_add_to_executor_with_node = false`, a registered callback function is called automatically by Executor when a topic message is received. +One of advantages of this method is you don't need to take care whether a topic message is passed through inter-process or itra-process. Remind that in the enhanced method, `take()` can only be used in case of inter-process communication while `take_type_erased()` needs to be used in case of intra-process communication. ## Appendix -A callback function is used to obtain a topic message in many of ROS 2 applications as if it is a rule or a custom. As we have seen, you can use `Subscription->take()` method to obtain a topic message without calling a callback function. +A callback function is used to obtain a topic message in many of ROS 2 applications as if it is a rule or a custom. As we have seen, you can use `Subscription->take()` method to obtain a topic message without calling a subscription callback function. This method is also documented in [Template Class Subscription — rclcpp 16.0.8 documentation](https://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1Subscription.html#_CPPv4N6rclcpp12Subscription4takeER14ROSMessageTypeRN6rclcpp11MessageInfoE). Many of ROS 2 users may feel anxious to use `take()` method because they may not be so familiar with it, but it is widely used in Executor implementation as in [rclcpp/executor.cpp](https://github.com/ros2/rclcpp/blob/47c977d1bc82fc76dd21f870bcd3ea473eca2f59/rclcpp/src/rclcpp/executor.cpp#L643-L648) shown below. Therefore it turns out that you use `take()` method indirectly whether you know it or not. diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index fbf7bd55106..b74b9fc9210 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -2,8 +2,8 @@ ## Topic message handling in intra-process communication -rlcpp supports intra-process communication. As explained in [Topic message handling guideline](00-topic-message-handling.md), `take()` method of Subscription can not be used in case of intra-process communication. `take()` can not obtain a topic message which is received through inter-process communication. Besides, even though a method is provided to obtain a received topic message through intra-process communication, a method is not provided to refer to the message. -But a method are provided for intra-process communication similar to a method for inter-process communication described in [obtain data by calling Subscription->take and then call a callback function](./00-topic-message-handling/#3-obtain-data-by-calling-subscription-take-and-then-call-a-callback-function). +rlcpp supports intra-process communication. As explained in [Topic message handling guideline](00-topic-message-handling.md), `take()` method of Subscription can not be used in case of intra-process communication. `take()` can not obtain a topic message which is received through inter-process communication. Besides, even though a method is provided to obtain a received topic message through intra-process communication, a method is not provided to refer to the message directly. +But a method are provided for intra-process communication similar to a method for inter-process communication described in [obtain data by calling Subscription->take and then call a callback function](../00-topic-message-handling/#3-obtain-data-by-calling-subscription-take-and-then-call-a-callback-function). `take_data()` method is provided to obtain a received data in case of intra-process communication and the received data must be processed through `execute()` method. Refer to [Template Class SubscriptionIntraProcess — rclcpp 16.0.8 documentation](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1experimental_1_1SubscriptionIntraProcess.html#_CPPv4N6rclcpp12experimental24SubscriptionIntraProcess9take_dataEv) for `take_data()` and `execute()` for more detail. @@ -18,7 +18,7 @@ waitable.execute(data); ``` Here is a sample program in [ros2_subscription_examples/intra_process_talker_listener/src/timer_listener_intra_process.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/intra_process_talker_listener/src/timer_listener_intra_process.cpp). -You can run the program as below. If you set `false` to `use_intra_process_comms`, inter-process communication is performed. +You can run the program as below. If you set `true` to `use_intra_process_comms`, intra-process communication is performed, while if you set `false`, inter-process communication is performed. ``` ros2 intra_process_talker_listener talker_listener_intra_process.launch.py use_intra_process_comms:=true @@ -29,13 +29,18 @@ Here is a excerption from [ros2_subscription_examples/intra_process_talker_liste ```c++ // check if intra-process communication is enabled. if (this->get_node_options().use_intra_process_comms()){ + // get the intra-process subscription's waitable. auto intra_process_sub = sub_->get_intra_process_waitable(); + // check if the waitable has data. if (intra_process_sub->is_ready(nullptr) == true) { + // take the data and execute the callback. std::shared_ptr data = intra_process_sub->take_data(); + RCLCPP_INFO(this->get_logger(), " Intra-process communication is performed."); + // execute the callback. intra_process_sub->execute(data); ``` @@ -54,7 +59,7 @@ Below is explanation of above code one line by one. * `std::shared_ptr data = intra_process_sub->take_data();` - obtain a topic message - - `intra_process_sub->take_data();` does not return Boolean value which indicates a message is received successfully or not, therefore need to verify it by calling `is_ready()` in advance + - `intra_process_sub->take_data()` does not return Boolean value which indicates a message is received successfully or not, therefore it is needed to verify it by calling `is_ready()` in advance * `intra_process_sub->execute(data);` - a callback function corresponded to the received message is called inside `execute()` diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md index c6c543b5e98..2ca9cb28801 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md @@ -2,8 +2,8 @@ ## What is `rclcpp::WaitSet` -As explained in [call take() method of Subscription object](./00-topic-message-handling/#call-take-method-of-subscription-object), `take()` method is irreversible. Once `take()` method is executed, Subscription object state changes and undo can not be applied, therefore Subscription object can not be restored to previous state. You can use `rclcpp::WaitSet` to call `take()` after verifying there is a received message in Subscription Queue. -Here is a sample code. `wait_set_.wait()` tells you that a message has already been received and can be obtained by `take()`. +As explained in [call take() method of Subscription object](../00-topic-message-handling/#call-take-method-of-subscription-object), `take()` method is irreversible. Once `take()` method is executed, Subscription object state changes and undo can not be applied, therefore Subscription object can not be restored to previous state. You can use `rclcpp::WaitSet` in advance to call `take()` so that a message is received after verifying it is in Subscription Queue. +Here is a sample code in which `wait_set_.wait()` tells you that a message has already been received and can be obtained by `take()`. ```c++ auto wait_result = wait_set_.wait(std::chrono::milliseconds(0)); @@ -31,11 +31,11 @@ If your code needs to proceed after several types of messages got together, usin } ``` -In code above, unless `rclcpp::WaitSet` is used, it is difficult to verify that all needed messages got together. +In code above, unless `rclcpp::WaitSet` is used, it is difficult to verify that all needed messages get together. ## Coding method -We will explain coding method of `rclcpp::WaitSet` using a sample code in [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp). +We will explain coding method of `rclcpp::WaitSet` using a sample code below. * [ros2_subscription_examples/waitset_examples/src/talker_triple.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/talker_triple.cpp) - it publishes `/chatter` per one second, `/slower_chatter` per two seconds, and `/slowest_chatter` per three seconds periodically @@ -59,7 +59,7 @@ Note that there are three types of `WaitSet` as below. * [Typedef rclcpp::WaitSet](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1ad6fb19c154de27e92430309d2da25ac3.html) - Subscription, Timer, and so on can be registered to WaitSet at any time * [Typedef rclcpp::ThreadSafeWaitSet](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1acaec573e71549fd3078644e18e7f7127.html) - - Subscription, Timer, ans so on can be registered to WaitSet only in thread-safe state + - Subscription, Timer, and so on can be registered to WaitSet only in thread-safe state - sample code is here: [examples/rclcpp/wait_set/src/thread_safe_wait_set.cpp at rolling · ros2/examples](https://github.com/ros2/examples/blob/rolling/rclcpp/wait_set/src/thread_safe_wait_set.cpp) * [Typedef rclcpp::StaticWaitSet](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1adb06acf4a5723b1445fa6ed4e8f73374.html) - Subscription, Timer, and so on can be registered to WaitSet only at initialization @@ -76,6 +76,7 @@ Below is excerption from [ros2_subscription_examples/waitset_examples/src/timer_ subscriptions_array_[0] = create_subscription("chatter", qos, not_executed_callback, subscription_options); subscriptions_array_[1] = create_subscription("slower_chatter", qos, not_executed_callback, subscription_options); subscriptions_array_[2] = create_subscription("slowest_chatter", qos, not_executed_callback, subscription_options); + // Add subscription to waitset for (auto & subscription : subscriptions_array_) { wait_set_.add_subscription(subscription); @@ -111,7 +112,7 @@ As for 1, here is a sample code excerpted from [ros2_subscription_examples/waits } ``` -In code above, it is verified whether any trigger has been invoked which is registered to `wait_set_` by `auto wait_result = wait_set_.wait(std::chrono::milliseconds(0));`. +In code above, it is verified whether any trigger has been invoked which is registered to `wait_set_` by `auto wait_result = wait_set_.wait(std::chrono::milliseconds(0))`. if `wait_result.kind() == rclcpp::WaitResultKind::Ready` is `true`, it indicates any trigger has been invoked. As for 2, here is a sample code excerpted from [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp). @@ -126,5 +127,5 @@ As for 2, here is a sample code excerpted from [ros2_subscription_examples/waits RCLCPP_INFO(this->get_logger(), "I heard: [%s]", msg.data.c_str()); ``` -In code above, `wait_result.get_wait_set().get_rcl_wait_set().subscriptions[i]` indicates whether each individual trigger has been invoked or not. The result was stored to `subscriptions` array. The order in `subscriptions` array is the same as the order in which triggers are registered. +In code above, `wait_result.get_wait_set().get_rcl_wait_set().subscriptions[i]` indicates whether each individual trigger has been invoked or not. The result is stored to `subscriptions` array. The order in `subscriptions` array is the same as the order in which triggers are registered. From 26097852fce69f2b10b029e0219ff430773d716c Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 30 Apr 2024 05:49:33 +0000 Subject: [PATCH 005/225] style(pre-commit): autofix --- .../00-topic-message-handling.md | 16 ++++++++-------- .../01-supp-intra-process-comm.md | 15 ++++++++++----- .../topic-message-handling/02-supp-waitset.md | 13 ++++++------- 3 files changed, 24 insertions(+), 20 deletions(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/00-topic-message-handling.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/00-topic-message-handling.md index 7c76a955c27..f88d6146cb5 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/00-topic-message-handling.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/00-topic-message-handling.md @@ -33,9 +33,9 @@ In this case, a topic message is not obtained by a subscription callback. To be By using this manner, following advantages are achieved. -* it can reduce invocations of subscription callback functions which is relatively expensive -* there is no need to take a topic message which is not read -* there is no need of exclusive lock between a subscription callback thread and a timer callback thread +- it can reduce invocations of subscription callback functions which is relatively expensive +- there is no need to take a topic message which is not read +- there is no need of exclusive lock between a subscription callback thread and a timer callback thread ## Methods to handle topic message data @@ -55,7 +55,7 @@ You can see an example of the typical usage of `take()` method in [ros2_subscrip It is needed to create a Subscription object with a callback group which makes registered callback functions not called automtically. Note that it is needed to register a callback function to Subscription object even if the function will not be called. If you register `nullptr` instead of a callback function, it can not be built. -Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp). +Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp). ```c++ rclcpp::CallbackGroup::SharedPtr cb_group_noexec = this->create_callback_group( @@ -64,7 +64,7 @@ Here is a sample code excerpted from [ros2_subscription_examples/simple_example subscription_options.callback_group = cb_group_noexec; rclcpp::QoS qos(rclcpp::KeepLast(10)); - if (use_transient_local) { + if (use_transient_local) { qos = qos.transient_local(); } @@ -84,7 +84,7 @@ If `automatically_add_to_executor_with_node` is set to `true`, callback function #### call `take()` method of Subscription object -Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp) in which `take()` method is used. +Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp) in which `take()` method is used. ```c++ std_msgs::msg::String msg; @@ -94,7 +94,7 @@ Here is a sample code excerpted from [ros2_subscription_examples/simple_example RCLCPP_INFO(this->get_logger(), "I heard: [%s]", msg.data.c_str()); ``` -In code above, `take(msg, msg_info)` is called in a timer driven callback function by `sub_` instance which is created from Subscription class. `msg` and `msg_info` indicate a message body and meta data of it respectively. When `take(msg, msg_info)` is called, if there is a message in Subscription Queue, then the message is copied to `msg`. +In code above, `take(msg, msg_info)` is called in a timer driven callback function by `sub_` instance which is created from Subscription class. `msg` and `msg_info` indicate a message body and meta data of it respectively. When `take(msg, msg_info)` is called, if there is a message in Subscription Queue, then the message is copied to `msg`. `take(msg, msg_info)` returns `true` if a message is received from Subscription successfully. In this case in code above, a content of the message is outputted by `RCLCPP_INFO`. `take(msg, msg_info)` returns `false` if a mesage is not received from Subscription. When `take(msg, msg_info)` is called, if the size of Subscription Queue is larger than one and there are two or more messages in the queue, then the oldest message is copied to `msg`. If the size of Queue is one, the latest message is always obtained. @@ -127,7 +127,7 @@ In code above, `msg` is created by `create_serialized_message()` to store a rece Subscription can hold multiple messages in its queue. Such messages can be obtained by consecutive calls of `take()` method from a callback function at a time. Note that in a normal manner in which a subscription callback function is used to take a topic message, if there are one or more messages in Subscription Queue, the oldest one is taken and a thread is assigned to execute a callback function, which continues until the queue becomes empty. If you use `take()` method, you can obtain multiple messages at a time. -Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_batch_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_batch_listener.cpp) in which `take()` method is called consecutively. +Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_batch_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_batch_listener.cpp) in which `take()` method is called consecutively. ```c++ std_msgs::msg::String msg; diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index b74b9fc9210..0b89ffd0354 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -44,23 +44,28 @@ Here is a excerption from [ros2_subscription_examples/intra_process_talker_liste // execute the callback. intra_process_sub->execute(data); ``` + Below is explanation of above code one line by one. -* `if (this->get_node_options().use_intra_process_comms()){` +- `if (this->get_node_options().use_intra_process_comms()){` + - verify intra-process communication is enabled or not by using NodeOptions -* `auto intra_process_sub = sub_->get_intra_process_waitable();` +- `auto intra_process_sub = sub_->get_intra_process_waitable();` + - get an object which is used by Subscription in case of intra-process communication -* `if (intra_process_sub->is_ready(nullptr) == true) {` +- `if (intra_process_sub->is_ready(nullptr) == true) {` + - check if a message has already been received through intra-process communication - the argument of `is_ready()` is of rcl_wait_set_t type, but because the argument is not used inside `is_ready()`, `nullptr` is used tentatively - using `nullptr` is a workaround at this point of time, because it is not preferable -* `std::shared_ptr data = intra_process_sub->take_data();` +- `std::shared_ptr data = intra_process_sub->take_data();` + - obtain a topic message - `intra_process_sub->take_data()` does not return Boolean value which indicates a message is received successfully or not, therefore it is needed to verify it by calling `is_ready()` in advance -* `intra_process_sub->execute(data);` +- `intra_process_sub->execute(data);` - a callback function corresponded to the received message is called inside `execute()` - the callback function is executed by the thread which executes `execute()` without context switch diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md index 2ca9cb28801..efd3d7db23d 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md @@ -7,7 +7,7 @@ Here is a sample code in which `wait_set_.wait()` tells you that a message has a ```c++ auto wait_result = wait_set_.wait(std::chrono::milliseconds(0)); - if (wait_result.kind() == rclcpp::WaitResultKind::Ready && + if (wait_result.kind() == rclcpp::WaitResultKind::Ready && wait_result.get_wait_set().get_rcl_wait_set().subscriptions[0]) { sub_->take(msg, msg_info); RCLCPP_INFO(this->get_logger(), "Catch message"); @@ -37,9 +37,9 @@ In code above, unless `rclcpp::WaitSet` is used, it is difficult to verify that We will explain coding method of `rclcpp::WaitSet` using a sample code below. -* [ros2_subscription_examples/waitset_examples/src/talker_triple.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/talker_triple.cpp) +- [ros2_subscription_examples/waitset_examples/src/talker_triple.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/talker_triple.cpp) - it publishes `/chatter` per one second, `/slower_chatter` per two seconds, and `/slowest_chatter` per three seconds periodically -* [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp) +- [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp) - it queries `WaitSet` per one second and if there is a message available, it obtains the message by `take()` - it has each subscription for `/chatter` `/slower_chatter`, and `/slower_chatter` @@ -56,12 +56,12 @@ rclcpp::WaitSet wait_set_; Note that there are three types of `WaitSet` as below. -* [Typedef rclcpp::WaitSet](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1ad6fb19c154de27e92430309d2da25ac3.html) +- [Typedef rclcpp::WaitSet](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1ad6fb19c154de27e92430309d2da25ac3.html) - Subscription, Timer, and so on can be registered to WaitSet at any time -* [Typedef rclcpp::ThreadSafeWaitSet](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1acaec573e71549fd3078644e18e7f7127.html) +- [Typedef rclcpp::ThreadSafeWaitSet](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1acaec573e71549fd3078644e18e7f7127.html) - Subscription, Timer, and so on can be registered to WaitSet only in thread-safe state - sample code is here: [examples/rclcpp/wait_set/src/thread_safe_wait_set.cpp at rolling · ros2/examples](https://github.com/ros2/examples/blob/rolling/rclcpp/wait_set/src/thread_safe_wait_set.cpp) -* [Typedef rclcpp::StaticWaitSet](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1adb06acf4a5723b1445fa6ed4e8f73374.html) +- [Typedef rclcpp::StaticWaitSet](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1adb06acf4a5723b1445fa6ed4e8f73374.html) - Subscription, Timer, and so on can be registered to WaitSet only at initialization - here are sample codes: - [ros2_subscription_examples/waitset_examples/src/timer_listener_twin_static.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_twin_static.cpp) @@ -128,4 +128,3 @@ As for 2, here is a sample code excerpted from [ros2_subscription_examples/waits ``` In code above, `wait_result.get_wait_set().get_rcl_wait_set().subscriptions[i]` indicates whether each individual trigger has been invoked or not. The result is stored to `subscriptions` array. The order in `subscriptions` array is the same as the order in which triggers are registered. - From 54f31e8af85c760fd8e6755b59a76859e00e59ba Mon Sep 17 00:00:00 2001 From: ohsawa1204 Date: Tue, 30 Apr 2024 15:15:09 +0900 Subject: [PATCH 006/225] doc:change 5 Signed-off-by: ohsawa1204 --- .../topic-message-handling/00-topic-message-handling.md | 2 +- .../topic-message-handling/01-supp-intra-process-comm.md | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/00-topic-message-handling.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/00-topic-message-handling.md index f88d6146cb5..679ecb99135 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/00-topic-message-handling.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/00-topic-message-handling.md @@ -46,7 +46,7 @@ We will explain four methods including the enhanced method. To use the enhanced method using `Subscription->take()`, you need to do two things below basically. 1. prevent calling a callback function when a topic message is received -1. call `take()` method of Subscription object when a topic message is needed +2. call `take()` method of Subscription object when a topic message is needed You can see an example of the typical usage of `take()` method in [ros2_subscription_examples/simple_examples/src /timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp). diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index 0b89ffd0354..d69f2bf0400 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -20,7 +20,7 @@ waitable.execute(data); Here is a sample program in [ros2_subscription_examples/intra_process_talker_listener/src/timer_listener_intra_process.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/intra_process_talker_listener/src/timer_listener_intra_process.cpp). You can run the program as below. If you set `true` to `use_intra_process_comms`, intra-process communication is performed, while if you set `false`, inter-process communication is performed. -``` +```console ros2 intra_process_talker_listener talker_listener_intra_process.launch.py use_intra_process_comms:=true ``` From cabe89bff2d46e7f5f336741d3484eacc6072dfc Mon Sep 17 00:00:00 2001 From: Takayuki AKAMINE Date: Wed, 1 May 2024 10:50:29 +0900 Subject: [PATCH 007/225] docs(topic-message-handling): create page structure using .pages Signed-off-by: Takayuki AKAMINE --- docs/contributing/coding-guidelines/ros-nodes/.pages | 1 + .../coding-guidelines/ros-nodes/topic-message-handling/.pages | 4 ++++ .../ros-nodes/topic-message-handling/02-supp-waitset.md | 2 +- .../{00-topic-message-handling.md => index.md} | 0 4 files changed, 6 insertions(+), 1 deletion(-) create mode 100644 docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/.pages rename docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/{00-topic-message-handling.md => index.md} (100%) diff --git a/docs/contributing/coding-guidelines/ros-nodes/.pages b/docs/contributing/coding-guidelines/ros-nodes/.pages index e446c5224d5..3bc81879e16 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/.pages +++ b/docs/contributing/coding-guidelines/ros-nodes/.pages @@ -8,3 +8,4 @@ nav: - parameters.md - task-scheduling.md - topic-namespaces.md + - topic-message-handling diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/.pages b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/.pages new file mode 100644 index 00000000000..c162833180a --- /dev/null +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/.pages @@ -0,0 +1,4 @@ +nav: + - index.md + - 01-supp-intra-process-comm.md + - 02-supp-waitset.md diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md index efd3d7db23d..bbc2ad1322c 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md @@ -2,7 +2,7 @@ ## What is `rclcpp::WaitSet` -As explained in [call take() method of Subscription object](../00-topic-message-handling/#call-take-method-of-subscription-object), `take()` method is irreversible. Once `take()` method is executed, Subscription object state changes and undo can not be applied, therefore Subscription object can not be restored to previous state. You can use `rclcpp::WaitSet` in advance to call `take()` so that a message is received after verifying it is in Subscription Queue. +As explained in [call take() method of Subscription object](./index#call-take-method-of-subscription-object), `take()` method is irreversible. Once `take()` method is executed, Subscription object state changes and undo can not be applied, therefore Subscription object can not be restored to previous state. You can use `rclcpp::WaitSet` in advance to call `take()` so that a message is received after verifying it is in Subscription Queue. Here is a sample code in which `wait_set_.wait()` tells you that a message has already been received and can be obtained by `take()`. ```c++ diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/00-topic-message-handling.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md similarity index 100% rename from docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/00-topic-message-handling.md rename to docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md From 13bd80039f7c58f15f835722e3256fdcda363fa6 Mon Sep 17 00:00:00 2001 From: Takayuki AKAMINE Date: Wed, 1 May 2024 11:04:54 +0900 Subject: [PATCH 008/225] docs(topic-message-handling): fix missing links Signed-off-by: Takayuki AKAMINE --- .../topic-message-handling/01-supp-intra-process-comm.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index d69f2bf0400..9ebc35f9006 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -2,8 +2,8 @@ ## Topic message handling in intra-process communication -rlcpp supports intra-process communication. As explained in [Topic message handling guideline](00-topic-message-handling.md), `take()` method of Subscription can not be used in case of intra-process communication. `take()` can not obtain a topic message which is received through inter-process communication. Besides, even though a method is provided to obtain a received topic message through intra-process communication, a method is not provided to refer to the message directly. -But a method are provided for intra-process communication similar to a method for inter-process communication described in [obtain data by calling Subscription->take and then call a callback function](../00-topic-message-handling/#3-obtain-data-by-calling-subscription-take-and-then-call-a-callback-function). +rlcpp supports intra-process communication. As explained in [Topic message handling guideline](index.md), `take()` method of Subscription can not be used in case of intra-process communication. `take()` can not obtain a topic message which is received through inter-process communication. Besides, even though a method is provided to obtain a received topic message through intra-process communication, a method is not provided to refer to the message directly. +But a method are provided for intra-process communication similar to a method for inter-process communication described in [obtain data by calling Subscription->take and then call a callback function](./index.md#3-obtain-data-by-calling-subscription-take-and-then-call-a-callback-function). `take_data()` method is provided to obtain a received data in case of intra-process communication and the received data must be processed through `execute()` method. Refer to [Template Class SubscriptionIntraProcess — rclcpp 16.0.8 documentation](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1experimental_1_1SubscriptionIntraProcess.html#_CPPv4N6rclcpp12experimental24SubscriptionIntraProcess9take_dataEv) for `take_data()` and `execute()` for more detail. From f38d7a0a88da7a27337c17c88cea473ebe8629c0 Mon Sep 17 00:00:00 2001 From: ohsawa1204 Date: Wed, 1 May 2024 11:39:30 +0900 Subject: [PATCH 009/225] docs(topic-message-handling): index -> index.md in 02-supp-waitset.md Signed-off-by: ohsawa1204 --- .../ros-nodes/topic-message-handling/02-supp-waitset.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md index bbc2ad1322c..1ae1a79b097 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md @@ -2,7 +2,7 @@ ## What is `rclcpp::WaitSet` -As explained in [call take() method of Subscription object](./index#call-take-method-of-subscription-object), `take()` method is irreversible. Once `take()` method is executed, Subscription object state changes and undo can not be applied, therefore Subscription object can not be restored to previous state. You can use `rclcpp::WaitSet` in advance to call `take()` so that a message is received after verifying it is in Subscription Queue. +As explained in [call take() method of Subscription object](./index.md#call-take-method-of-subscription-object), `take()` method is irreversible. Once `take()` method is executed, Subscription object state changes and undo can not be applied, therefore Subscription object can not be restored to previous state. You can use `rclcpp::WaitSet` in advance to call `take()` so that a message is received after verifying it is in Subscription Queue. Here is a sample code in which `wait_set_.wait()` tells you that a message has already been received and can be obtained by `take()`. ```c++ From 7b36ae065a3f253fdaf1c304c4876f83b441f8de Mon Sep 17 00:00:00 2001 From: ohsawa1204 Date: Wed, 1 May 2024 12:25:23 +0900 Subject: [PATCH 010/225] docs(topic-message-handling): correct misspelled words Signed-off-by: ohsawa1204 --- .../01-supp-intra-process-comm.md | 2 +- .../topic-message-handling/02-supp-waitset.md | 2 +- .../ros-nodes/topic-message-handling/index.md | 12 ++++++------ 3 files changed, 8 insertions(+), 8 deletions(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index 9ebc35f9006..b1921ae9d02 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -2,7 +2,7 @@ ## Topic message handling in intra-process communication -rlcpp supports intra-process communication. As explained in [Topic message handling guideline](index.md), `take()` method of Subscription can not be used in case of intra-process communication. `take()` can not obtain a topic message which is received through inter-process communication. Besides, even though a method is provided to obtain a received topic message through intra-process communication, a method is not provided to refer to the message directly. +rclcpp supports intra-process communication. As explained in [Topic message handling guideline](index.md), `take()` method of Subscription can not be used in case of intra-process communication. `take()` can not obtain a topic message which is received through inter-process communication. Besides, even though a method is provided to obtain a received topic message through intra-process communication, a method is not provided to refer to the message directly. But a method are provided for intra-process communication similar to a method for inter-process communication described in [obtain data by calling Subscription->take and then call a callback function](./index.md#3-obtain-data-by-calling-subscription-take-and-then-call-a-callback-function). `take_data()` method is provided to obtain a received data in case of intra-process communication and the received data must be processed through `execute()` method. Refer to [Template Class SubscriptionIntraProcess — rclcpp 16.0.8 documentation](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1experimental_1_1SubscriptionIntraProcess.html#_CPPv4N6rclcpp12experimental24SubscriptionIntraProcess9take_dataEv) for `take_data()` and `execute()` for more detail. diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md index 1ae1a79b097..0aec0163b78 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md @@ -15,7 +15,7 @@ Here is a sample code in which `wait_set_.wait()` tells you that a message has a ``` Also you can verify that there are messages in multiple Subscription Queues in advance. -If your code needs to proceed after several types of messages got together, using `rclcpp::WaitSet` is prefarable. +If your code needs to proceed after several types of messages got together, using `rclcpp::WaitSet` is preferable. ```c++ auto wait_result = wait_set_.wait(std::chrono::milliseconds(0)); diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 679ecb99135..108055c2138 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -16,7 +16,7 @@ In a typical ROS 2 application, a topic message which is received by Subscriptio [this](SteeringReport::SharedPtr msg) { current_steer_ = msg->steering_tire_angle; }); ``` -In code above, when a topic message whose name is `input/steering` is received, an anonymous function whose description is `{current_steer_ = msg->steering_tier_angle;}` is executed as a callback in a thread. The callback function is always executed when the message is received, which leads to waste computing resource if the message is not always necessary. Besides, it costs thread-wakeup overhread just to take a message. +In code above, when a topic message whose name is `input/steering` is received, an anonymous function whose description is `{current_steer_ = msg->steering_tier_angle;}` is executed as a callback in a thread. The callback function is always executed when the message is received, which leads to waste computing resource if the message is not always necessary. Besides, it costs thread-wakeup overhead just to take a message. ## Enhanced method @@ -53,7 +53,7 @@ You can see an example of the typical usage of `take()` method in [ros2_subscrip #### prevent calling a callback function -It is needed to create a Subscription object with a callback group which makes registered callback functions not called automtically. +It is needed to create a Subscription object with a callback group which makes registered callback functions not called automatically. Note that it is needed to register a callback function to Subscription object even if the function will not be called. If you register `nullptr` instead of a callback function, it can not be built. Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp). @@ -96,7 +96,7 @@ Here is a sample code excerpted from [ros2_subscription_examples/simple_examples In code above, `take(msg, msg_info)` is called in a timer driven callback function by `sub_` instance which is created from Subscription class. `msg` and `msg_info` indicate a message body and meta data of it respectively. When `take(msg, msg_info)` is called, if there is a message in Subscription Queue, then the message is copied to `msg`. `take(msg, msg_info)` returns `true` if a message is received from Subscription successfully. In this case in code above, a content of the message is outputted by `RCLCPP_INFO`. -`take(msg, msg_info)` returns `false` if a mesage is not received from Subscription. +`take(msg, msg_info)` returns `false` if a message is not received from Subscription. When `take(msg, msg_info)` is called, if the size of Subscription Queue is larger than one and there are two or more messages in the queue, then the oldest message is copied to `msg`. If the size of Queue is one, the latest message is always obtained. Note 1. `take()` method is irreversible in terms that a obtained message by `take()` method can not be returned to Subscription Queue. **You can determine whether a message is in Subscription Queue or not by the return value of `take()` method, but it changes Subscription queue state.** If you want to know whether there is a message in Subscription Queue or not, you can use `rclcpp::WaitSet`. @@ -106,7 +106,7 @@ Note 2. You can use `take()` method to obtain a message which is passed through #### 1.1 obtain Serialized Message from Subscription -ROS 2 provides Serialized Message functon which supports communication with arbitrary message types as explained in [Class SerializedMessage](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1SerializedMessage.html). It is used by `topic_state_monitor` in Autoware. +ROS 2 provides Serialized Message function which supports communication with arbitrary message types as explained in [Class SerializedMessage](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1SerializedMessage.html). It is used by `topic_state_monitor` in Autoware. You need to use `take_serialized()` method instead of `take()` method to obtain a message of Serialized Message type from Subscription object. Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener_serialized_message.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener_serialized_message.cpp). @@ -146,7 +146,7 @@ It is effective to use the method if a reception of message occurs very frequent ### 3. obtain data by calling `Subscription->take` and then call a callback function -If you want to use the enhanced method introduced in this guideline, you may feel it is needed to implement a new funcation in which a message is taken by `take()` method and then processed. But there is a way to make a callback function be called indirectly which is registered to Subscription object. +If you want to use the enhanced method introduced in this guideline, you may feel it is needed to implement a new function in which a message is taken by `take()` method and then processed. But there is a way to make a callback function be called indirectly which is registered to Subscription object. Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener_using_callback.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener_using_callback.cpp). ```c++ @@ -164,7 +164,7 @@ You can also refer to [API document](http://docs.ros.org/en/humble/p/rclcpp/gene ### 4. obtain data by a callback function A typical method usually used is also usable, by which a message is obtained in subscription callback function . If you don't use a callback group with `automatically_add_to_executor_with_node = false`, a registered callback function is called automatically by Executor when a topic message is received. -One of advantages of this method is you don't need to take care whether a topic message is passed through inter-process or itra-process. Remind that in the enhanced method, `take()` can only be used in case of inter-process communication while `take_type_erased()` needs to be used in case of intra-process communication. +One of advantages of this method is you don't need to take care whether a topic message is passed through inter-process or intra-process. Remind that in the enhanced method, `take()` can only be used in case of inter-process communication while `take_type_erased()` needs to be used in case of intra-process communication. ## Appendix From 136ab2da00a197ebd776953fb163b4247ad328ed Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:18:12 +0900 Subject: [PATCH 011/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/index.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 108055c2138..12b128e19e6 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -8,7 +8,8 @@ You can find sample source codes in [ros2_subscription_examples](https://github. ## Typical message handling method usually used At first, let us see a typical message handling method usually used. -In a typical ROS 2 application, a topic message which is received by Subscription is referred to and processed by a dedicated callback function. +[ROS 2 Tutorials](https://docs.ros.org/en/rolling/Tutorials/Beginner-Client-Libraries/Writing-A-Simple-Cpp-Publisher-And-Subscriber.html#write-the-subscriber-node) is one of the most cited references for ROS 2 applications, including Autoware. +It implicitly recommends that messages received by subscriptions should be referred and processed by a dedicated callback function. Autoware follows that manner thoroughly. ```c++ steer_sub_ = create_subscription( From 8fa4990f21165095ed84c18e3d8c294a6e354511 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:18:44 +0900 Subject: [PATCH 012/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 12b128e19e6..39cd3775d81 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -22,7 +22,7 @@ In code above, when a topic message whose name is `input/steering` is received, ## Enhanced method There is an enhanced method to take a message using `Subscription->take()` method only when it is needed. -Here is a sample code to use `Subscription->take()` method executed as a timer or subscription callback to perform a main logic. +The sample code given below shows that `Subscription->take()` method is called during execution of any callback function. In most cases, `Subscription->take()` method is called before a received message is consumed by a main logic. In this case, a topic message is not obtained by a subscription callback. To be exact, you need to program your code so that a callback function is not called automatically. ```c++ From 554b3599f60e63d28651d3deb10fd7d2debbd598 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:19:11 +0900 Subject: [PATCH 013/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 39cd3775d81..669f12c9f75 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -35,7 +35,7 @@ In this case, a topic message is not obtained by a subscription callback. To be By using this manner, following advantages are achieved. - it can reduce invocations of subscription callback functions which is relatively expensive -- there is no need to take a topic message which is not read +- There is no need to take a topic message, which a main logic does not consume, from a subscription - there is no need of exclusive lock between a subscription callback thread and a timer callback thread ## Methods to handle topic message data From cba9ec8ef70f71c0154b4f6f0966e9b5991a8ece Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:19:38 +0900 Subject: [PATCH 014/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 669f12c9f75..6d31db06420 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -34,7 +34,7 @@ In this case, a topic message is not obtained by a subscription callback. To be By using this manner, following advantages are achieved. -- it can reduce invocations of subscription callback functions which is relatively expensive +- It can reduce invocations of subscription callback functions - There is no need to take a topic message, which a main logic does not consume, from a subscription - there is no need of exclusive lock between a subscription callback thread and a timer callback thread From 564901aba905f387213e42fa9bb293fb636e117f Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:19:59 +0900 Subject: [PATCH 015/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 6d31db06420..f3d96055ddf 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -36,7 +36,7 @@ By using this manner, following advantages are achieved. - It can reduce invocations of subscription callback functions - There is no need to take a topic message, which a main logic does not consume, from a subscription -- there is no need of exclusive lock between a subscription callback thread and a timer callback thread +- There is no mandatory thread waking for the callback function, which leads to multi-threaded programming, data races and exclusive locking ## Methods to handle topic message data From 30ddb45d290ede17ea1f1173c704a2ee8d15b866 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:20:29 +0900 Subject: [PATCH 016/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index f3d96055ddf..99e5f861d93 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -46,7 +46,7 @@ We will explain four methods including the enhanced method. To use the enhanced method using `Subscription->take()`, you need to do two things below basically. -1. prevent calling a callback function when a topic message is received +1. Prevent calling a callback function when a topic message is received 2. call `take()` method of Subscription object when a topic message is needed You can see an example of the typical usage of `take()` method in [ros2_subscription_examples/simple_examples/src From 9658b88f370e31b14f3c7b2ffe8bf6849b416fa8 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:20:46 +0900 Subject: [PATCH 017/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 99e5f861d93..e24d2aeb346 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -47,7 +47,7 @@ We will explain four methods including the enhanced method. To use the enhanced method using `Subscription->take()`, you need to do two things below basically. 1. Prevent calling a callback function when a topic message is received -2. call `take()` method of Subscription object when a topic message is needed +2. Call `take()` method of Subscription object when a topic message is needed You can see an example of the typical usage of `take()` method in [ros2_subscription_examples/simple_examples/src /timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp). From 64ae6cdd83e9f9ad9a9c174d6b1abd8cef8863bc Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:21:18 +0900 Subject: [PATCH 018/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index e24d2aeb346..5308fc5ed6e 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -40,7 +40,7 @@ By using this manner, following advantages are achieved. ## Methods to handle topic message data -We will explain four methods including the enhanced method. +This section introduces four manners including the recommended ones. ### 1. obtain data by calling `Subscription->take()` From 81dbcf78eb61d86e08ff0cfd7928d47f6233a67b Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:21:46 +0900 Subject: [PATCH 019/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 5308fc5ed6e..6f74a2df30d 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -54,7 +54,7 @@ You can see an example of the typical usage of `take()` method in [ros2_subscrip #### prevent calling a callback function -It is needed to create a Subscription object with a callback group which makes registered callback functions not called automatically. +To prevent a callback function from being called automatically, the callback function has to belong a callback group whose callback functions will not added to executor. Note that it is needed to register a callback function to Subscription object even if the function will not be called. If you register `nullptr` instead of a callback function, it can not be built. Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp). From b7a9d762d9e9400be3c6fb9dec65c2102c5b2f19 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:22:13 +0900 Subject: [PATCH 020/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 6f74a2df30d..178a7fa33b7 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -55,7 +55,7 @@ You can see an example of the typical usage of `take()` method in [ros2_subscrip #### prevent calling a callback function To prevent a callback function from being called automatically, the callback function has to belong a callback group whose callback functions will not added to executor. -Note that it is needed to register a callback function to Subscription object even if the function will not be called. If you register `nullptr` instead of a callback function, it can not be built. +Due to [API specification of `create_subscription`](http://docs.ros.org/en/iron/p/rclcpp/generated/classrclcpp_1_1Node.html), registering a callback function to a `Subscription` based object is mandatory even if the callback function has no operation. Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp). ```c++ From b94b519db1f2352052b45f41f7371c7c66483565 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:22:37 +0900 Subject: [PATCH 021/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 1 + 1 file changed, 1 insertion(+) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 178a7fa33b7..1bfb0286226 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -85,6 +85,7 @@ If `automatically_add_to_executor_with_node` is set to `true`, callback function #### call `take()` method of Subscription object +To take a topic message from the `Subscription` based object, the `take()` method is called at the expected time. Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp) in which `take()` method is used. ```c++ From 353badd679f0aff24a45b0ad5cf06d3026bd24ab Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:23:15 +0900 Subject: [PATCH 022/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 1bfb0286226..ef43458eba5 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -96,7 +96,7 @@ Here is a sample code excerpted from [ros2_subscription_examples/simple_examples RCLCPP_INFO(this->get_logger(), "I heard: [%s]", msg.data.c_str()); ``` -In code above, `take(msg, msg_info)` is called in a timer driven callback function by `sub_` instance which is created from Subscription class. `msg` and `msg_info` indicate a message body and meta data of it respectively. When `take(msg, msg_info)` is called, if there is a message in Subscription Queue, then the message is copied to `msg`. +In the code above, `take(msg, msg_info)` is called by `sub_` instance which is created from `Subscription` class. It is called in a timer driven callback function. `msg` and `msg_info` indicate a message body and its metadata respectively. If there is a message in the subscription queue when `take(msg, msg_info)` is called, then the message is copied to `msg`. `take(msg, msg_info)` returns `true` if a message is received from Subscription successfully. In this case in code above, a content of the message is outputted by `RCLCPP_INFO`. `take(msg, msg_info)` returns `false` if a message is not received from Subscription. When `take(msg, msg_info)` is called, if the size of Subscription Queue is larger than one and there are two or more messages in the queue, then the oldest message is copied to `msg`. If the size of Queue is one, the latest message is always obtained. From 2d289f119ec816ba055581335c46fabd84a6de6e Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:23:50 +0900 Subject: [PATCH 023/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index ef43458eba5..3961d48261f 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -97,7 +97,7 @@ Here is a sample code excerpted from [ros2_subscription_examples/simple_examples ``` In the code above, `take(msg, msg_info)` is called by `sub_` instance which is created from `Subscription` class. It is called in a timer driven callback function. `msg` and `msg_info` indicate a message body and its metadata respectively. If there is a message in the subscription queue when `take(msg, msg_info)` is called, then the message is copied to `msg`. -`take(msg, msg_info)` returns `true` if a message is received from Subscription successfully. In this case in code above, a content of the message is outputted by `RCLCPP_INFO`. +`take(msg, msg_info)` returns `true` if a message is taken from the subscription successfully. In this case in code above, a string data of the message is outputted by `RCLCPP_INFO`. `take(msg, msg_info)` returns `false` if a message is not received from Subscription. When `take(msg, msg_info)` is called, if the size of Subscription Queue is larger than one and there are two or more messages in the queue, then the oldest message is copied to `msg`. If the size of Queue is one, the latest message is always obtained. From f7ce39b61d555d862509e54f8ce3e9fc0f967e86 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:24:11 +0900 Subject: [PATCH 024/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 3961d48261f..8901cbb4e66 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -98,7 +98,7 @@ Here is a sample code excerpted from [ros2_subscription_examples/simple_examples In the code above, `take(msg, msg_info)` is called by `sub_` instance which is created from `Subscription` class. It is called in a timer driven callback function. `msg` and `msg_info` indicate a message body and its metadata respectively. If there is a message in the subscription queue when `take(msg, msg_info)` is called, then the message is copied to `msg`. `take(msg, msg_info)` returns `true` if a message is taken from the subscription successfully. In this case in code above, a string data of the message is outputted by `RCLCPP_INFO`. -`take(msg, msg_info)` returns `false` if a message is not received from Subscription. +`take(msg, msg_info)` returns `false` if a message is not taken from Subscription. When `take(msg, msg_info)` is called, if the size of Subscription Queue is larger than one and there are two or more messages in the queue, then the oldest message is copied to `msg`. If the size of Queue is one, the latest message is always obtained. Note 1. `take()` method is irreversible in terms that a obtained message by `take()` method can not be returned to Subscription Queue. **You can determine whether a message is in Subscription Queue or not by the return value of `take()` method, but it changes Subscription queue state.** If you want to know whether there is a message in Subscription Queue or not, you can use `rclcpp::WaitSet`. From 8588e50e2f9077dc91076618fbda96f434722519 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 2 May 2024 06:24:26 +0000 Subject: [PATCH 025/225] style(pre-commit): autofix --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 8901cbb4e66..ffc88acca4c 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -96,7 +96,7 @@ Here is a sample code excerpted from [ros2_subscription_examples/simple_examples RCLCPP_INFO(this->get_logger(), "I heard: [%s]", msg.data.c_str()); ``` -In the code above, `take(msg, msg_info)` is called by `sub_` instance which is created from `Subscription` class. It is called in a timer driven callback function. `msg` and `msg_info` indicate a message body and its metadata respectively. If there is a message in the subscription queue when `take(msg, msg_info)` is called, then the message is copied to `msg`. +In the code above, `take(msg, msg_info)` is called by `sub_` instance which is created from `Subscription` class. It is called in a timer driven callback function. `msg` and `msg_info` indicate a message body and its metadata respectively. If there is a message in the subscription queue when `take(msg, msg_info)` is called, then the message is copied to `msg`. `take(msg, msg_info)` returns `true` if a message is taken from the subscription successfully. In this case in code above, a string data of the message is outputted by `RCLCPP_INFO`. `take(msg, msg_info)` returns `false` if a message is not taken from Subscription. When `take(msg, msg_info)` is called, if the size of Subscription Queue is larger than one and there are two or more messages in the queue, then the oldest message is copied to `msg`. If the size of Queue is one, the latest message is always obtained. From 98c976994e40e6dc81cd5f252c4f3350acb195ab Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:25:24 +0900 Subject: [PATCH 026/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/index.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index ffc88acca4c..7c89d33c1c8 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -101,7 +101,8 @@ In the code above, `take(msg, msg_info)` is called by `sub_` instance which is c `take(msg, msg_info)` returns `false` if a message is not taken from Subscription. When `take(msg, msg_info)` is called, if the size of Subscription Queue is larger than one and there are two or more messages in the queue, then the oldest message is copied to `msg`. If the size of Queue is one, the latest message is always obtained. -Note 1. `take()` method is irreversible in terms that a obtained message by `take()` method can not be returned to Subscription Queue. **You can determine whether a message is in Subscription Queue or not by the return value of `take()` method, but it changes Subscription queue state.** If you want to know whether there is a message in Subscription Queue or not, you can use `rclcpp::WaitSet`. +!!! Note + You can check the presence of incoming message with the returned value of `take()` method. However, you have to take care of destructive nature of take() method. `take()` method changes the subscription queue. Besides, `take()` method is irreversible while there is no undo operation against `take()` method. Checking the incoming message with only `take()` method always changes the subscription queue. If you want to check without changing the subscription queue, rclcpp::WaitSet is recommended. Refer to [[supplement] Use rclcpp::WaitSet](./02-supp-waitset.md) for more detail. Note 2. You can use `take()` method to obtain a message which is passed through DDS as an inter-process communication. You can not use it for an intra-process communication. Refer to [[supplement] Obtain a received message through intra-process communication](./01-supp-intra-process-comm.md) in case of intra-process communication. From 1c49fa3396158b1ed113ff4e916f80c66cf9133e Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:25:44 +0900 Subject: [PATCH 027/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 7c89d33c1c8..f1141722aa6 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -103,7 +103,7 @@ When `take(msg, msg_info)` is called, if the size of Subscription Queue is large !!! Note You can check the presence of incoming message with the returned value of `take()` method. However, you have to take care of destructive nature of take() method. `take()` method changes the subscription queue. Besides, `take()` method is irreversible while there is no undo operation against `take()` method. Checking the incoming message with only `take()` method always changes the subscription queue. If you want to check without changing the subscription queue, rclcpp::WaitSet is recommended. -Refer to [[supplement] Use rclcpp::WaitSet](./02-supp-waitset.md) for more detail. + Refer to [[supplement] Use rclcpp::WaitSet](./02-supp-waitset.md) for more detail. Note 2. You can use `take()` method to obtain a message which is passed through DDS as an inter-process communication. You can not use it for an intra-process communication. Refer to [[supplement] Obtain a received message through intra-process communication](./01-supp-intra-process-comm.md) in case of intra-process communication. From 2521119b058e6f8d15d9b9b20b0a7846dd89890e Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:26:11 +0900 Subject: [PATCH 028/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/index.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index f1141722aa6..7dc02c720d3 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -105,7 +105,8 @@ When `take(msg, msg_info)` is called, if the size of Subscription Queue is large You can check the presence of incoming message with the returned value of `take()` method. However, you have to take care of destructive nature of take() method. `take()` method changes the subscription queue. Besides, `take()` method is irreversible while there is no undo operation against `take()` method. Checking the incoming message with only `take()` method always changes the subscription queue. If you want to check without changing the subscription queue, rclcpp::WaitSet is recommended. Refer to [[supplement] Use rclcpp::WaitSet](./02-supp-waitset.md) for more detail. -Note 2. You can use `take()` method to obtain a message which is passed through DDS as an inter-process communication. You can not use it for an intra-process communication. Refer to [[supplement] Obtain a received message through intra-process communication](./01-supp-intra-process-comm.md) in case of intra-process communication. +!!! Note + `take()` method is supported to only obtain a message which is passed through DDS as an inter-process communication. You must not use it for an intra-process communication because intra-process communication is based on another software stack of `rclcpp`. Refer to [[supplement] Obtain a received message through intra-process communication](./01-supp-intra-process-comm.md) in case of intra-process communication. #### 1.1 obtain Serialized Message from Subscription From 3bb54a7e325f0e39414fd06adcb285432879167a Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:26:35 +0900 Subject: [PATCH 029/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/index.md | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 7dc02c720d3..bad0f19c2a8 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -127,6 +127,10 @@ Here is a sample code excerpted from [ros2_subscription_examples/simple_examples In code above, `msg` is created by `create_serialized_message()` to store a received message, whose type is `std::shared_ptr`. You can obtain a message of Serialized Message type by `take_serialized()` method. Note that `take_serialized()` method needs reference type data as its first argument therefore you need to convert `msg` type using `*`. +!!! Note + ROS 2's `rclcpp` supports `rclcpp::LoanedMessage` as well as `rclcpp::SerializedMessage`. If [zero copy communication via loaned messages](https://design.ros2.org/articles/zero_copy.html) is introduced to Autoware, `take_loaned()` method should be used for communication via loaned messages instead. In this document, the explanation of `take_loaned()` method is omitted because it is not used for Autoware in the present (May. 2024). + + ### 2. obtain multiple data stored in Subscription Queue Subscription can hold multiple messages in its queue. Such messages can be obtained by consecutive calls of `take()` method from a callback function at a time. Note that in a normal manner in which a subscription callback function is used to take a topic message, if there are one or more messages in Subscription Queue, the oldest one is taken and a thread is assigned to execute a callback function, which continues until the queue becomes empty. If you use `take()` method, you can obtain multiple messages at a time. From aa01ec7fd83380c9f3cf73f61669e7b9f9d1a165 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:26:58 +0900 Subject: [PATCH 030/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index bad0f19c2a8..2ccc20e19d4 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -146,7 +146,7 @@ Here is a sample code excerpted from [ros2_subscription_examples/simple_examples RCLCPP_INFO(this->get_logger(), "I heard: [%s]", msg.data.c_str()); ``` -In code above, `while(sub->take(msg, msg_info))` continues to take messages from Subscription Queue until the queue becomes empty. While a message is taken, the message is processed each by each. +In the code above, `while(sub->take(msg, msg_info))` continues to take messages from the subscription queue until the queue becomes empty. While a message is taken, the message is processed each by each. Note that you need to determine Subscription Queue size considering frequency of an invocation of a callback function and that of a reception of message. For example, if frequency of an invocation of a callback function is 10Hz and that of a reception of message is 50Hz, Subscription Queue size needs to be at least 5 for messages not to be lost. To assign a thread and let it execute a callback function each time a message is received leads to increase overhead in terms of performance. You can use the method introduced in this section to avoid the overhead. From 22f5b2f712e280a0311106cfde155dc19fa1b38c Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:27:17 +0900 Subject: [PATCH 031/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/index.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 2ccc20e19d4..4074c2ffef5 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -189,7 +189,8 @@ Many of ROS 2 users may feel anxious to use `take()` method because they may not [&]() {subscription->handle_message(message, message_info);}); ``` -Note: Strictly speaking, `take_type_erased()` method is called in Executor implementation instead of `take()`. +!!!Note + Strictly speaking, `take_type_erased()` method is called in the Executor, but not `take()` method. But `take_type_erased()` is called inside of `take()`. If Executor is programmed to call a callback function, Executor itself determines when to do it. Because Executor calls a callback function with best-effort basis basically, it can occur that a message is not referred to or processed when it is needed in a node. Therefore it is desirable to call `take()` method directly **to ensue that a message is referred to or processed at the intended time.** From 3056fd8b9eeda888dfe1b0c4d822fc1ca81de408 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:27:40 +0900 Subject: [PATCH 032/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 4074c2ffef5..94be7ec02aa 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -191,6 +191,6 @@ Many of ROS 2 users may feel anxious to use `take()` method because they may not !!!Note Strictly speaking, `take_type_erased()` method is called in the Executor, but not `take()` method. -But `take_type_erased()` is called inside of `take()`. +But `take_type_erased()` is the embodiment of `take()`, while `take()` internally calls `take_type_erased()`. If Executor is programmed to call a callback function, Executor itself determines when to do it. Because Executor calls a callback function with best-effort basis basically, it can occur that a message is not referred to or processed when it is needed in a node. Therefore it is desirable to call `take()` method directly **to ensue that a message is referred to or processed at the intended time.** From 753cd0c8f0bb7b8b670ccf13cf76473e83281168 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:28:01 +0900 Subject: [PATCH 033/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 94be7ec02aa..3275d0c3359 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -176,7 +176,7 @@ One of advantages of this method is you don't need to take care whether a topic ## Appendix -A callback function is used to obtain a topic message in many of ROS 2 applications as if it is a rule or a custom. As we have seen, you can use `Subscription->take()` method to obtain a topic message without calling a subscription callback function. +A callback function is used to obtain a topic message in many of ROS 2 applications as if it is a rule or a custom. As this document page explained, you can use `Subscription->take()` method to obtain a topic message without calling a subscription callback function. This method is also documented in [Template Class Subscription — rclcpp 16.0.8 documentation](https://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1Subscription.html#_CPPv4N6rclcpp12Subscription4takeER14ROSMessageTypeRN6rclcpp11MessageInfoE). Many of ROS 2 users may feel anxious to use `take()` method because they may not be so familiar with it, but it is widely used in Executor implementation as in [rclcpp/executor.cpp](https://github.com/ros2/rclcpp/blob/47c977d1bc82fc76dd21f870bcd3ea473eca2f59/rclcpp/src/rclcpp/executor.cpp#L643-L648) shown below. Therefore it turns out that you use `take()` method indirectly whether you know it or not. From 5de0f788de005019de8f6b0fbcd5d84dabfe230e Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:28:23 +0900 Subject: [PATCH 034/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 3275d0c3359..d5afd2a37ad 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -178,7 +178,7 @@ One of advantages of this method is you don't need to take care whether a topic A callback function is used to obtain a topic message in many of ROS 2 applications as if it is a rule or a custom. As this document page explained, you can use `Subscription->take()` method to obtain a topic message without calling a subscription callback function. This method is also documented in [Template Class Subscription — rclcpp 16.0.8 documentation](https://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1Subscription.html#_CPPv4N6rclcpp12Subscription4takeER14ROSMessageTypeRN6rclcpp11MessageInfoE). -Many of ROS 2 users may feel anxious to use `take()` method because they may not be so familiar with it, but it is widely used in Executor implementation as in [rclcpp/executor.cpp](https://github.com/ros2/rclcpp/blob/47c977d1bc82fc76dd21f870bcd3ea473eca2f59/rclcpp/src/rclcpp/executor.cpp#L643-L648) shown below. Therefore it turns out that you use `take()` method indirectly whether you know it or not. +Many of ROS 2 users may feel anxious to use `take()` method because they may not be so familiar with it and there is a lack of documentation about `take()`, but it is widely used in Executor implementation as in [rclcpp/executor.cpp](https://github.com/ros2/rclcpp/blob/47c977d1bc82fc76dd21f870bcd3ea473eca2f59/rclcpp/src/rclcpp/executor.cpp#L643-L648) shown below. Therefore it turns out that you use `take()` method indirectly whether you know it or not. ```c++ std::shared_ptr message = subscription->create_message(); From 7cf816e279e1b21e2407b3f09d3d7e93429955ee Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 2 May 2024 06:28:30 +0000 Subject: [PATCH 035/225] style(pre-commit): autofix --- .../ros-nodes/topic-message-handling/index.md | 15 +++++++-------- 1 file changed, 7 insertions(+), 8 deletions(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index d5afd2a37ad..e54d21c7199 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -101,12 +101,12 @@ In the code above, `take(msg, msg_info)` is called by `sub_` instance which is c `take(msg, msg_info)` returns `false` if a message is not taken from Subscription. When `take(msg, msg_info)` is called, if the size of Subscription Queue is larger than one and there are two or more messages in the queue, then the oldest message is copied to `msg`. If the size of Queue is one, the latest message is always obtained. -!!! Note - You can check the presence of incoming message with the returned value of `take()` method. However, you have to take care of destructive nature of take() method. `take()` method changes the subscription queue. Besides, `take()` method is irreversible while there is no undo operation against `take()` method. Checking the incoming message with only `take()` method always changes the subscription queue. If you want to check without changing the subscription queue, rclcpp::WaitSet is recommended. - Refer to [[supplement] Use rclcpp::WaitSet](./02-supp-waitset.md) for more detail. +!!! Note +You can check the presence of incoming message with the returned value of `take()` method. However, you have to take care of destructive nature of take() method. `take()` method changes the subscription queue. Besides, `take()` method is irreversible while there is no undo operation against `take()` method. Checking the incoming message with only `take()` method always changes the subscription queue. If you want to check without changing the subscription queue, rclcpp::WaitSet is recommended. +Refer to [[supplement] Use rclcpp::WaitSet](./02-supp-waitset.md) for more detail. !!! Note - `take()` method is supported to only obtain a message which is passed through DDS as an inter-process communication. You must not use it for an intra-process communication because intra-process communication is based on another software stack of `rclcpp`. Refer to [[supplement] Obtain a received message through intra-process communication](./01-supp-intra-process-comm.md) in case of intra-process communication. +`take()` method is supported to only obtain a message which is passed through DDS as an inter-process communication. You must not use it for an intra-process communication because intra-process communication is based on another software stack of `rclcpp`. Refer to [[supplement] Obtain a received message through intra-process communication](./01-supp-intra-process-comm.md) in case of intra-process communication. #### 1.1 obtain Serialized Message from Subscription @@ -128,8 +128,7 @@ Here is a sample code excerpted from [ros2_subscription_examples/simple_examples In code above, `msg` is created by `create_serialized_message()` to store a received message, whose type is `std::shared_ptr`. You can obtain a message of Serialized Message type by `take_serialized()` method. Note that `take_serialized()` method needs reference type data as its first argument therefore you need to convert `msg` type using `*`. !!! Note - ROS 2's `rclcpp` supports `rclcpp::LoanedMessage` as well as `rclcpp::SerializedMessage`. If [zero copy communication via loaned messages](https://design.ros2.org/articles/zero_copy.html) is introduced to Autoware, `take_loaned()` method should be used for communication via loaned messages instead. In this document, the explanation of `take_loaned()` method is omitted because it is not used for Autoware in the present (May. 2024). - +ROS 2's `rclcpp` supports `rclcpp::LoanedMessage` as well as `rclcpp::SerializedMessage`. If [zero copy communication via loaned messages](https://design.ros2.org/articles/zero_copy.html) is introduced to Autoware, `take_loaned()` method should be used for communication via loaned messages instead. In this document, the explanation of `take_loaned()` method is omitted because it is not used for Autoware in the present (May. 2024). ### 2. obtain multiple data stored in Subscription Queue @@ -190,7 +189,7 @@ Many of ROS 2 users may feel anxious to use `take()` method because they may not ``` !!!Note - Strictly speaking, `take_type_erased()` method is called in the Executor, but not `take()` method. -But `take_type_erased()` is the embodiment of `take()`, while `take()` internally calls `take_type_erased()`. +Strictly speaking, `take_type_erased()` method is called in the Executor, but not `take()` method. +But `take_type_erased()` is the embodiment of `take()`, while `take()` internally calls `take_type_erased()`. If Executor is programmed to call a callback function, Executor itself determines when to do it. Because Executor calls a callback function with best-effort basis basically, it can occur that a message is not referred to or processed when it is needed in a node. Therefore it is desirable to call `take()` method directly **to ensue that a message is referred to or processed at the intended time.** From adc814a92fea537b66bd7148fad699de86fbd0fe Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:29:28 +0900 Subject: [PATCH 036/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index e54d21c7199..111bce72c1b 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -192,4 +192,4 @@ Many of ROS 2 users may feel anxious to use `take()` method because they may not Strictly speaking, `take_type_erased()` method is called in the Executor, but not `take()` method. But `take_type_erased()` is the embodiment of `take()`, while `take()` internally calls `take_type_erased()`. -If Executor is programmed to call a callback function, Executor itself determines when to do it. Because Executor calls a callback function with best-effort basis basically, it can occur that a message is not referred to or processed when it is needed in a node. Therefore it is desirable to call `take()` method directly **to ensue that a message is referred to or processed at the intended time.** +If Executor is programmed to call a callback function, Executor itself determines when to do it. Because Executor calls a callback function with best-effort policy basically, it can occur that a message is not referred to or processed when it is needed in a node. Therefore it is desirable to call `take()` method directly **to ensue that a message is referred to or processed at the intended time.** From fe96888cf174148170526eea8276a04afcc2a0a7 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:29:51 +0900 Subject: [PATCH 037/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 111bce72c1b..bb8066c1f04 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -171,7 +171,7 @@ You can also refer to [API document](http://docs.ros.org/en/humble/p/rclcpp/gene ### 4. obtain data by a callback function A typical method usually used is also usable, by which a message is obtained in subscription callback function . If you don't use a callback group with `automatically_add_to_executor_with_node = false`, a registered callback function is called automatically by Executor when a topic message is received. -One of advantages of this method is you don't need to take care whether a topic message is passed through inter-process or intra-process. Remind that in the enhanced method, `take()` can only be used in case of inter-process communication while `take_type_erased()` needs to be used in case of intra-process communication. +One of advantages of this method is you don't need to take care whether a topic message is passed through inter-process or intra-process. Remind that `take()` can only be used in case of inter-process communication via DDS, while another manner provided by `rlclcpp` can be used for intra-process communication via `rlclcpp`. ## Appendix From b78671341dc8c227fe139b4882cee40441d9cbcd Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:30:50 +0900 Subject: [PATCH 038/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index bb8066c1f04..db12f0ff185 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -17,7 +17,7 @@ It implicitly recommends that messages received by subscriptions should be refer [this](SteeringReport::SharedPtr msg) { current_steer_ = msg->steering_tire_angle; }); ``` -In code above, when a topic message whose name is `input/steering` is received, an anonymous function whose description is `{current_steer_ = msg->steering_tier_angle;}` is executed as a callback in a thread. The callback function is always executed when the message is received, which leads to waste computing resource if the message is not always necessary. Besides, it costs thread-wakeup overhead just to take a message. +In the code above, when a topic message whose name is `input/steering` is received, an anonymous function whose description is `{current_steer_ = msg->steering_tier_angle;}` is executed as a callback in a thread. The callback function is always executed when the message is received, which leads to waste computing resource if the message is not always necessary. Besides, it costs thread-wakeup overhead just to take a message. ## Enhanced method From a9a53e68b628096bf71c616ed6b8768fa7a3c0cc Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:31:23 +0900 Subject: [PATCH 039/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-waitset.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md index 0aec0163b78..fe3bb9444e2 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md @@ -31,7 +31,7 @@ If your code needs to proceed after several types of messages got together, usin } ``` -In code above, unless `rclcpp::WaitSet` is used, it is difficult to verify that all needed messages get together. +In the code above, unless `rclcpp::WaitSet` is used, it is impossible to verify arrival of all needed messages without changing state of the subscription objects. ## Coding method From 99c8db491a4a39662f17f302aad340fd1c8a0d59 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:31:49 +0900 Subject: [PATCH 040/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index db12f0ff185..e15df319cdb 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -72,7 +72,7 @@ Here is a sample code excerpted from [ros2_subscription_examples/simple_examples sub_ = create_subscription("chatter", qos, not_executed_callback, subscription_options); ``` -In code above, `cb_group_noexec` is created by calling `create_callback_group` with its second argument `false`. A callback function which belongs to the callback group will not be called by Executor. +In the code above, `cb_group_noexec` is created by calling `create_callback_group` with its second argument `false`. A callback function which belongs to the callback group will not be called by Executor. If `callback_group` member of `subscription_options` is set to `cb_group_noexec`, `not_executed_callback` will not be called when a corresponded topic message `chatter` is received. The second argument of `create_callback_group` is defined as below. From a7fca6e4df2bbe0c79e399f453212b3bfad39176 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:32:17 +0900 Subject: [PATCH 041/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index e15df319cdb..d4c9e0f3d70 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -153,7 +153,7 @@ It is effective to use the method if a reception of message occurs very frequent ### 3. obtain data by calling `Subscription->take` and then call a callback function -If you want to use the enhanced method introduced in this guideline, you may feel it is needed to implement a new function in which a message is taken by `take()` method and then processed. But there is a way to make a callback function be called indirectly which is registered to Subscription object. +You can combine the `take()` (strictly `take_type_erased()`) method and the callback function to process received messages in a consistent way. Using this combination does not require waking up a thread. Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener_using_callback.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener_using_callback.cpp). ```c++ From 3241515781dc3b8ed43d1ac75ce6d89f6c1ca958 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:32:53 +0900 Subject: [PATCH 042/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/index.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index d4c9e0f3d70..8c01e008f38 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -132,7 +132,8 @@ ROS 2's `rclcpp` supports `rclcpp::LoanedMessage` as well as `rclcpp::Serialized ### 2. obtain multiple data stored in Subscription Queue -Subscription can hold multiple messages in its queue. Such messages can be obtained by consecutive calls of `take()` method from a callback function at a time. Note that in a normal manner in which a subscription callback function is used to take a topic message, if there are one or more messages in Subscription Queue, the oldest one is taken and a thread is assigned to execute a callback function, which continues until the queue becomes empty. If you use `take()` method, you can obtain multiple messages at a time. +The subscription object can hold multiple messages in its queue if multiple queue size is configured with QoS setting. The conventional manner with callback function usage force a callback function to run per message. In other words, there is a constraints; a single cycle of callback function processes a single message . Note that in the conventional manner if there are one or more messages in Subscription Queue, the oldest one is taken and a thread is assigned to execute a callback function, which continues until the queue becomes empty. +`take()` method would mitigate the constraint. `take()` method can be called in multiple iterations, so that single cycle of callback function processes multiple messages taken by `take()` methods. Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_batch_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_batch_listener.cpp) in which `take()` method is called consecutively. From bb1b0be85dc58400274d00b1aef2b0ef29ce68ba Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:33:21 +0900 Subject: [PATCH 043/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 8c01e008f38..4d6d84df118 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -52,7 +52,7 @@ To use the enhanced method using `Subscription->take()`, you need to do two thin You can see an example of the typical usage of `take()` method in [ros2_subscription_examples/simple_examples/src /timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp). -#### prevent calling a callback function +#### Prevent calling a callback function To prevent a callback function from being called automatically, the callback function has to belong a callback group whose callback functions will not added to executor. Due to [API specification of `create_subscription`](http://docs.ros.org/en/iron/p/rclcpp/generated/classrclcpp_1_1Node.html), registering a callback function to a `Subscription` based object is mandatory even if the callback function has no operation. From 537f25295c7150ef5f8d23e6148fb1374f98284b Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 2 May 2024 06:33:19 +0000 Subject: [PATCH 044/225] style(pre-commit): autofix --- .../ros-nodes/topic-message-handling/index.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 4d6d84df118..1f42741bd18 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -132,8 +132,8 @@ ROS 2's `rclcpp` supports `rclcpp::LoanedMessage` as well as `rclcpp::Serialized ### 2. obtain multiple data stored in Subscription Queue -The subscription object can hold multiple messages in its queue if multiple queue size is configured with QoS setting. The conventional manner with callback function usage force a callback function to run per message. In other words, there is a constraints; a single cycle of callback function processes a single message . Note that in the conventional manner if there are one or more messages in Subscription Queue, the oldest one is taken and a thread is assigned to execute a callback function, which continues until the queue becomes empty. -`take()` method would mitigate the constraint. `take()` method can be called in multiple iterations, so that single cycle of callback function processes multiple messages taken by `take()` methods. +The subscription object can hold multiple messages in its queue if multiple queue size is configured with QoS setting. The conventional manner with callback function usage force a callback function to run per message. In other words, there is a constraints; a single cycle of callback function processes a single message . Note that in the conventional manner if there are one or more messages in Subscription Queue, the oldest one is taken and a thread is assigned to execute a callback function, which continues until the queue becomes empty. +`take()` method would mitigate the constraint. `take()` method can be called in multiple iterations, so that single cycle of callback function processes multiple messages taken by `take()` methods. Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_batch_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_batch_listener.cpp) in which `take()` method is called consecutively. @@ -154,7 +154,7 @@ It is effective to use the method if a reception of message occurs very frequent ### 3. obtain data by calling `Subscription->take` and then call a callback function -You can combine the `take()` (strictly `take_type_erased()`) method and the callback function to process received messages in a consistent way. Using this combination does not require waking up a thread. +You can combine the `take()` (strictly `take_type_erased()`) method and the callback function to process received messages in a consistent way. Using this combination does not require waking up a thread. Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener_using_callback.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener_using_callback.cpp). ```c++ From 72cd561c92d0ece97811e2b07ce714cf8579eb12 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:33:45 +0900 Subject: [PATCH 045/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 1f42741bd18..7756bf6de9f 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -83,7 +83,7 @@ rclcpp::CallbackGroup::SharedPtr create_callback_group(rclcpp::CallbackGroupType If `automatically_add_to_executor_with_node` is set to `true`, callback functions included in a node which is added to Executor will be called automatically by Executor. -#### call `take()` method of Subscription object +#### Call `take()` method of Subscription object To take a topic message from the `Subscription` based object, the `take()` method is called at the expected time. Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp) in which `take()` method is used. From 5e9f69057a5a15e44204c9ea863c9b31568f2a7f Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:34:08 +0900 Subject: [PATCH 046/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 7756bf6de9f..9372c626765 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -42,7 +42,7 @@ By using this manner, following advantages are achieved. This section introduces four manners including the recommended ones. -### 1. obtain data by calling `Subscription->take()` +### 1. Obtain data by calling `Subscription->take()` To use the enhanced method using `Subscription->take()`, you need to do two things below basically. From f63139126e68c5ca41a2acb8efd78f975c1082ec Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:34:37 +0900 Subject: [PATCH 047/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 9372c626765..a137e34bb60 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -23,7 +23,7 @@ In the code above, when a topic message whose name is `input/steering` is receiv There is an enhanced method to take a message using `Subscription->take()` method only when it is needed. The sample code given below shows that `Subscription->take()` method is called during execution of any callback function. In most cases, `Subscription->take()` method is called before a received message is consumed by a main logic. -In this case, a topic message is not obtained by a subscription callback. To be exact, you need to program your code so that a callback function is not called automatically. +In this case, a topic message is retrieved from the subscription queue, the queue embedded in the subscription object, instead of using a callback function. To be exact, you need to program your code so that a callback function is not called automatically. ```c++ SteeringReport::SharedPtr msg; From f81d2f9f17187222f32d4fbd7092de5341d246d2 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:35:02 +0900 Subject: [PATCH 048/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index a137e34bb60..cc5eff53d60 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -99,7 +99,7 @@ Here is a sample code excerpted from [ros2_subscription_examples/simple_examples In the code above, `take(msg, msg_info)` is called by `sub_` instance which is created from `Subscription` class. It is called in a timer driven callback function. `msg` and `msg_info` indicate a message body and its metadata respectively. If there is a message in the subscription queue when `take(msg, msg_info)` is called, then the message is copied to `msg`. `take(msg, msg_info)` returns `true` if a message is taken from the subscription successfully. In this case in code above, a string data of the message is outputted by `RCLCPP_INFO`. `take(msg, msg_info)` returns `false` if a message is not taken from Subscription. -When `take(msg, msg_info)` is called, if the size of Subscription Queue is larger than one and there are two or more messages in the queue, then the oldest message is copied to `msg`. If the size of Queue is one, the latest message is always obtained. +When `take(msg, msg_info)` is called, if the size of the subscription queue is larger than one and there are two or more messages in the queue, then the oldest message is copied to `msg`. If the size of the queue is one, the latest message is always obtained. !!! Note You can check the presence of incoming message with the returned value of `take()` method. However, you have to take care of destructive nature of take() method. `take()` method changes the subscription queue. Besides, `take()` method is irreversible while there is no undo operation against `take()` method. Checking the incoming message with only `take()` method always changes the subscription queue. If you want to check without changing the subscription queue, rclcpp::WaitSet is recommended. From 2e85fe9233f4c7d42bf99d4477a6c3e320304723 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:35:27 +0900 Subject: [PATCH 049/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index cc5eff53d60..603ce1d6cba 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -32,7 +32,7 @@ In this case, a topic message is retrieved from the subscription queue, the queu // processing and publishing after this ``` -By using this manner, following advantages are achieved. +Using this manner will give you following advantages. - It can reduce invocations of subscription callback functions - There is no need to take a topic message, which a main logic does not consume, from a subscription From b5f244348716b3082e78f9d713e2270de6d15068 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:35:55 +0900 Subject: [PATCH 050/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 603ce1d6cba..89bebf8de72 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -149,7 +149,7 @@ Here is a sample code excerpted from [ros2_subscription_examples/simple_examples In the code above, `while(sub->take(msg, msg_info))` continues to take messages from the subscription queue until the queue becomes empty. While a message is taken, the message is processed each by each. Note that you need to determine Subscription Queue size considering frequency of an invocation of a callback function and that of a reception of message. For example, if frequency of an invocation of a callback function is 10Hz and that of a reception of message is 50Hz, Subscription Queue size needs to be at least 5 for messages not to be lost. -To assign a thread and let it execute a callback function each time a message is received leads to increase overhead in terms of performance. You can use the method introduced in this section to avoid the overhead. +Assigning a thread to execute a callback function per message will cause performance overhead. You can use the manner introduced in this section to avoid the unexpected overhead. It is effective to use the method if a reception of message occurs very frequently but it doesn't need to be processed with so high frequency. For example, if a message is received with more than 100 Hz such as CAN message, it is desirable to obtain multiple messages in a callback function at a time with one thread invocation. ### 3. obtain data by calling `Subscription->take` and then call a callback function From c0b3b391bc54181c9143ed615e58e2ff4cfdcb45 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:36:27 +0900 Subject: [PATCH 051/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 89bebf8de72..d27aa0cb76a 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -147,7 +147,7 @@ Here is a sample code excerpted from [ros2_subscription_examples/simple_examples ``` In the code above, `while(sub->take(msg, msg_info))` continues to take messages from the subscription queue until the queue becomes empty. While a message is taken, the message is processed each by each. -Note that you need to determine Subscription Queue size considering frequency of an invocation of a callback function and that of a reception of message. For example, if frequency of an invocation of a callback function is 10Hz and that of a reception of message is 50Hz, Subscription Queue size needs to be at least 5 for messages not to be lost. +Note that you need to determine size of a subscription queue considering both frequency of a callback function and that of a message reception. For example, if a callback function is invoked at 10Hz and topic messages are received at 50Hz, the size of the subscription queue must be at least 5 not to lose received messages. Assigning a thread to execute a callback function per message will cause performance overhead. You can use the manner introduced in this section to avoid the unexpected overhead. It is effective to use the method if a reception of message occurs very frequently but it doesn't need to be processed with so high frequency. For example, if a message is received with more than 100 Hz such as CAN message, it is desirable to obtain multiple messages in a callback function at a time with one thread invocation. From 84c293d8a92842fbba2033d8a819b311ddbc5171 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:36:54 +0900 Subject: [PATCH 052/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index d27aa0cb76a..0a10ab547a5 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -150,7 +150,7 @@ In the code above, `while(sub->take(msg, msg_info))` continues to take messages Note that you need to determine size of a subscription queue considering both frequency of a callback function and that of a message reception. For example, if a callback function is invoked at 10Hz and topic messages are received at 50Hz, the size of the subscription queue must be at least 5 not to lose received messages. Assigning a thread to execute a callback function per message will cause performance overhead. You can use the manner introduced in this section to avoid the unexpected overhead. -It is effective to use the method if a reception of message occurs very frequently but it doesn't need to be processed with so high frequency. For example, if a message is received with more than 100 Hz such as CAN message, it is desirable to obtain multiple messages in a callback function at a time with one thread invocation. +The manner will be effective if there is a large difference between reception frequency and consumption frequency. For example, even if a message, like a CAN message, is received at higher than 100 Hz, a user logic consumes messages at slower frequency like 10 Hz. In such case, the user logic should retrieve the required number of messages with `take()` method to avoid the unexpected overhead. ### 3. obtain data by calling `Subscription->take` and then call a callback function From 1887c69c32181f7a3089460bb3133cd173843755 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:37:22 +0900 Subject: [PATCH 053/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 0a10ab547a5..a2936905c2a 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -165,7 +165,7 @@ Here is a sample code excerpted from [ros2_subscription_examples/simple_examples ``` -In code above, a message is taken by `take_type_erased()` method before calling a registered callback function. Note that you need to use `take_type_erased()` instead of `take()` and that `take_type_erased()` needs `void` type data as its first argument. You need to use `get()` method to convert `msg` whose type is `shared_ptr` to `void` type. Then `handle_message()` method is called with the obtained message. A registered callback function is called inside of `handle_message()`. +In the code above, a message is taken by `take_type_erased()` method before calling a registered callback function via `handle_message()` method. Note that you need to use `take_type_erased()` instead of `take()`. `take_type_erased()` needs `void` type data as its first argument. You need to use `get()` method to convert `msg` whose type is `shared_ptr` to `void` type. Then `handle_message()` method is called with the obtained message. A registered callback function is called inside of `handle_message()`. You don't need to take special care of message type which is passed to `take_type_erased()`, the same as `take_type_erased()` and `handle_message()` are not based on any specific types. You can define message variable as `auto msg = sub_->create_message();`. You can also refer to [API document](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1SubscriptionBase.html#_CPPv4N6rclcpp16SubscriptionBase16take_type_erasedEPvRN6rclcpp11MessageInfoE) as for `create_message()`, `take_type_erased()` and `handle_message()`. From 8e6bacf307730e3dc48e67ad170e9c8788dce681 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:38:02 +0900 Subject: [PATCH 054/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index a2936905c2a..7e7ae7f8b4c 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -166,7 +166,7 @@ Here is a sample code excerpted from [ros2_subscription_examples/simple_examples ``` In the code above, a message is taken by `take_type_erased()` method before calling a registered callback function via `handle_message()` method. Note that you need to use `take_type_erased()` instead of `take()`. `take_type_erased()` needs `void` type data as its first argument. You need to use `get()` method to convert `msg` whose type is `shared_ptr` to `void` type. Then `handle_message()` method is called with the obtained message. A registered callback function is called inside of `handle_message()`. -You don't need to take special care of message type which is passed to `take_type_erased()`, the same as `take_type_erased()` and `handle_message()` are not based on any specific types. You can define message variable as `auto msg = sub_->create_message();`. +You don't need to take care of message type which is passed to `take_type_erased()` and `handle_message()`. You can define the message variable as `auto msg = sub_->create_message();`. You can also refer to [API document](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1SubscriptionBase.html#_CPPv4N6rclcpp16SubscriptionBase16take_type_erasedEPvRN6rclcpp11MessageInfoE) as for `create_message()`, `take_type_erased()` and `handle_message()`. ### 4. obtain data by a callback function From 508cc74e8e238bf3d2e574b9bc45474efb82ad65 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:38:23 +0900 Subject: [PATCH 055/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 7e7ae7f8b4c..bcf51754892 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -171,7 +171,7 @@ You can also refer to [API document](http://docs.ros.org/en/humble/p/rclcpp/gene ### 4. obtain data by a callback function -A typical method usually used is also usable, by which a message is obtained in subscription callback function . If you don't use a callback group with `automatically_add_to_executor_with_node = false`, a registered callback function is called automatically by Executor when a topic message is received. +A conventional manner used typically in ROS 2 application, a message reference using a callback function, is available. If you don't use a callback group with `automatically_add_to_executor_with_node = false`, a registered callback function is called automatically by Executor when a topic message is received. One of advantages of this method is you don't need to take care whether a topic message is passed through inter-process or intra-process. Remind that `take()` can only be used in case of inter-process communication via DDS, while another manner provided by `rlclcpp` can be used for intra-process communication via `rlclcpp`. ## Appendix From f69cdb6e90ed0c5e931088bc6bd745ef418c14df Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:38:39 +0900 Subject: [PATCH 056/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index bcf51754892..0c9c967e923 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -125,7 +125,7 @@ Here is a sample code excerpted from [ros2_subscription_examples/simple_examples } ``` -In code above, `msg` is created by `create_serialized_message()` to store a received message, whose type is `std::shared_ptr`. You can obtain a message of Serialized Message type by `take_serialized()` method. Note that `take_serialized()` method needs reference type data as its first argument therefore you need to convert `msg` type using `*`. +In the code above, `msg` is created by `create_serialized_message()` to store a received message, whose type is `std::shared_ptr`. You can obtain a message of Serialized Message type by `take_serialized()` method. Note that `take_serialized()` method needs reference type data as its first argument therefore you need to convert `msg` type using `*`. !!! Note ROS 2's `rclcpp` supports `rclcpp::LoanedMessage` as well as `rclcpp::SerializedMessage`. If [zero copy communication via loaned messages](https://design.ros2.org/articles/zero_copy.html) is introduced to Autoware, `take_loaned()` method should be used for communication via loaned messages instead. In this document, the explanation of `take_loaned()` method is omitted because it is not used for Autoware in the present (May. 2024). From 72a2260988bf0f0d98efbb40fcdbf2e9aad96986 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:38:56 +0900 Subject: [PATCH 057/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 0c9c967e923..b1f30b89441 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -2,7 +2,7 @@ ## Introduction -Here is coding guideline for a topic message handling method which includes more enhanced method than usually used one, which is roughly explained in [Discussions page](https://github.com/orgs/autowarefoundation/discussions/4612). Refer to the page to understand the basic concept of the enhanced method. +Here is coding guideline for a topic message handling in Autoware. It includes the recommended manner than conventional one, which is roughly explained in [Discussions page](https://github.com/orgs/autowarefoundation/discussions/4612). Refer to the page to understand the basic concept of the enhanced method. You can find sample source codes in [ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples) referred from this document. ## Typical message handling method usually used From 4cf187945aad10f243953c7be2f9d14070b997b3 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 2 May 2024 06:39:27 +0000 Subject: [PATCH 058/225] style(pre-commit): autofix --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index b1f30b89441..15ed75191d8 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -171,7 +171,7 @@ You can also refer to [API document](http://docs.ros.org/en/humble/p/rclcpp/gene ### 4. obtain data by a callback function -A conventional manner used typically in ROS 2 application, a message reference using a callback function, is available. If you don't use a callback group with `automatically_add_to_executor_with_node = false`, a registered callback function is called automatically by Executor when a topic message is received. +A conventional manner used typically in ROS 2 application, a message reference using a callback function, is available. If you don't use a callback group with `automatically_add_to_executor_with_node = false`, a registered callback function is called automatically by Executor when a topic message is received. One of advantages of this method is you don't need to take care whether a topic message is passed through inter-process or intra-process. Remind that `take()` can only be used in case of inter-process communication via DDS, while another manner provided by `rlclcpp` can be used for intra-process communication via `rlclcpp`. ## Appendix From 0d4d2453bd56894ef462a2c26049662822865c98 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:42:41 +0900 Subject: [PATCH 059/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../topic-message-handling/01-supp-intra-process-comm.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index b1921ae9d02..23266947120 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -2,7 +2,7 @@ ## Topic message handling in intra-process communication -rclcpp supports intra-process communication. As explained in [Topic message handling guideline](index.md), `take()` method of Subscription can not be used in case of intra-process communication. `take()` can not obtain a topic message which is received through inter-process communication. Besides, even though a method is provided to obtain a received topic message through intra-process communication, a method is not provided to refer to the message directly. +rclcpp supports intra-process communication. As explained in [Topic message handling guideline](index.md), `take()` method can not be used in case of intra-process communication. `take()` can not return a topic message which is received through inter-process communication. But a method are provided for intra-process communication similar to a method for inter-process communication described in [obtain data by calling Subscription->take and then call a callback function](./index.md#3-obtain-data-by-calling-subscription-take-and-then-call-a-callback-function). `take_data()` method is provided to obtain a received data in case of intra-process communication and the received data must be processed through `execute()` method. Refer to [Template Class SubscriptionIntraProcess — rclcpp 16.0.8 documentation](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1experimental_1_1SubscriptionIntraProcess.html#_CPPv4N6rclcpp12experimental24SubscriptionIntraProcess9take_dataEv) for `take_data()` and `execute()` for more detail. From ddd6ebb3ba2516f4e548bf679b8e5ce6db3b6b35 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:42:58 +0900 Subject: [PATCH 060/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../topic-message-handling/01-supp-intra-process-comm.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index 23266947120..0c681637f66 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -4,7 +4,7 @@ rclcpp supports intra-process communication. As explained in [Topic message handling guideline](index.md), `take()` method can not be used in case of intra-process communication. `take()` can not return a topic message which is received through inter-process communication. But a method are provided for intra-process communication similar to a method for inter-process communication described in [obtain data by calling Subscription->take and then call a callback function](./index.md#3-obtain-data-by-calling-subscription-take-and-then-call-a-callback-function). -`take_data()` method is provided to obtain a received data in case of intra-process communication and the received data must be processed through `execute()` method. +`take_data()` method is provided to obtain a received data in case of intra-process communication and the received data must be processed through `execute()` method. The return value of `take_data()` is based on the complicated data structure, `execute()` method should be used along with `take_data()` method. Refer to [Template Class SubscriptionIntraProcess — rclcpp 16.0.8 documentation](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1experimental_1_1SubscriptionIntraProcess.html#_CPPv4N6rclcpp12experimental24SubscriptionIntraProcess9take_dataEv) for `take_data()` and `execute()` for more detail. ## coding method From 70bf2b454b51b752e94a6a24d6c361431b3e3b01 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:43:15 +0900 Subject: [PATCH 061/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../topic-message-handling/01-supp-intra-process-comm.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index 0c681637f66..1a54cd1cafa 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -7,7 +7,7 @@ But a method are provided for intra-process communication similar to a method fo `take_data()` method is provided to obtain a received data in case of intra-process communication and the received data must be processed through `execute()` method. The return value of `take_data()` is based on the complicated data structure, `execute()` method should be used along with `take_data()` method. Refer to [Template Class SubscriptionIntraProcess — rclcpp 16.0.8 documentation](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1experimental_1_1SubscriptionIntraProcess.html#_CPPv4N6rclcpp12experimental24SubscriptionIntraProcess9take_dataEv) for `take_data()` and `execute()` for more detail. -## coding method +## Coding manner Call `take_data()` method and then `execute()` method as below. From a82036d9d9560307f1164f5050741f586b9ddfac Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:43:31 +0900 Subject: [PATCH 062/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../topic-message-handling/01-supp-intra-process-comm.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index 1a54cd1cafa..64e18cc01bc 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -9,7 +9,7 @@ Refer to [Template Class SubscriptionIntraProcess — rclcpp 16.0.8 documentatio ## Coding manner -Call `take_data()` method and then `execute()` method as below. +To handle messages via intra-process communication, call `take_data()` method and then `execute()` method as below. ```c++ // Execute any entities of the Waitable that may be ready From 92c51cb1512963ce22b8f1df23fc1b1aaadfa13a Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:43:52 +0900 Subject: [PATCH 063/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../topic-message-handling/01-supp-intra-process-comm.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index 64e18cc01bc..4959682b672 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -45,7 +45,7 @@ Here is a excerption from [ros2_subscription_examples/intra_process_talker_liste intra_process_sub->execute(data); ``` -Below is explanation of above code one line by one. +Below is explanation of the above code one line by one. - `if (this->get_node_options().use_intra_process_comms()){` From e287933ce38a5a507651c9b5c0a0e27069ec4537 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:44:18 +0900 Subject: [PATCH 064/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../topic-message-handling/01-supp-intra-process-comm.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index 4959682b672..6589e1e1ee2 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -49,7 +49,7 @@ Below is explanation of the above code one line by one. - `if (this->get_node_options().use_intra_process_comms()){` - - verify intra-process communication is enabled or not by using NodeOptions + - the statement verifies intra-process communication is enabled or not by using `NodeOptions` - `auto intra_process_sub = sub_->get_intra_process_waitable();` From 1e9eeb98e9d98f35c63181372411ed5f4cc649d8 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:44:30 +0900 Subject: [PATCH 065/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../topic-message-handling/01-supp-intra-process-comm.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index 6589e1e1ee2..603ec6ca75c 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -53,7 +53,7 @@ Below is explanation of the above code one line by one. - `auto intra_process_sub = sub_->get_intra_process_waitable();` - - get an object which is used by Subscription in case of intra-process communication + - the statement means to get an embodied object which performs intra-process communication - `if (intra_process_sub->is_ready(nullptr) == true) {` From 9a32617e626c9b10a5f5cbab4690c748e88422bb Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:44:52 +0900 Subject: [PATCH 066/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../topic-message-handling/01-supp-intra-process-comm.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index 603ec6ca75c..1fad365ea13 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -57,7 +57,7 @@ Below is explanation of the above code one line by one. - `if (intra_process_sub->is_ready(nullptr) == true) {` - - check if a message has already been received through intra-process communication + - the statement checks if a message has already been received through intra-process communication - the argument of `is_ready()` is of rcl_wait_set_t type, but because the argument is not used inside `is_ready()`, `nullptr` is used tentatively - using `nullptr` is a workaround at this point of time, because it is not preferable From 55f482a15a7256c93fc57f258b22beff635971b1 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:45:01 +0900 Subject: [PATCH 067/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../topic-message-handling/01-supp-intra-process-comm.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index 1fad365ea13..890f1b3ec26 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -58,7 +58,7 @@ Below is explanation of the above code one line by one. - `if (intra_process_sub->is_ready(nullptr) == true) {` - the statement checks if a message has already been received through intra-process communication - - the argument of `is_ready()` is of rcl_wait_set_t type, but because the argument is not used inside `is_ready()`, `nullptr` is used tentatively + - the argument of `is_ready()` is of `rcl_wait_set_t` type, but because the argument is not used inside `is_ready()`, `nullptr` is used tentatively - using `nullptr` is a workaround at this point of time, because it is not preferable - `std::shared_ptr data = intra_process_sub->take_data();` From 0cfdee98ef50befcaffa50b90c33420c1dbf0fe9 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:45:09 +0900 Subject: [PATCH 068/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../topic-message-handling/01-supp-intra-process-comm.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index 890f1b3ec26..f83f44bcc3c 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -59,7 +59,7 @@ Below is explanation of the above code one line by one. - the statement checks if a message has already been received through intra-process communication - the argument of `is_ready()` is of `rcl_wait_set_t` type, but because the argument is not used inside `is_ready()`, `nullptr` is used tentatively - - using `nullptr` is a workaround at this point of time, because it is not preferable + - using `nullptr` is a workaround at the present because it is does not have any intention. - `std::shared_ptr data = intra_process_sub->take_data();` From 77d5d03e3433718b410f150959bd6f3bbb590dab Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:45:26 +0900 Subject: [PATCH 069/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../topic-message-handling/01-supp-intra-process-comm.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index f83f44bcc3c..91bbc87cb2d 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -63,7 +63,7 @@ Below is explanation of the above code one line by one. - `std::shared_ptr data = intra_process_sub->take_data();` - - obtain a topic message + - this statement means to obtain a topic message from subscriptions for intra-process communication. - `intra_process_sub->take_data()` does not return Boolean value which indicates a message is received successfully or not, therefore it is needed to verify it by calling `is_ready()` in advance - `intra_process_sub->execute(data);` From 89b3e4787f7ae276beb98ef2ecc487838cdc6f88 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:46:39 +0900 Subject: [PATCH 070/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-waitset.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md index fe3bb9444e2..4ba9158d94e 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md @@ -2,7 +2,7 @@ ## What is `rclcpp::WaitSet` -As explained in [call take() method of Subscription object](./index.md#call-take-method-of-subscription-object), `take()` method is irreversible. Once `take()` method is executed, Subscription object state changes and undo can not be applied, therefore Subscription object can not be restored to previous state. You can use `rclcpp::WaitSet` in advance to call `take()` so that a message is received after verifying it is in Subscription Queue. +As explained in [call take() method of Subscription object](./index.md#call-take-method-of-subscription-object), `take()` method is irreversible. Once `take()` method is executed, state of the subscription object changes. Because of no undo operation against `take()` method, the subscription object can not be restored to previous state. You can use `rclcpp::WaitSet` before calling `take()` to check arrival of any incoming message in the subscription queue. Here is a sample code in which `wait_set_.wait()` tells you that a message has already been received and can be obtained by `take()`. ```c++ From b72e848a56eb46a5c9a39cb1beb77b51ed8b21d5 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:47:01 +0900 Subject: [PATCH 071/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-waitset.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md index 4ba9158d94e..897483de2b5 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md @@ -14,7 +14,7 @@ Here is a sample code in which `wait_set_.wait()` tells you that a message has a RCLCPP_INFO(this->get_logger(), "I heard: [%s]", msg.data.c_str()); ``` -Also you can verify that there are messages in multiple Subscription Queues in advance. +A single `rclcpp::WaitSet` object is able to observe multiple subscription objects. If there are multiple subscriptions for different topics, you can check arrival of incoming messages per subscription. Algorithms used in the field of autonomous robot requires multiple incoming messages, like sensor data or actuation state. Using `rclcpp::WaitSet` for the multiple subscriptions, they are able to check whether of not required messages have arrived without taking any message. If your code needs to proceed after several types of messages got together, using `rclcpp::WaitSet` is preferable. ```c++ From 6d0898d4f2bcef7948c23556e7f2e5d969373e97 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:47:28 +0900 Subject: [PATCH 072/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-waitset.md | 1 - 1 file changed, 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md index 897483de2b5..fbcfd1e8b6c 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md @@ -15,7 +15,6 @@ Here is a sample code in which `wait_set_.wait()` tells you that a message has a ``` A single `rclcpp::WaitSet` object is able to observe multiple subscription objects. If there are multiple subscriptions for different topics, you can check arrival of incoming messages per subscription. Algorithms used in the field of autonomous robot requires multiple incoming messages, like sensor data or actuation state. Using `rclcpp::WaitSet` for the multiple subscriptions, they are able to check whether of not required messages have arrived without taking any message. -If your code needs to proceed after several types of messages got together, using `rclcpp::WaitSet` is preferable. ```c++ auto wait_result = wait_set_.wait(std::chrono::milliseconds(0)); From ab8615ba97cf451454a8cc2e125566a0b51625e1 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:47:43 +0900 Subject: [PATCH 073/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-waitset.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md index fbcfd1e8b6c..0f7abd76ad5 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md @@ -34,7 +34,7 @@ In the code above, unless `rclcpp::WaitSet` is used, it is impossible to verify ## Coding method -We will explain coding method of `rclcpp::WaitSet` using a sample code below. +This section explains the coding manner using `rclcpp::WaitSet` with a sample code below. - [ros2_subscription_examples/waitset_examples/src/talker_triple.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/talker_triple.cpp) - it publishes `/chatter` per one second, `/slower_chatter` per two seconds, and `/slowest_chatter` per three seconds periodically From 9ca747b1c78f04275482dbd756fd02ca102da8b1 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:48:05 +0900 Subject: [PATCH 074/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-waitset.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md index 0f7abd76ad5..f94904d4128 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md @@ -53,7 +53,8 @@ Below is excerption from [ros2_subscription_examples/waitset_examples/src/timer_ rclcpp::WaitSet wait_set_; ``` -Note that there are three types of `WaitSet` as below. +`rlcpp::WaitSet` object can be configured during runtime. It is not thread-safe as explained [the API specification](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1ad6fb19c154de27e92430309d2da25ac3.html) +Thread-safe `WaitSet` are prepared by the `rclcpp` package as listed below. - [Typedef rclcpp::WaitSet](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1ad6fb19c154de27e92430309d2da25ac3.html) - Subscription, Timer, and so on can be registered to WaitSet at any time From 8bb54f55e0f9f97d2b5ae42329324530fb673113 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:48:16 +0900 Subject: [PATCH 075/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-waitset.md | 2 -- 1 file changed, 2 deletions(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md index f94904d4128..8e76892d140 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md @@ -56,8 +56,6 @@ rclcpp::WaitSet wait_set_; `rlcpp::WaitSet` object can be configured during runtime. It is not thread-safe as explained [the API specification](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1ad6fb19c154de27e92430309d2da25ac3.html) Thread-safe `WaitSet` are prepared by the `rclcpp` package as listed below. -- [Typedef rclcpp::WaitSet](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1ad6fb19c154de27e92430309d2da25ac3.html) - - Subscription, Timer, and so on can be registered to WaitSet at any time - [Typedef rclcpp::ThreadSafeWaitSet](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1acaec573e71549fd3078644e18e7f7127.html) - Subscription, Timer, and so on can be registered to WaitSet only in thread-safe state - sample code is here: [examples/rclcpp/wait_set/src/thread_safe_wait_set.cpp at rolling · ros2/examples](https://github.com/ros2/examples/blob/rolling/rclcpp/wait_set/src/thread_safe_wait_set.cpp) From d48b9036da2b21499fc78dd8e60951e76d94229e Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:48:42 +0900 Subject: [PATCH 076/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-waitset.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md index 8e76892d140..9ceaadeed46 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md @@ -81,7 +81,7 @@ Below is excerption from [ros2_subscription_examples/waitset_examples/src/timer_ } ``` -In code above, created subscriptions are registered to `WaitSet` by `add_subscription()`. +In the code above, created subscriptions are registered to the `wait_set_` object by `add_subscription()` method. You can also register another type of trigger to WaitSet by which a callback function registered to Subscription is invoked, such as Timer, Service, or Action. A sample code to register Timer trigger is here. From 6929da8e16df77c18085efced3c9260c2058507a Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:49:03 +0900 Subject: [PATCH 077/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-waitset.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md index 9ceaadeed46..1a143080809 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md @@ -82,7 +82,7 @@ Below is excerption from [ros2_subscription_examples/waitset_examples/src/timer_ ``` In the code above, created subscriptions are registered to the `wait_set_` object by `add_subscription()` method. -You can also register another type of trigger to WaitSet by which a callback function registered to Subscription is invoked, such as Timer, Service, or Action. +`rclcpp::WaitSet`-based object basically handles objects each of which have a corresponding callback function. Not only `Subscription` based objects, but `Timer`, `Service` or `Action` based objects can be observed by `rclcpp::WaitSet`-based object. A single `WaitSet` object accepts mixture of different types of objects. A sample code to register Timer trigger is here. ```c++ From 9d345b93fed38321327a5c01abb607ceadc5aba9 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:49:16 +0900 Subject: [PATCH 078/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-waitset.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md index 1a143080809..4a5510407fd 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md @@ -93,7 +93,8 @@ A trigger can be registered at declaration and initialization as [https://github ### 3. verify WaitSet result -You can see WaitSet result by doing 1 below first and then 2 below. +The data structure of testing result returned from `WaitSet` is nested. +You can find `WaitSet` result by the following 2 steps; 1. verifying if any trigger has been invoked 2. verifying if specified trigger has been invoked From 49fc5749b227c85232a927266bb9f1c5872bed67 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:49:31 +0900 Subject: [PATCH 079/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-waitset.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md index 4a5510407fd..e4799648810 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md @@ -96,7 +96,7 @@ A trigger can be registered at declaration and initialization as [https://github The data structure of testing result returned from `WaitSet` is nested. You can find `WaitSet` result by the following 2 steps; -1. verifying if any trigger has been invoked +1. Verify if any trigger has been invoked 2. verifying if specified trigger has been invoked As for 1, here is a sample code excerpted from [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp). From dc01618bf8239b7803dacb128cb35e146215ac68 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:49:51 +0900 Subject: [PATCH 080/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-waitset.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md index e4799648810..eb33c8dfdb6 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md @@ -97,7 +97,7 @@ The data structure of testing result returned from `WaitSet` is nested. You can find `WaitSet` result by the following 2 steps; 1. Verify if any trigger has been invoked -2. verifying if specified trigger has been invoked +2. Verify if a specified trigger has been invoked As for 1, here is a sample code excerpted from [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp). From c1ad1bc81f863ecda533d5bb0763d3033608d22e Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:50:18 +0900 Subject: [PATCH 081/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-waitset.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md index eb33c8dfdb6..17dd75d4e5c 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md @@ -99,7 +99,7 @@ You can find `WaitSet` result by the following 2 steps; 1. Verify if any trigger has been invoked 2. Verify if a specified trigger has been invoked -As for 1, here is a sample code excerpted from [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp). +For step 1., here is a sample code excerpted from [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp). ```c++ auto wait_result = wait_set_.wait(std::chrono::milliseconds(0)); From a7f359fa3927646b88aa5a6bb7518005b0c04aa7 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:50:35 +0900 Subject: [PATCH 082/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-waitset.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md index 17dd75d4e5c..9dda8da7f9e 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md @@ -111,7 +111,7 @@ For step 1., here is a sample code excerpted from [ros2_subscription_examples/wa } ``` -In code above, it is verified whether any trigger has been invoked which is registered to `wait_set_` by `auto wait_result = wait_set_.wait(std::chrono::milliseconds(0))`. +In the code above, `auto wait_result = wait_set_.wait(std::chrono::milliseconds(0))` tests whether any trigger in `wait_set_` has been invoked. The argument to the `wait()` method is duration for timeout. If it is greater than 0 milliseconds or seconds, this method will wait for message reception until timeout. if `wait_result.kind() == rclcpp::WaitResultKind::Ready` is `true`, it indicates any trigger has been invoked. As for 2, here is a sample code excerpted from [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp). From 634bc9273179395a3a19d1e23154bd4dea809e40 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:50:56 +0900 Subject: [PATCH 083/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-waitset.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md index 9dda8da7f9e..948315ae19e 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md @@ -112,7 +112,7 @@ For step 1., here is a sample code excerpted from [ros2_subscription_examples/wa ``` In the code above, `auto wait_result = wait_set_.wait(std::chrono::milliseconds(0))` tests whether any trigger in `wait_set_` has been invoked. The argument to the `wait()` method is duration for timeout. If it is greater than 0 milliseconds or seconds, this method will wait for message reception until timeout. -if `wait_result.kind() == rclcpp::WaitResultKind::Ready` is `true`, it indicates any trigger has been invoked. +If `wait_result.kind() == rclcpp::WaitResultKind::Ready` is `true`, any trigger has been invoked. As for 2, here is a sample code excerpted from [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp). From c41be374b3273015b6ccab5163569fba0a3a5bac Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:51:15 +0900 Subject: [PATCH 084/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-waitset.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md index 948315ae19e..1b4d4430d57 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md @@ -114,7 +114,7 @@ For step 1., here is a sample code excerpted from [ros2_subscription_examples/wa In the code above, `auto wait_result = wait_set_.wait(std::chrono::milliseconds(0))` tests whether any trigger in `wait_set_` has been invoked. The argument to the `wait()` method is duration for timeout. If it is greater than 0 milliseconds or seconds, this method will wait for message reception until timeout. If `wait_result.kind() == rclcpp::WaitResultKind::Ready` is `true`, any trigger has been invoked. -As for 2, here is a sample code excerpted from [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp). +For step 2., here is a sample code excerpted from [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp). ```c++ for (size_t i = 0; i < subscriptions_num; i++) { From 0138c58a41c2f5a0bc41c17ca55789402c53d88e Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 2 May 2024 15:51:29 +0900 Subject: [PATCH 085/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-waitset.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md index 1b4d4430d57..5d1751fbd6f 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md @@ -126,4 +126,4 @@ For step 2., here is a sample code excerpted from [ros2_subscription_examples/wa RCLCPP_INFO(this->get_logger(), "I heard: [%s]", msg.data.c_str()); ``` -In code above, `wait_result.get_wait_set().get_rcl_wait_set().subscriptions[i]` indicates whether each individual trigger has been invoked or not. The result is stored to `subscriptions` array. The order in `subscriptions` array is the same as the order in which triggers are registered. +In the code above, `wait_result.get_wait_set().get_rcl_wait_set().subscriptions[i]` indicates whether each individual trigger has been invoked or not. The result is stored to `subscriptions` array. The order in `subscriptions` array is the same as the order in which triggers are registered. From 6627ff382477b134597fbce943d63b843e68027e Mon Sep 17 00:00:00 2001 From: ohsawa1204 Date: Thu, 2 May 2024 16:38:37 +0900 Subject: [PATCH 086/225] docs(topic-message-handling): some corrections related to Akamine-san's review Signed-off-by: ohsawa1204 --- .../01-supp-intra-process-comm.md | 4 +-- .../topic-message-handling/02-supp-waitset.md | 8 +++--- .../ros-nodes/topic-message-handling/index.md | 26 +++++++++---------- 3 files changed, 19 insertions(+), 19 deletions(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index 91bbc87cb2d..4813e7ba483 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -3,7 +3,7 @@ ## Topic message handling in intra-process communication rclcpp supports intra-process communication. As explained in [Topic message handling guideline](index.md), `take()` method can not be used in case of intra-process communication. `take()` can not return a topic message which is received through inter-process communication. -But a method are provided for intra-process communication similar to a method for inter-process communication described in [obtain data by calling Subscription->take and then call a callback function](./index.md#3-obtain-data-by-calling-subscription-take-and-then-call-a-callback-function). +But methods are provided for intra-process communication similar to methods for inter-process communication described in [obtain data by calling Subscription->take and then call a callback function](./index.md#3-obtain-data-by-calling-subscription-take-and-then-call-a-callback-function). `take_data()` method is provided to obtain a received data in case of intra-process communication and the received data must be processed through `execute()` method. The return value of `take_data()` is based on the complicated data structure, `execute()` method should be used along with `take_data()` method. Refer to [Template Class SubscriptionIntraProcess — rclcpp 16.0.8 documentation](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1experimental_1_1SubscriptionIntraProcess.html#_CPPv4N6rclcpp12experimental24SubscriptionIntraProcess9take_dataEv) for `take_data()` and `execute()` for more detail. @@ -59,7 +59,7 @@ Below is explanation of the above code one line by one. - the statement checks if a message has already been received through intra-process communication - the argument of `is_ready()` is of `rcl_wait_set_t` type, but because the argument is not used inside `is_ready()`, `nullptr` is used tentatively - - using `nullptr` is a workaround at the present because it is does not have any intention. + - using `nullptr` is a workaround at the present because it does not have any intention. - `std::shared_ptr data = intra_process_sub->take_data();` diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md index 5d1751fbd6f..2cc87da4b1c 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md @@ -32,7 +32,7 @@ A single `rclcpp::WaitSet` object is able to observe multiple subscription objec In the code above, unless `rclcpp::WaitSet` is used, it is impossible to verify arrival of all needed messages without changing state of the subscription objects. -## Coding method +## Coding manner This section explains the coding manner using `rclcpp::WaitSet` with a sample code below. @@ -44,7 +44,7 @@ This section explains the coding manner using `rclcpp::WaitSet` with a sample co Following three steps are needed to use `WaitSet`. -### 1. declare and initialize `WaitSet` +### 1. Declare and initialize `WaitSet` You need to declare WaitSet variable first to use. Below is excerption from [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp). @@ -65,7 +65,7 @@ Thread-safe `WaitSet` are prepared by the `rclcpp` package as listed below. - [ros2_subscription_examples/waitset_examples/src/timer_listener_twin_static.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_twin_static.cpp) - [examples/rclcpp/wait_set/src/static_wait_set.cpp at rolling · ros2/examples](https://github.com/ros2/examples/blob/rolling/rclcpp/wait_set/src/static_wait_set.cpp) -### 2. register trigger (Subscription, Timer, and so on) to `WaitSet` +### 2. Register trigger (Subscription, Timer, and so on) to `WaitSet` You need to register a trigger to `WaitSet`. Below is excerption from [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp) @@ -91,7 +91,7 @@ wait_set_.add_timer(much_slower_timer_); A trigger can be registered at declaration and initialization as [https://github.com/ros2/examples/blob/rolling/rclcpp/wait_set/src/wait_set_topics_and_timer.cpp#L66](https://github.com/ros2/examples/blob/rolling/rclcpp/wait_set/src/wait_set_topics_and_timer.cpp#L66). -### 3. verify WaitSet result +### 3. Verify WaitSet result The data structure of testing result returned from `WaitSet` is nested. You can find `WaitSet` result by the following 2 steps; diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 15ed75191d8..b77e8e422eb 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -2,12 +2,12 @@ ## Introduction -Here is coding guideline for a topic message handling in Autoware. It includes the recommended manner than conventional one, which is roughly explained in [Discussions page](https://github.com/orgs/autowarefoundation/discussions/4612). Refer to the page to understand the basic concept of the enhanced method. +Here is coding guideline for a topic message handling in Autoware. It includes the recommended manner than conventional one, which is roughly explained in [Discussions page](https://github.com/orgs/autowarefoundation/discussions/4612). Refer to the page to understand the basic concept of the recommended manner. You can find sample source codes in [ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples) referred from this document. -## Typical message handling method usually used +## Typical message handling manner usually used -At first, let us see a typical message handling method usually used. +At first, let us see a typical message handling manner usually used. [ROS 2 Tutorials](https://docs.ros.org/en/rolling/Tutorials/Beginner-Client-Libraries/Writing-A-Simple-Cpp-Publisher-And-Subscriber.html#write-the-subscriber-node) is one of the most cited references for ROS 2 applications, including Autoware. It implicitly recommends that messages received by subscriptions should be referred and processed by a dedicated callback function. Autoware follows that manner thoroughly. @@ -19,9 +19,9 @@ It implicitly recommends that messages received by subscriptions should be refer In the code above, when a topic message whose name is `input/steering` is received, an anonymous function whose description is `{current_steer_ = msg->steering_tier_angle;}` is executed as a callback in a thread. The callback function is always executed when the message is received, which leads to waste computing resource if the message is not always necessary. Besides, it costs thread-wakeup overhead just to take a message. -## Enhanced method +## Recommended manner -There is an enhanced method to take a message using `Subscription->take()` method only when it is needed. +There is a recommended manner to take a message using `Subscription->take()` method only when it is needed. The sample code given below shows that `Subscription->take()` method is called during execution of any callback function. In most cases, `Subscription->take()` method is called before a received message is consumed by a main logic. In this case, a topic message is retrieved from the subscription queue, the queue embedded in the subscription object, instead of using a callback function. To be exact, you need to program your code so that a callback function is not called automatically. @@ -38,13 +38,13 @@ Using this manner will give you following advantages. - There is no need to take a topic message, which a main logic does not consume, from a subscription - There is no mandatory thread waking for the callback function, which leads to multi-threaded programming, data races and exclusive locking -## Methods to handle topic message data +## Manners to handle topic message data This section introduces four manners including the recommended ones. ### 1. Obtain data by calling `Subscription->take()` -To use the enhanced method using `Subscription->take()`, you need to do two things below basically. +To use the recommended manner using `Subscription->take()`, you need to do two things below basically. 1. Prevent calling a callback function when a topic message is received 2. Call `take()` method of Subscription object when a topic message is needed @@ -130,9 +130,9 @@ In the code above, `msg` is created by `create_serialized_message()` to store a !!! Note ROS 2's `rclcpp` supports `rclcpp::LoanedMessage` as well as `rclcpp::SerializedMessage`. If [zero copy communication via loaned messages](https://design.ros2.org/articles/zero_copy.html) is introduced to Autoware, `take_loaned()` method should be used for communication via loaned messages instead. In this document, the explanation of `take_loaned()` method is omitted because it is not used for Autoware in the present (May. 2024). -### 2. obtain multiple data stored in Subscription Queue +### 2. Obtain multiple data stored in Subscription Queue -The subscription object can hold multiple messages in its queue if multiple queue size is configured with QoS setting. The conventional manner with callback function usage force a callback function to run per message. In other words, there is a constraints; a single cycle of callback function processes a single message . Note that in the conventional manner if there are one or more messages in Subscription Queue, the oldest one is taken and a thread is assigned to execute a callback function, which continues until the queue becomes empty. +The subscription object can hold multiple messages in its queue if multiple queue size is configured with QoS setting. The conventional manner with callback function usage force a callback function to run per message. In other words, there is a constraints; a single cycle of callback function processes a single message . Note that in the conventional manner if there are one or more messages in the subscription queue, the oldest one is taken and a thread is assigned to execute a callback function, which continues until the queue becomes empty. `take()` method would mitigate the constraint. `take()` method can be called in multiple iterations, so that single cycle of callback function processes multiple messages taken by `take()` methods. Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_batch_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_batch_listener.cpp) in which `take()` method is called consecutively. @@ -152,7 +152,7 @@ Note that you need to determine size of a subscription queue considering both fr Assigning a thread to execute a callback function per message will cause performance overhead. You can use the manner introduced in this section to avoid the unexpected overhead. The manner will be effective if there is a large difference between reception frequency and consumption frequency. For example, even if a message, like a CAN message, is received at higher than 100 Hz, a user logic consumes messages at slower frequency like 10 Hz. In such case, the user logic should retrieve the required number of messages with `take()` method to avoid the unexpected overhead. -### 3. obtain data by calling `Subscription->take` and then call a callback function +### 3. Obtain data by calling `Subscription->take` and then call a callback function You can combine the `take()` (strictly `take_type_erased()`) method and the callback function to process received messages in a consistent way. Using this combination does not require waking up a thread. Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener_using_callback.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener_using_callback.cpp). @@ -169,15 +169,15 @@ In the code above, a message is taken by `take_type_erased()` method before call You don't need to take care of message type which is passed to `take_type_erased()` and `handle_message()`. You can define the message variable as `auto msg = sub_->create_message();`. You can also refer to [API document](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1SubscriptionBase.html#_CPPv4N6rclcpp16SubscriptionBase16take_type_erasedEPvRN6rclcpp11MessageInfoE) as for `create_message()`, `take_type_erased()` and `handle_message()`. -### 4. obtain data by a callback function +### 4. Obtain data by a callback function A conventional manner used typically in ROS 2 application, a message reference using a callback function, is available. If you don't use a callback group with `automatically_add_to_executor_with_node = false`, a registered callback function is called automatically by Executor when a topic message is received. -One of advantages of this method is you don't need to take care whether a topic message is passed through inter-process or intra-process. Remind that `take()` can only be used in case of inter-process communication via DDS, while another manner provided by `rlclcpp` can be used for intra-process communication via `rlclcpp`. +One of advantages of this manner is you don't need to take care whether a topic message is passed through inter-process or intra-process. Remind that `take()` can only be used in case of inter-process communication via DDS, while another manner provided by `rlclcpp` can be used for intra-process communication via `rlclcpp`. ## Appendix A callback function is used to obtain a topic message in many of ROS 2 applications as if it is a rule or a custom. As this document page explained, you can use `Subscription->take()` method to obtain a topic message without calling a subscription callback function. -This method is also documented in [Template Class Subscription — rclcpp 16.0.8 documentation](https://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1Subscription.html#_CPPv4N6rclcpp12Subscription4takeER14ROSMessageTypeRN6rclcpp11MessageInfoE). +This manner is also documented in [Template Class Subscription — rclcpp 16.0.8 documentation](https://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1Subscription.html#_CPPv4N6rclcpp12Subscription4takeER14ROSMessageTypeRN6rclcpp11MessageInfoE). Many of ROS 2 users may feel anxious to use `take()` method because they may not be so familiar with it and there is a lack of documentation about `take()`, but it is widely used in Executor implementation as in [rclcpp/executor.cpp](https://github.com/ros2/rclcpp/blob/47c977d1bc82fc76dd21f870bcd3ea473eca2f59/rclcpp/src/rclcpp/executor.cpp#L643-L648) shown below. Therefore it turns out that you use `take()` method indirectly whether you know it or not. ```c++ From b5a1df138eb801bf8e8af06f66f97f123282a98d Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Mon, 13 May 2024 09:09:07 +0900 Subject: [PATCH 087/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index b77e8e422eb..ffecd6b60a5 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -2,7 +2,7 @@ ## Introduction -Here is coding guideline for a topic message handling in Autoware. It includes the recommended manner than conventional one, which is roughly explained in [Discussions page](https://github.com/orgs/autowarefoundation/discussions/4612). Refer to the page to understand the basic concept of the recommended manner. +Here is coding guideline for topic message handling in Autoware. It includes the recommended manner than conventional one, which is roughly explained in [_Discussions page_](https://github.com/orgs/autowarefoundation/discussions/4612). Refer to the page to understand the basic concept of the recommended manner. You can find sample source codes in [ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples) referred from this document. ## Typical message handling manner usually used From 56133570104eb1a18f1bad71e37374666ff0fef5 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Mon, 13 May 2024 09:09:38 +0900 Subject: [PATCH 088/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index ffecd6b60a5..f7f8830451f 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -3,7 +3,7 @@ ## Introduction Here is coding guideline for topic message handling in Autoware. It includes the recommended manner than conventional one, which is roughly explained in [_Discussions page_](https://github.com/orgs/autowarefoundation/discussions/4612). Refer to the page to understand the basic concept of the recommended manner. -You can find sample source codes in [ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples) referred from this document. +You can find sample source code in [_ros2_subscription_examples_](https://github.com/takam5f2/ros2_subscription_examples) referred from this document. ## Typical message handling manner usually used From 4d32ce242d040e1e37c35853df30426bacc288aa Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Mon, 13 May 2024 09:09:55 +0900 Subject: [PATCH 089/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index f7f8830451f..d16b60e5bf6 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -5,7 +5,7 @@ Here is coding guideline for topic message handling in Autoware. It includes the recommended manner than conventional one, which is roughly explained in [_Discussions page_](https://github.com/orgs/autowarefoundation/discussions/4612). Refer to the page to understand the basic concept of the recommended manner. You can find sample source code in [_ros2_subscription_examples_](https://github.com/takam5f2/ros2_subscription_examples) referred from this document. -## Typical message handling manner usually used +## Conventional message handling manner typically used At first, let us see a typical message handling manner usually used. [ROS 2 Tutorials](https://docs.ros.org/en/rolling/Tutorials/Beginner-Client-Libraries/Writing-A-Simple-Cpp-Publisher-And-Subscriber.html#write-the-subscriber-node) is one of the most cited references for ROS 2 applications, including Autoware. From e7ca6a8578efb75c10702691c91e2e5ede686050 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Mon, 13 May 2024 09:10:09 +0900 Subject: [PATCH 090/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index d16b60e5bf6..4753ce00565 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -7,7 +7,7 @@ You can find sample source code in [_ros2_subscription_examples_](https://github ## Conventional message handling manner typically used -At first, let us see a typical message handling manner usually used. +At first, let us see a conventional message handling manner that is commonly used. [ROS 2 Tutorials](https://docs.ros.org/en/rolling/Tutorials/Beginner-Client-Libraries/Writing-A-Simple-Cpp-Publisher-And-Subscriber.html#write-the-subscriber-node) is one of the most cited references for ROS 2 applications, including Autoware. It implicitly recommends that messages received by subscriptions should be referred and processed by a dedicated callback function. Autoware follows that manner thoroughly. From 28557343d0b12c18f133aab9ebf48d9051c6fc67 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Mon, 13 May 2024 09:11:09 +0900 Subject: [PATCH 091/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../topic-message-handling/01-supp-intra-process-comm.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index 4813e7ba483..e5a666ea2c8 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -2,7 +2,7 @@ ## Topic message handling in intra-process communication -rclcpp supports intra-process communication. As explained in [Topic message handling guideline](index.md), `take()` method can not be used in case of intra-process communication. `take()` can not return a topic message which is received through inter-process communication. +`rclcpp` supports intra-process communication. As explained in [Topic message handling guideline](index.md), `take()` method can not be used in the case of intra-process communication. `take()` can not return a topic message which is received through inter-process communication. But methods are provided for intra-process communication similar to methods for inter-process communication described in [obtain data by calling Subscription->take and then call a callback function](./index.md#3-obtain-data-by-calling-subscription-take-and-then-call-a-callback-function). `take_data()` method is provided to obtain a received data in case of intra-process communication and the received data must be processed through `execute()` method. The return value of `take_data()` is based on the complicated data structure, `execute()` method should be used along with `take_data()` method. Refer to [Template Class SubscriptionIntraProcess — rclcpp 16.0.8 documentation](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1experimental_1_1SubscriptionIntraProcess.html#_CPPv4N6rclcpp12experimental24SubscriptionIntraProcess9take_dataEv) for `take_data()` and `execute()` for more detail. From d483f9e4a15166c9a20260ecbc29bbb0189cdcea Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Mon, 13 May 2024 09:11:33 +0900 Subject: [PATCH 092/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../topic-message-handling/01-supp-intra-process-comm.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index e5a666ea2c8..43e026241ff 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -3,7 +3,7 @@ ## Topic message handling in intra-process communication `rclcpp` supports intra-process communication. As explained in [Topic message handling guideline](index.md), `take()` method can not be used in the case of intra-process communication. `take()` can not return a topic message which is received through inter-process communication. -But methods are provided for intra-process communication similar to methods for inter-process communication described in [obtain data by calling Subscription->take and then call a callback function](./index.md#3-obtain-data-by-calling-subscription-take-and-then-call-a-callback-function). +However, methods for intra-process communication are provided, similar to the methods for inter-process communication described in [_obtain data by calling Subscription->take and then call a callback function_](./index.md#3-obtain-data-by-calling-subscription-take-and-then-call-a-callback-function). `take_data()` method is provided to obtain a received data in case of intra-process communication and the received data must be processed through `execute()` method. The return value of `take_data()` is based on the complicated data structure, `execute()` method should be used along with `take_data()` method. Refer to [Template Class SubscriptionIntraProcess — rclcpp 16.0.8 documentation](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1experimental_1_1SubscriptionIntraProcess.html#_CPPv4N6rclcpp12experimental24SubscriptionIntraProcess9take_dataEv) for `take_data()` and `execute()` for more detail. From d93fcfeb5786492ee60d2fc2a7ee3c79153814ae Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Mon, 13 May 2024 09:12:11 +0900 Subject: [PATCH 093/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../topic-message-handling/01-supp-intra-process-comm.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index 43e026241ff..49ec664d6cb 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -4,7 +4,7 @@ `rclcpp` supports intra-process communication. As explained in [Topic message handling guideline](index.md), `take()` method can not be used in the case of intra-process communication. `take()` can not return a topic message which is received through inter-process communication. However, methods for intra-process communication are provided, similar to the methods for inter-process communication described in [_obtain data by calling Subscription->take and then call a callback function_](./index.md#3-obtain-data-by-calling-subscription-take-and-then-call-a-callback-function). -`take_data()` method is provided to obtain a received data in case of intra-process communication and the received data must be processed through `execute()` method. The return value of `take_data()` is based on the complicated data structure, `execute()` method should be used along with `take_data()` method. +`take_data()` method is provided to obtain a received data in the case of intra-process communication and the received data must be processed through `execute()` method. The return value of `take_data()` is based on the complicated data structure, `execute()` method should be used along with `take_data()` method. Refer to [Template Class SubscriptionIntraProcess — rclcpp 16.0.8 documentation](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1experimental_1_1SubscriptionIntraProcess.html#_CPPv4N6rclcpp12experimental24SubscriptionIntraProcess9take_dataEv) for `take_data()` and `execute()` for more detail. ## Coding manner From cf82e967faecc18b01a850ea700b2bcefd4e0288 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Mon, 13 May 2024 09:13:24 +0900 Subject: [PATCH 094/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../topic-message-handling/01-supp-intra-process-comm.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index 49ec664d6cb..0fce60947f9 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -5,7 +5,7 @@ `rclcpp` supports intra-process communication. As explained in [Topic message handling guideline](index.md), `take()` method can not be used in the case of intra-process communication. `take()` can not return a topic message which is received through inter-process communication. However, methods for intra-process communication are provided, similar to the methods for inter-process communication described in [_obtain data by calling Subscription->take and then call a callback function_](./index.md#3-obtain-data-by-calling-subscription-take-and-then-call-a-callback-function). `take_data()` method is provided to obtain a received data in the case of intra-process communication and the received data must be processed through `execute()` method. The return value of `take_data()` is based on the complicated data structure, `execute()` method should be used along with `take_data()` method. -Refer to [Template Class SubscriptionIntraProcess — rclcpp 16.0.8 documentation](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1experimental_1_1SubscriptionIntraProcess.html#_CPPv4N6rclcpp12experimental24SubscriptionIntraProcess9take_dataEv) for `take_data()` and `execute()` for more detail. +Refer to [_Template Class SubscriptionIntraProcess — rclcpp 16.0.8 documentation_](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1experimental_1_1SubscriptionIntraProcess.html#_CPPv4N6rclcpp12experimental24SubscriptionIntraProcess9take_dataEv) for `take_data()` and `execute()` for more detail. ## Coding manner From 5ab6de106a16cfd446db6daf99ffa842f7cf2c28 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Mon, 13 May 2024 09:15:17 +0900 Subject: [PATCH 095/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../topic-message-handling/01-supp-intra-process-comm.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index 0fce60947f9..8c87bb96aee 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -24,7 +24,7 @@ You can run the program as below. If you set `true` to `use_intra_process_comms` ros2 intra_process_talker_listener talker_listener_intra_process.launch.py use_intra_process_comms:=true ``` -Here is a excerption from [ros2_subscription_examples/intra_process_talker_listener/src/timer_listener_intra_process.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/intra_process_talker_listener/src/timer_listener_intra_process.cpp). +Here is a snippet of [_ros2_subscription_examples/intra_process_talker_listener/src/timer_listener_intra_process.cpp at main · takam5f2/ros2_subscription_examples_](https://github.com/takam5f2/ros2_subscription_examples/blob/main/intra_process_talker_listener/src/timer_listener_intra_process.cpp). ```c++ // check if intra-process communication is enabled. From a0b8c8863da50c04e081f8b22ef00108d080c3cf Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Mon, 13 May 2024 09:43:45 +0900 Subject: [PATCH 096/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../topic-message-handling/01-supp-intra-process-comm.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index 8c87bb96aee..8a1761fa80f 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -45,7 +45,7 @@ Here is a snippet of [_ros2_subscription_examples/intra_process_talker_listener/ intra_process_sub->execute(data); ``` -Below is explanation of the above code one line by one. +Below is a line-by-line explanation of the above code. - `if (this->get_node_options().use_intra_process_comms()){` From fdbfafa69dcf68c60ee33c43c77e9cf3413f0412 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Mon, 13 May 2024 09:44:11 +0900 Subject: [PATCH 097/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../topic-message-handling/01-supp-intra-process-comm.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index 8a1761fa80f..a3bae7fa2a2 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -49,7 +49,7 @@ Below is a line-by-line explanation of the above code. - `if (this->get_node_options().use_intra_process_comms()){` - - the statement verifies intra-process communication is enabled or not by using `NodeOptions` + - The statement checks whether or not intra-process communication is enabled or not by using `NodeOptions` - `auto intra_process_sub = sub_->get_intra_process_waitable();` From f6aa4cd1321221f7964d230f95087be6b44e5306 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Mon, 13 May 2024 09:44:34 +0900 Subject: [PATCH 098/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../topic-message-handling/01-supp-intra-process-comm.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index a3bae7fa2a2..e8bb2598dd7 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -53,7 +53,7 @@ Below is a line-by-line explanation of the above code. - `auto intra_process_sub = sub_->get_intra_process_waitable();` - - the statement means to get an embodied object which performs intra-process communication + - The statement means to get an embodied object which performs intra-process communication - `if (intra_process_sub->is_ready(nullptr) == true) {` From 710a15bbe17166e2dd369ac80239e22916af4946 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Mon, 13 May 2024 09:44:58 +0900 Subject: [PATCH 099/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../topic-message-handling/01-supp-intra-process-comm.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index e8bb2598dd7..5ca9a2ab008 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -57,7 +57,7 @@ Below is a line-by-line explanation of the above code. - `if (intra_process_sub->is_ready(nullptr) == true) {` - - the statement checks if a message has already been received through intra-process communication + - The statement checks if a message has already been received through intra-process communication - the argument of `is_ready()` is of `rcl_wait_set_t` type, but because the argument is not used inside `is_ready()`, `nullptr` is used tentatively - using `nullptr` is a workaround at the present because it does not have any intention. From 7cd7f0b8df88839fde7ef409628ec8ddd0457105 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Mon, 13 May 2024 09:56:28 +0900 Subject: [PATCH 100/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-waitset.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md index 2cc87da4b1c..44fa0af0073 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md @@ -2,7 +2,7 @@ ## What is `rclcpp::WaitSet` -As explained in [call take() method of Subscription object](./index.md#call-take-method-of-subscription-object), `take()` method is irreversible. Once `take()` method is executed, state of the subscription object changes. Because of no undo operation against `take()` method, the subscription object can not be restored to previous state. You can use `rclcpp::WaitSet` before calling `take()` to check arrival of any incoming message in the subscription queue. +As explained in [_call take() method of Subscription object_](./index.md#call-take-method-of-subscription-object), `take()` method is irreversible. Once `take()` method is executed, a state of a subscription object changes. Because there is no undo operation against `take()` method, the subscription object can not be restored to its previous state. You can use `rclcpp::WaitSet` before calling `take()` to check the arrival of an incoming message in the subscription queue. Here is a sample code in which `wait_set_.wait()` tells you that a message has already been received and can be obtained by `take()`. ```c++ From 9487a4a84174f1478ba83cb67305b7bdf55c273f Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Mon, 13 May 2024 09:56:53 +0900 Subject: [PATCH 101/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../topic-message-handling/01-supp-intra-process-comm.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index 5ca9a2ab008..d87a0b64d74 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -58,7 +58,7 @@ Below is a line-by-line explanation of the above code. - `if (intra_process_sub->is_ready(nullptr) == true) {` - The statement checks if a message has already been received through intra-process communication - - the argument of `is_ready()` is of `rcl_wait_set_t` type, but because the argument is not used inside `is_ready()`, `nullptr` is used tentatively + - The argument of `is_ready()` is of type `rcl_wait_set_t` type, but because the argument is not used within `is_ready()`, `nullptr` is used for the moment. - using `nullptr` is a workaround at the present because it does not have any intention. - `std::shared_ptr data = intra_process_sub->take_data();` From 025acb482b7f31ca01cd6db0a58f2f38bd387d30 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Mon, 13 May 2024 09:57:37 +0900 Subject: [PATCH 102/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../topic-message-handling/01-supp-intra-process-comm.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index d87a0b64d74..00a81ae06cb 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -59,7 +59,7 @@ Below is a line-by-line explanation of the above code. - The statement checks if a message has already been received through intra-process communication - The argument of `is_ready()` is of type `rcl_wait_set_t` type, but because the argument is not used within `is_ready()`, `nullptr` is used for the moment. - - using `nullptr` is a workaround at the present because it does not have any intention. + - Using `nullptr` is currently a workaround, as it has no intent. - `std::shared_ptr data = intra_process_sub->take_data();` From 592fec9d39284ee9d78c4658b3ab2ddf81b4ce3e Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Mon, 13 May 2024 09:57:57 +0900 Subject: [PATCH 103/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../topic-message-handling/01-supp-intra-process-comm.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index 00a81ae06cb..0dbc48d6002 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -63,7 +63,7 @@ Below is a line-by-line explanation of the above code. - `std::shared_ptr data = intra_process_sub->take_data();` - - this statement means to obtain a topic message from subscriptions for intra-process communication. + - This statement means to obtain a topic message from subscriptions for intra-process communication. - `intra_process_sub->take_data()` does not return Boolean value which indicates a message is received successfully or not, therefore it is needed to verify it by calling `is_ready()` in advance - `intra_process_sub->execute(data);` From 1191372d3f3cf32ceeb6096b9129afebd4e0ea58 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Mon, 13 May 2024 09:58:38 +0900 Subject: [PATCH 104/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../topic-message-handling/01-supp-intra-process-comm.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index 0dbc48d6002..b0212b59050 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -64,7 +64,7 @@ Below is a line-by-line explanation of the above code. - `std::shared_ptr data = intra_process_sub->take_data();` - This statement means to obtain a topic message from subscriptions for intra-process communication. - - `intra_process_sub->take_data()` does not return Boolean value which indicates a message is received successfully or not, therefore it is needed to verify it by calling `is_ready()` in advance + - `intra_process_sub->take_data()` does not return a boolean value indicating whether a message is received successfully or not, so it is necessary to check this by calling `is_ready()` beforehand - `intra_process_sub->execute(data);` - a callback function corresponded to the received message is called inside `execute()` From 9d00a72d3acfc971680628ac683ac59cc9d0db7b Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Mon, 13 May 2024 09:59:04 +0900 Subject: [PATCH 105/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../topic-message-handling/01-supp-intra-process-comm.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index b0212b59050..24b1c8556ce 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -67,5 +67,5 @@ Below is a line-by-line explanation of the above code. - `intra_process_sub->take_data()` does not return a boolean value indicating whether a message is received successfully or not, so it is necessary to check this by calling `is_ready()` beforehand - `intra_process_sub->execute(data);` - - a callback function corresponded to the received message is called inside `execute()` + - A callback function corresponding to the received message is called within `execute()` - the callback function is executed by the thread which executes `execute()` without context switch From 8c82a8da3e90ad6d25f5c930c9120595c3e6eb09 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Mon, 13 May 2024 09:59:31 +0900 Subject: [PATCH 106/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../topic-message-handling/01-supp-intra-process-comm.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index 24b1c8556ce..2de3f5ae0f3 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -68,4 +68,4 @@ Below is a line-by-line explanation of the above code. - `intra_process_sub->execute(data);` - A callback function corresponding to the received message is called within `execute()` - - the callback function is executed by the thread which executes `execute()` without context switch + - The callback function is executed by the thread that calls `execute()` without a context switch From c25e351290f202bcafbd08500089efdf3996ee4a Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Mon, 13 May 2024 09:59:51 +0900 Subject: [PATCH 107/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-waitset.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md index 44fa0af0073..33d4e32216b 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md @@ -3,7 +3,7 @@ ## What is `rclcpp::WaitSet` As explained in [_call take() method of Subscription object_](./index.md#call-take-method-of-subscription-object), `take()` method is irreversible. Once `take()` method is executed, a state of a subscription object changes. Because there is no undo operation against `take()` method, the subscription object can not be restored to its previous state. You can use `rclcpp::WaitSet` before calling `take()` to check the arrival of an incoming message in the subscription queue. -Here is a sample code in which `wait_set_.wait()` tells you that a message has already been received and can be obtained by `take()`. +The following sample code shows how `wait_set_.wait()` tells you that a message has already been received and can be obtained by `take()`. ```c++ auto wait_result = wait_set_.wait(std::chrono::milliseconds(0)); From 1f5889bc714cbc7c6481f296a5f628fb43212583 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Mon, 13 May 2024 10:00:08 +0900 Subject: [PATCH 108/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-waitset.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md index 33d4e32216b..8fe7f7d437e 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md @@ -53,7 +53,7 @@ Below is excerption from [ros2_subscription_examples/waitset_examples/src/timer_ rclcpp::WaitSet wait_set_; ``` -`rlcpp::WaitSet` object can be configured during runtime. It is not thread-safe as explained [the API specification](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1ad6fb19c154de27e92430309d2da25ac3.html) +The `rclcpp::WaitSet` object can be configured during runtime. It is not thread-safe as explained in[_API specification of `rclcpp::WaitSet`_](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1ad6fb19c154de27e92430309d2da25ac3.html) Thread-safe `WaitSet` are prepared by the `rclcpp` package as listed below. - [Typedef rclcpp::ThreadSafeWaitSet](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1acaec573e71549fd3078644e18e7f7127.html) From 4dffcab65e930177446ec07bb8e374d0cc0f5ddb Mon Sep 17 00:00:00 2001 From: ohsawa1204 Date: Mon, 13 May 2024 10:35:15 +0900 Subject: [PATCH 109/225] docs(topic-message-handling): rename 02-supp-waitset.md Signed-off-by: ohsawa1204 --- .../coding-guidelines/ros-nodes/topic-message-handling/.pages | 2 +- .../{02-supp-waitset.md => 02-supp-wait_set.md} | 0 .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 3 files changed, 2 insertions(+), 2 deletions(-) rename docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/{02-supp-waitset.md => 02-supp-wait_set.md} (100%) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/.pages b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/.pages index c162833180a..69029377561 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/.pages +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/.pages @@ -1,4 +1,4 @@ nav: - index.md - 01-supp-intra-process-comm.md - - 02-supp-waitset.md + - 02-supp-wait_set.md diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md similarity index 100% rename from docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-waitset.md rename to docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 4753ce00565..f06746382b3 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -103,7 +103,7 @@ When `take(msg, msg_info)` is called, if the size of the subscription queue is l !!! Note You can check the presence of incoming message with the returned value of `take()` method. However, you have to take care of destructive nature of take() method. `take()` method changes the subscription queue. Besides, `take()` method is irreversible while there is no undo operation against `take()` method. Checking the incoming message with only `take()` method always changes the subscription queue. If you want to check without changing the subscription queue, rclcpp::WaitSet is recommended. -Refer to [[supplement] Use rclcpp::WaitSet](./02-supp-waitset.md) for more detail. +Refer to [[supplement] Use rclcpp::WaitSet](./02-supp-wait_set.md) for more detail. !!! Note `take()` method is supported to only obtain a message which is passed through DDS as an inter-process communication. You must not use it for an intra-process communication because intra-process communication is based on another software stack of `rclcpp`. Refer to [[supplement] Obtain a received message through intra-process communication](./01-supp-intra-process-comm.md) in case of intra-process communication. From d00fb2e1db3bb164742afdccf8a766e20c40e138 Mon Sep 17 00:00:00 2001 From: ohsawa1204 Date: Mon, 13 May 2024 13:19:57 +0900 Subject: [PATCH 110/225] docs(topic-message-handling): correct typo Signed-off-by: ohsawa1204 --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index f06746382b3..cf6613da867 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -172,7 +172,7 @@ You can also refer to [API document](http://docs.ros.org/en/humble/p/rclcpp/gene ### 4. Obtain data by a callback function A conventional manner used typically in ROS 2 application, a message reference using a callback function, is available. If you don't use a callback group with `automatically_add_to_executor_with_node = false`, a registered callback function is called automatically by Executor when a topic message is received. -One of advantages of this manner is you don't need to take care whether a topic message is passed through inter-process or intra-process. Remind that `take()` can only be used in case of inter-process communication via DDS, while another manner provided by `rlclcpp` can be used for intra-process communication via `rlclcpp`. +One of advantages of this manner is you don't need to take care whether a topic message is passed through inter-process or intra-process. Remind that `take()` can only be used in case of inter-process communication via DDS, while another manner provided by `rclcpp` can be used for intra-process communication via `rclcpp`. ## Appendix From 5355a252b9ed5c01055acf9f3371b613632b14c3 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 09:46:28 +0900 Subject: [PATCH 111/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index cf6613da867..649d05067cb 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -8,7 +8,7 @@ You can find sample source code in [_ros2_subscription_examples_](https://github ## Conventional message handling manner typically used At first, let us see a conventional message handling manner that is commonly used. -[ROS 2 Tutorials](https://docs.ros.org/en/rolling/Tutorials/Beginner-Client-Libraries/Writing-A-Simple-Cpp-Publisher-And-Subscriber.html#write-the-subscriber-node) is one of the most cited references for ROS 2 applications, including Autoware. +[_ROS 2 Tutorials_](https://docs.ros.org/en/rolling/Tutorials/Beginner-Client-Libraries/Writing-A-Simple-Cpp-Publisher-And-Subscriber.html#write-the-subscriber-node) is one of the most cited references for ROS 2 applications, including Autoware. It implicitly recommends that messages received by subscriptions should be referred and processed by a dedicated callback function. Autoware follows that manner thoroughly. ```c++ From 7c782d9f73f88656c02817afee8811c450bd3e44 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 09:49:39 +0900 Subject: [PATCH 112/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 649d05067cb..be9d71aff9a 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -7,7 +7,7 @@ You can find sample source code in [_ros2_subscription_examples_](https://github ## Conventional message handling manner typically used -At first, let us see a conventional message handling manner that is commonly used. +At first, let us see a conventional manner of handling messages that is commonly used. [_ROS 2 Tutorials_](https://docs.ros.org/en/rolling/Tutorials/Beginner-Client-Libraries/Writing-A-Simple-Cpp-Publisher-And-Subscriber.html#write-the-subscriber-node) is one of the most cited references for ROS 2 applications, including Autoware. It implicitly recommends that messages received by subscriptions should be referred and processed by a dedicated callback function. Autoware follows that manner thoroughly. From 038f09f163581631bf2bc41e5d6a6961eb4641fa Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 09:50:14 +0900 Subject: [PATCH 113/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index be9d71aff9a..7cc491a4ac4 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -21,7 +21,7 @@ In the code above, when a topic message whose name is `input/steering` is receiv ## Recommended manner -There is a recommended manner to take a message using `Subscription->take()` method only when it is needed. +This section introduces a recommended manner to take a message using `Subscription->take()` method only when the message is needed. The sample code given below shows that `Subscription->take()` method is called during execution of any callback function. In most cases, `Subscription->take()` method is called before a received message is consumed by a main logic. In this case, a topic message is retrieved from the subscription queue, the queue embedded in the subscription object, instead of using a callback function. To be exact, you need to program your code so that a callback function is not called automatically. From bc49c9e4b2486e3b455f4f705d8f4497dabd0fb0 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 09:50:43 +0900 Subject: [PATCH 114/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 7cc491a4ac4..41c7417ddc8 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -9,7 +9,7 @@ You can find sample source code in [_ros2_subscription_examples_](https://github At first, let us see a conventional manner of handling messages that is commonly used. [_ROS 2 Tutorials_](https://docs.ros.org/en/rolling/Tutorials/Beginner-Client-Libraries/Writing-A-Simple-Cpp-Publisher-And-Subscriber.html#write-the-subscriber-node) is one of the most cited references for ROS 2 applications, including Autoware. -It implicitly recommends that messages received by subscriptions should be referred and processed by a dedicated callback function. Autoware follows that manner thoroughly. +It implicitly recommends that each of messages received by subscriptions should be referred to and processed by a dedicated callback function. Autoware follows that manner thoroughly. ```c++ steer_sub_ = create_subscription( From 4aa951ba78113a6d170a232cca9cc1482c4080dc Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 09:51:39 +0900 Subject: [PATCH 115/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 41c7417ddc8..fa2d2add11a 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -17,7 +17,7 @@ It implicitly recommends that each of messages received by subscriptions should [this](SteeringReport::SharedPtr msg) { current_steer_ = msg->steering_tire_angle; }); ``` -In the code above, when a topic message whose name is `input/steering` is received, an anonymous function whose description is `{current_steer_ = msg->steering_tier_angle;}` is executed as a callback in a thread. The callback function is always executed when the message is received, which leads to waste computing resource if the message is not always necessary. Besides, it costs thread-wakeup overhead just to take a message. +In the code above, when a topic message whose name is `input/steering` is received, an anonymous function whose description is `{current_steer_ = msg->steering_tier_angle;}` is executed as a callback in a thread. The callback function is always executed when the message is received, which leads to waste computing resource if the message is not always necessary. Besides, waking up a thread costs computational overhead. ## Recommended manner From 94b849542c16e4af1461ce8a2ee0c0fdac090514 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 09:52:40 +0900 Subject: [PATCH 116/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index fa2d2add11a..e8e75e83f4d 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -23,7 +23,7 @@ In the code above, when a topic message whose name is `input/steering` is receiv This section introduces a recommended manner to take a message using `Subscription->take()` method only when the message is needed. The sample code given below shows that `Subscription->take()` method is called during execution of any callback function. In most cases, `Subscription->take()` method is called before a received message is consumed by a main logic. -In this case, a topic message is retrieved from the subscription queue, the queue embedded in the subscription object, instead of using a callback function. To be exact, you need to program your code so that a callback function is not called automatically. +In this case, a topic message is retrieved from the subscription queue, the queue embedded in the subscription object, instead of using a callback function. To be precise, you have to program your code so that a callback function is not automatically called. ```c++ SteeringReport::SharedPtr msg; From 36c6dd53bae1284e7d1a891f358f396c21f750cc Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 09:53:05 +0900 Subject: [PATCH 117/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index e8e75e83f4d..658044cdada 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -32,7 +32,7 @@ In this case, a topic message is retrieved from the subscription queue, the queu // processing and publishing after this ``` -Using this manner will give you following advantages. +Using this manner has the following benefits. - It can reduce invocations of subscription callback functions - There is no need to take a topic message, which a main logic does not consume, from a subscription From c0e897b0d22e937a11ed1905a04a782f7212bce6 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 09:53:33 +0900 Subject: [PATCH 118/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 658044cdada..65e7c93c785 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -34,7 +34,7 @@ In this case, a topic message is retrieved from the subscription queue, the queu Using this manner has the following benefits. -- It can reduce invocations of subscription callback functions +- It can reduce the number of calls to subscription callback functions - There is no need to take a topic message, which a main logic does not consume, from a subscription - There is no mandatory thread waking for the callback function, which leads to multi-threaded programming, data races and exclusive locking From 3e2fb0826b468d678c52cfed71b5a0809d059026 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 09:54:31 +0900 Subject: [PATCH 119/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 65e7c93c785..ff6b696f98a 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -35,7 +35,7 @@ In this case, a topic message is retrieved from the subscription queue, the queu Using this manner has the following benefits. - It can reduce the number of calls to subscription callback functions -- There is no need to take a topic message, which a main logic does not consume, from a subscription +- There is no need to take a topic message from a subscription that a main logic does not consume - There is no mandatory thread waking for the callback function, which leads to multi-threaded programming, data races and exclusive locking ## Manners to handle topic message data From af5afdd1ce62792f4e61cbe3d946e24733c37040 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 09:55:16 +0900 Subject: [PATCH 120/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/index.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index ff6b696f98a..75cea70effd 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -178,7 +178,8 @@ One of advantages of this manner is you don't need to take care whether a topic A callback function is used to obtain a topic message in many of ROS 2 applications as if it is a rule or a custom. As this document page explained, you can use `Subscription->take()` method to obtain a topic message without calling a subscription callback function. This manner is also documented in [Template Class Subscription — rclcpp 16.0.8 documentation](https://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1Subscription.html#_CPPv4N6rclcpp12Subscription4takeER14ROSMessageTypeRN6rclcpp11MessageInfoE). -Many of ROS 2 users may feel anxious to use `take()` method because they may not be so familiar with it and there is a lack of documentation about `take()`, but it is widely used in Executor implementation as in [rclcpp/executor.cpp](https://github.com/ros2/rclcpp/blob/47c977d1bc82fc76dd21f870bcd3ea473eca2f59/rclcpp/src/rclcpp/executor.cpp#L643-L648) shown below. Therefore it turns out that you use `take()` method indirectly whether you know it or not. + +Many of ROS 2 users may be afraid to use the `take()` method because they may not be so familiar with it and there is a lack of documentation about `take()`, but it is widely used in the `rclcpp::Executor` implementation as shown in [_rclcpp/executor.cpp_](https://github.com/ros2/rclcpp/blob/47c977d1bc82fc76dd21f870bcd3ea473eca2f59/rclcpp/src/rclcpp/executor.cpp#L643-L648) shown below. So it turns out that you are indirectly using the `take()` method, whether you know it or not. ```c++ std::shared_ptr message = subscription->create_message(); From 6ef44d4ec25249062d42dd311f8caf848684bbe4 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 09:55:38 +0900 Subject: [PATCH 121/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 75cea70effd..dcfa446a73a 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -40,7 +40,7 @@ Using this manner has the following benefits. ## Manners to handle topic message data -This section introduces four manners including the recommended ones. +This section introduces four manners, including the recommended ones. ### 1. Obtain data by calling `Subscription->take()` From 4ea3d5b5bd756bb47bbb4a732518e2c8f2e11251 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 09:56:00 +0900 Subject: [PATCH 122/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index dcfa446a73a..1cb35f0a380 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -44,7 +44,7 @@ This section introduces four manners, including the recommended ones. ### 1. Obtain data by calling `Subscription->take()` -To use the recommended manner using `Subscription->take()`, you need to do two things below basically. +To use the recommended manner using `Subscription->take()`, you basically need to do two things below. 1. Prevent calling a callback function when a topic message is received 2. Call `take()` method of Subscription object when a topic message is needed From a7143bba5d009acf7734cc846cb7da86cbe5435e Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 09:56:28 +0900 Subject: [PATCH 123/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 1cb35f0a380..665eb539c45 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -46,7 +46,7 @@ This section introduces four manners, including the recommended ones. To use the recommended manner using `Subscription->take()`, you basically need to do two things below. -1. Prevent calling a callback function when a topic message is received +1. Prevent a callback function from being called when a topic message is received 2. Call `take()` method of Subscription object when a topic message is needed You can see an example of the typical usage of `take()` method in [ros2_subscription_examples/simple_examples/src From c8a779ca53f92b2fa641682cd010eab63940066f Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 09:57:46 +0900 Subject: [PATCH 124/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 665eb539c45..8c4ac86a1ce 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -47,7 +47,7 @@ This section introduces four manners, including the recommended ones. To use the recommended manner using `Subscription->take()`, you basically need to do two things below. 1. Prevent a callback function from being called when a topic message is received -2. Call `take()` method of Subscription object when a topic message is needed +2. Call `take()` method of a subscription object when a topic message is needed You can see an example of the typical usage of `take()` method in [ros2_subscription_examples/simple_examples/src /timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp). From 106a7e13295096f7f68818c1d5a843bdf5b42bb4 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 09:58:08 +0900 Subject: [PATCH 125/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/index.md | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 8c4ac86a1ce..ae2aa66e366 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -49,8 +49,7 @@ To use the recommended manner using `Subscription->take()`, you basically need t 1. Prevent a callback function from being called when a topic message is received 2. Call `take()` method of a subscription object when a topic message is needed -You can see an example of the typical usage of `take()` method in [ros2_subscription_examples/simple_examples/src -/timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp). +You can see an example of the typical use of `take()` method in [_ros2_subscription_examples/simple_examples/src/timer_listener.cpp_](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp). #### Prevent calling a callback function From 76792bbc081b40b2cc2c31d0a1249fb4f615f48d Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 09:58:36 +0900 Subject: [PATCH 126/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index ae2aa66e366..e90ee682c90 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -53,7 +53,7 @@ You can see an example of the typical use of `take()` method in [_ros2_subscript #### Prevent calling a callback function -To prevent a callback function from being called automatically, the callback function has to belong a callback group whose callback functions will not added to executor. +To prevent a callback function from being called automatically, the callback function has to belong a callback group whose callback functions are not added to any executor. Due to [API specification of `create_subscription`](http://docs.ros.org/en/iron/p/rclcpp/generated/classrclcpp_1_1Node.html), registering a callback function to a `Subscription` based object is mandatory even if the callback function has no operation. Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp). From 6ee7031c820adcf5e22836b1ce47bd881261a361 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 09:59:11 +0900 Subject: [PATCH 127/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index e90ee682c90..f3c2978e36c 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -54,7 +54,7 @@ You can see an example of the typical use of `take()` method in [_ros2_subscript #### Prevent calling a callback function To prevent a callback function from being called automatically, the callback function has to belong a callback group whose callback functions are not added to any executor. -Due to [API specification of `create_subscription`](http://docs.ros.org/en/iron/p/rclcpp/generated/classrclcpp_1_1Node.html), registering a callback function to a `Subscription` based object is mandatory even if the callback function has no operation. +According to the [API specification of `create_subscription`](http://docs.ros.org/en/iron/p/rclcpp/generated/classrclcpp_1_1Node.html), registering a callback function to a `rclcpp::Subscription` based object is mandatory even if the callback function has no operation. Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp). ```c++ From f71dd912d23911bdf266f74738a5ed7ac8f3fbb8 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:00:09 +0900 Subject: [PATCH 128/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index f3c2978e36c..8a374f71fb1 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -55,7 +55,7 @@ You can see an example of the typical use of `take()` method in [_ros2_subscript To prevent a callback function from being called automatically, the callback function has to belong a callback group whose callback functions are not added to any executor. According to the [API specification of `create_subscription`](http://docs.ros.org/en/iron/p/rclcpp/generated/classrclcpp_1_1Node.html), registering a callback function to a `rclcpp::Subscription` based object is mandatory even if the callback function has no operation. -Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp). +Here is a sample code snippet from [ros2_subscription_examples/simple_examples/src/timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp). ```c++ rclcpp::CallbackGroup::SharedPtr cb_group_noexec = this->create_callback_group( From 7937d6bf6740379e5efc558b427f5caeb86e1137 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:00:34 +0900 Subject: [PATCH 129/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 8a374f71fb1..1f9db118f91 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -58,7 +58,7 @@ According to the [API specification of `create_subscription`](http://docs.ros.or Here is a sample code snippet from [ros2_subscription_examples/simple_examples/src/timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp). ```c++ - rclcpp::CallbackGroup::SharedPtr cb_group_noexec = this->create_callback_group( + rclcpp::CallbackGroup::SharedPtr cb_group_not_executed = this->create_callback_group( rclcpp::CallbackGroupType::MutuallyExclusive, false); auto subscription_options = rclcpp::SubscriptionOptions(); subscription_options.callback_group = cb_group_noexec; From aba383418ac2520bfc79a6e37d0375caa9487f2b Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:01:00 +0900 Subject: [PATCH 130/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 1f9db118f91..11e217d3082 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -61,7 +61,7 @@ Here is a sample code snippet from [ros2_subscription_examples/simple_examples/s rclcpp::CallbackGroup::SharedPtr cb_group_not_executed = this->create_callback_group( rclcpp::CallbackGroupType::MutuallyExclusive, false); auto subscription_options = rclcpp::SubscriptionOptions(); - subscription_options.callback_group = cb_group_noexec; + subscription_options.callback_group = cb_group_not_executed; rclcpp::QoS qos(rclcpp::KeepLast(10)); if (use_transient_local) { From 8e9bf2759c2a557ccf14ad0028a50970aab9f96a Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:01:26 +0900 Subject: [PATCH 131/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 11e217d3082..d17fe277741 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -71,7 +71,7 @@ Here is a sample code snippet from [ros2_subscription_examples/simple_examples/s sub_ = create_subscription("chatter", qos, not_executed_callback, subscription_options); ``` -In the code above, `cb_group_noexec` is created by calling `create_callback_group` with its second argument `false`. A callback function which belongs to the callback group will not be called by Executor. +In the code above, `cb_group_not_executed` is created by calling `create_callback_group` with the second argument `false`. Any callback function which belongs to the callback group will not be called by an executor. If `callback_group` member of `subscription_options` is set to `cb_group_noexec`, `not_executed_callback` will not be called when a corresponded topic message `chatter` is received. The second argument of `create_callback_group` is defined as below. From a2ab1d25212fc7a49ffb62c431c68d7010e32922 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:01:52 +0900 Subject: [PATCH 132/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index d17fe277741..b893a10e687 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -72,7 +72,7 @@ Here is a sample code snippet from [ros2_subscription_examples/simple_examples/s ``` In the code above, `cb_group_not_executed` is created by calling `create_callback_group` with the second argument `false`. Any callback function which belongs to the callback group will not be called by an executor. -If `callback_group` member of `subscription_options` is set to `cb_group_noexec`, `not_executed_callback` will not be called when a corresponded topic message `chatter` is received. +If the `callback_group` member of `subscription_options` is set to `cb_group_not_executed`, then `not_executed_callback` will not be called when a corresponding topic message `chatter` is received. The second argument of `create_callback_group` is defined as below. ```c++ From 9abdaa5fae4a083955ad8bf0b607b638ae01ac24 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:02:22 +0900 Subject: [PATCH 133/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index b893a10e687..cda7e7b548f 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -73,7 +73,7 @@ Here is a sample code snippet from [ros2_subscription_examples/simple_examples/s In the code above, `cb_group_not_executed` is created by calling `create_callback_group` with the second argument `false`. Any callback function which belongs to the callback group will not be called by an executor. If the `callback_group` member of `subscription_options` is set to `cb_group_not_executed`, then `not_executed_callback` will not be called when a corresponding topic message `chatter` is received. -The second argument of `create_callback_group` is defined as below. +The second argument to `create_callback_group` is defined as follows. ```c++ rclcpp::CallbackGroup::SharedPtr create_callback_group(rclcpp::CallbackGroupType group_type, \ From 39e3c97f1897841feafca49a7c3fe13892b05f7b Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:02:57 +0900 Subject: [PATCH 134/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index cda7e7b548f..9e7d65c2d27 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -80,7 +80,7 @@ rclcpp::CallbackGroup::SharedPtr create_callback_group(rclcpp::CallbackGroupType bool automatically_add_to_executor_with_node = true) ``` -If `automatically_add_to_executor_with_node` is set to `true`, callback functions included in a node which is added to Executor will be called automatically by Executor. +When `automatically_add_to_executor_with_node` is set to `true`, callback functions included in a node that is added to an executor will be automatically called by the executor. #### Call `take()` method of Subscription object From 72123f539e2a6a70fbedf52b7fbaa78b069a621e Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:04:52 +0900 Subject: [PATCH 135/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 9e7d65c2d27..eaa74cb5aa4 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -85,7 +85,7 @@ When `automatically_add_to_executor_with_node` is set to `true`, callback functi #### Call `take()` method of Subscription object To take a topic message from the `Subscription` based object, the `take()` method is called at the expected time. -Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp) in which `take()` method is used. +Here is a sample code snippet from [_ros2_subscription_examples/simple_examples/src/timer_listener.cpp_](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp) using `take()` method is used. ```c++ std_msgs::msg::String msg; From 9b5f07e0b62ae470db16576860b84037d517a333 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:05:22 +0900 Subject: [PATCH 136/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index eaa74cb5aa4..e4c50e1a698 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -104,7 +104,7 @@ When `take(msg, msg_info)` is called, if the size of the subscription queue is l You can check the presence of incoming message with the returned value of `take()` method. However, you have to take care of destructive nature of take() method. `take()` method changes the subscription queue. Besides, `take()` method is irreversible while there is no undo operation against `take()` method. Checking the incoming message with only `take()` method always changes the subscription queue. If you want to check without changing the subscription queue, rclcpp::WaitSet is recommended. Refer to [[supplement] Use rclcpp::WaitSet](./02-supp-wait_set.md) for more detail. -!!! Note +!!! note `take()` method is supported to only obtain a message which is passed through DDS as an inter-process communication. You must not use it for an intra-process communication because intra-process communication is based on another software stack of `rclcpp`. Refer to [[supplement] Obtain a received message through intra-process communication](./01-supp-intra-process-comm.md) in case of intra-process communication. #### 1.1 obtain Serialized Message from Subscription From fb478d21e8718a8c2abc0e2b461e9061fd2d850d Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:06:06 +0900 Subject: [PATCH 137/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/index.md | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index e4c50e1a698..f14ea469509 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -105,7 +105,9 @@ You can check the presence of incoming message with the returned value of `take( Refer to [[supplement] Use rclcpp::WaitSet](./02-supp-wait_set.md) for more detail. !!! note -`take()` method is supported to only obtain a message which is passed through DDS as an inter-process communication. You must not use it for an intra-process communication because intra-process communication is based on another software stack of `rclcpp`. Refer to [[supplement] Obtain a received message through intra-process communication](./01-supp-intra-process-comm.md) in case of intra-process communication. + + The `take()` method is supported to only obtain a message which is passed through DDS as an inter-process communication. You must not use it for an intra-process communication because intra-process communication is based on another software stack of `rclcpp`. Refer to [_[supplement] Obtain a received message through intra-process communication_](./01-supp-intra-process-comm.md) in case of intra-process communication. + #### 1.1 obtain Serialized Message from Subscription From 5337eb4e02047debdfdf0d44cf5f50ce9dad670f Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:06:33 +0900 Subject: [PATCH 138/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index f14ea469509..d10a890d2a9 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -100,7 +100,7 @@ In the code above, `take(msg, msg_info)` is called by `sub_` instance which is c `take(msg, msg_info)` returns `false` if a message is not taken from Subscription. When `take(msg, msg_info)` is called, if the size of the subscription queue is larger than one and there are two or more messages in the queue, then the oldest message is copied to `msg`. If the size of the queue is one, the latest message is always obtained. -!!! Note +!!! note You can check the presence of incoming message with the returned value of `take()` method. However, you have to take care of destructive nature of take() method. `take()` method changes the subscription queue. Besides, `take()` method is irreversible while there is no undo operation against `take()` method. Checking the incoming message with only `take()` method always changes the subscription queue. If you want to check without changing the subscription queue, rclcpp::WaitSet is recommended. Refer to [[supplement] Use rclcpp::WaitSet](./02-supp-wait_set.md) for more detail. From 1cd1d4a8b57fa81df9fd18d011971499f52bf8dc Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:07:03 +0900 Subject: [PATCH 139/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/index.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index d10a890d2a9..49c347ed78e 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -102,7 +102,8 @@ When `take(msg, msg_info)` is called, if the size of the subscription queue is l !!! note You can check the presence of incoming message with the returned value of `take()` method. However, you have to take care of destructive nature of take() method. `take()` method changes the subscription queue. Besides, `take()` method is irreversible while there is no undo operation against `take()` method. Checking the incoming message with only `take()` method always changes the subscription queue. If you want to check without changing the subscription queue, rclcpp::WaitSet is recommended. -Refer to [[supplement] Use rclcpp::WaitSet](./02-supp-wait_set.md) for more detail. + Refer to [_[supplement] Use rclcpp::WaitSet_](./02-supp-wait_set.md) for more detail. + !!! note From 161623fc5547b89e31491d1d560cd75a2feaf63c Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:08:01 +0900 Subject: [PATCH 140/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 49c347ed78e..354de4401df 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -95,7 +95,7 @@ Here is a sample code snippet from [_ros2_subscription_examples/simple_examples/ RCLCPP_INFO(this->get_logger(), "I heard: [%s]", msg.data.c_str()); ``` -In the code above, `take(msg, msg_info)` is called by `sub_` instance which is created from `Subscription` class. It is called in a timer driven callback function. `msg` and `msg_info` indicate a message body and its metadata respectively. If there is a message in the subscription queue when `take(msg, msg_info)` is called, then the message is copied to `msg`. +In the code above, `take(msg, msg_info)` is called by `sub_` object instantiated from the `rclcpp::Subscription` class. It is called in a timer driven callback function. `msg` and `msg_info` indicate a message body and its metadata respectively. If there is a message in the subscription queue when `take(msg, msg_info)` is called, then the message is copied to `msg`. `take(msg, msg_info)` returns `true` if a message is taken from the subscription successfully. In this case in code above, a string data of the message is outputted by `RCLCPP_INFO`. `take(msg, msg_info)` returns `false` if a message is not taken from Subscription. When `take(msg, msg_info)` is called, if the size of the subscription queue is larger than one and there are two or more messages in the queue, then the oldest message is copied to `msg`. If the size of the queue is one, the latest message is always obtained. From eb2743983419aa9549d4e27ba30d6335ea29b4fd Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:09:24 +0900 Subject: [PATCH 141/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 354de4401df..bd7056b9107 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -96,7 +96,7 @@ Here is a sample code snippet from [_ros2_subscription_examples/simple_examples/ ``` In the code above, `take(msg, msg_info)` is called by `sub_` object instantiated from the `rclcpp::Subscription` class. It is called in a timer driven callback function. `msg` and `msg_info` indicate a message body and its metadata respectively. If there is a message in the subscription queue when `take(msg, msg_info)` is called, then the message is copied to `msg`. -`take(msg, msg_info)` returns `true` if a message is taken from the subscription successfully. In this case in code above, a string data of the message is outputted by `RCLCPP_INFO`. +`take(msg, msg_info)` returns `true` if a message is successfully taken from the subscription. In this case, the above code prints out a string data of the message from `RCLCPP_INFO`. `take(msg, msg_info)` returns `false` if a message is not taken from Subscription. When `take(msg, msg_info)` is called, if the size of the subscription queue is larger than one and there are two or more messages in the queue, then the oldest message is copied to `msg`. If the size of the queue is one, the latest message is always obtained. From b909de6ff040a2caa479c8b6da97b1356cb1410d Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 14 May 2024 01:09:23 +0000 Subject: [PATCH 142/225] style(pre-commit): autofix --- .../ros-nodes/topic-message-handling/index.md | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index bd7056b9107..8d596af49b8 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -102,14 +102,12 @@ When `take(msg, msg_info)` is called, if the size of the subscription queue is l !!! note You can check the presence of incoming message with the returned value of `take()` method. However, you have to take care of destructive nature of take() method. `take()` method changes the subscription queue. Besides, `take()` method is irreversible while there is no undo operation against `take()` method. Checking the incoming message with only `take()` method always changes the subscription queue. If you want to check without changing the subscription queue, rclcpp::WaitSet is recommended. - Refer to [_[supplement] Use rclcpp::WaitSet_](./02-supp-wait_set.md) for more detail. - +Refer to [_[supplement] Use rclcpp::WaitSet_](./02-supp-wait_set.md) for more detail. !!! note The `take()` method is supported to only obtain a message which is passed through DDS as an inter-process communication. You must not use it for an intra-process communication because intra-process communication is based on another software stack of `rclcpp`. Refer to [_[supplement] Obtain a received message through intra-process communication_](./01-supp-intra-process-comm.md) in case of intra-process communication. - #### 1.1 obtain Serialized Message from Subscription ROS 2 provides Serialized Message function which supports communication with arbitrary message types as explained in [Class SerializedMessage](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1SerializedMessage.html). It is used by `topic_state_monitor` in Autoware. From 29a6dd3f263112deb0cb190b6d0545f2c5983e7d Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:10:07 +0900 Subject: [PATCH 143/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 8d596af49b8..bc80db4da6d 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -97,7 +97,7 @@ Here is a sample code snippet from [_ros2_subscription_examples/simple_examples/ In the code above, `take(msg, msg_info)` is called by `sub_` object instantiated from the `rclcpp::Subscription` class. It is called in a timer driven callback function. `msg` and `msg_info` indicate a message body and its metadata respectively. If there is a message in the subscription queue when `take(msg, msg_info)` is called, then the message is copied to `msg`. `take(msg, msg_info)` returns `true` if a message is successfully taken from the subscription. In this case, the above code prints out a string data of the message from `RCLCPP_INFO`. -`take(msg, msg_info)` returns `false` if a message is not taken from Subscription. +`take(msg, msg_info)` returns `false` if a message is not taken from the subscription. When `take(msg, msg_info)` is called, if the size of the subscription queue is larger than one and there are two or more messages in the queue, then the oldest message is copied to `msg`. If the size of the queue is one, the latest message is always obtained. !!! note From 348f75363586b067e16bfff2c6194c15cf996729 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:10:51 +0900 Subject: [PATCH 144/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index bc80db4da6d..4109c5ebefb 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -98,7 +98,7 @@ Here is a sample code snippet from [_ros2_subscription_examples/simple_examples/ In the code above, `take(msg, msg_info)` is called by `sub_` object instantiated from the `rclcpp::Subscription` class. It is called in a timer driven callback function. `msg` and `msg_info` indicate a message body and its metadata respectively. If there is a message in the subscription queue when `take(msg, msg_info)` is called, then the message is copied to `msg`. `take(msg, msg_info)` returns `true` if a message is successfully taken from the subscription. In this case, the above code prints out a string data of the message from `RCLCPP_INFO`. `take(msg, msg_info)` returns `false` if a message is not taken from the subscription. -When `take(msg, msg_info)` is called, if the size of the subscription queue is larger than one and there are two or more messages in the queue, then the oldest message is copied to `msg`. If the size of the queue is one, the latest message is always obtained. +When `take(msg, msg_info)` is called, if the size of the subscription queue is greater than one and there are two or more messages in the queue, then the oldest message is copied to `msg`. If the size of the queue is one, the latest message is always obtained. !!! note You can check the presence of incoming message with the returned value of `take()` method. However, you have to take care of destructive nature of take() method. `take()` method changes the subscription queue. Besides, `take()` method is irreversible while there is no undo operation against `take()` method. Checking the incoming message with only `take()` method always changes the subscription queue. If you want to check without changing the subscription queue, rclcpp::WaitSet is recommended. From 11754e2fb17f30edde5cd66b24d917f6df1db6ce Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:12:11 +0900 Subject: [PATCH 145/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/index.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 4109c5ebefb..04d0dd0a3df 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -101,7 +101,8 @@ In the code above, `take(msg, msg_info)` is called by `sub_` object instantiated When `take(msg, msg_info)` is called, if the size of the subscription queue is greater than one and there are two or more messages in the queue, then the oldest message is copied to `msg`. If the size of the queue is one, the latest message is always obtained. !!! note -You can check the presence of incoming message with the returned value of `take()` method. However, you have to take care of destructive nature of take() method. `take()` method changes the subscription queue. Besides, `take()` method is irreversible while there is no undo operation against `take()` method. Checking the incoming message with only `take()` method always changes the subscription queue. If you want to check without changing the subscription queue, rclcpp::WaitSet is recommended. + + You can check the presence of incoming message with the returned value of `take()` method. However, you have to take care of the destructive nature of the take() method. The `take()` method modifies the subscription queue. Also, the `take()` method is irreversible and there is no undo operation against the `take()` method. Checking the incoming message with only the `take()` method always changes the subscription queue. If you want to check without changing the subscription queue, rclcpp::WaitSet is recommended. Refer to [_[supplement] Use rclcpp::WaitSet_](./02-supp-wait_set.md) for more detail. !!! note From 80438844c16edd2bc68324df1f20c8747f138d36 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:12:54 +0900 Subject: [PATCH 146/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 04d0dd0a3df..8e516742154 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -109,7 +109,7 @@ Refer to [_[supplement] Use rclcpp::WaitSet_](./02-supp-wait_set.md) for more de The `take()` method is supported to only obtain a message which is passed through DDS as an inter-process communication. You must not use it for an intra-process communication because intra-process communication is based on another software stack of `rclcpp`. Refer to [_[supplement] Obtain a received message through intra-process communication_](./01-supp-intra-process-comm.md) in case of intra-process communication. -#### 1.1 obtain Serialized Message from Subscription +#### 1.1 Obtain Serialized Message from Subscription ROS 2 provides Serialized Message function which supports communication with arbitrary message types as explained in [Class SerializedMessage](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1SerializedMessage.html). It is used by `topic_state_monitor` in Autoware. You need to use `take_serialized()` method instead of `take()` method to obtain a message of Serialized Message type from Subscription object. From 86a08919a060982200cb6cfb4f73bca630729adc Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 14 May 2024 01:12:51 +0000 Subject: [PATCH 147/225] style(pre-commit): autofix --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 1 + 1 file changed, 1 insertion(+) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 8e516742154..0aa00968094 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -103,6 +103,7 @@ When `take(msg, msg_info)` is called, if the size of the subscription queue is g !!! note You can check the presence of incoming message with the returned value of `take()` method. However, you have to take care of the destructive nature of the take() method. The `take()` method modifies the subscription queue. Also, the `take()` method is irreversible and there is no undo operation against the `take()` method. Checking the incoming message with only the `take()` method always changes the subscription queue. If you want to check without changing the subscription queue, rclcpp::WaitSet is recommended. + Refer to [_[supplement] Use rclcpp::WaitSet_](./02-supp-wait_set.md) for more detail. !!! note From ce33caf7c14af8e308fa540c0c843391f0941967 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:13:41 +0900 Subject: [PATCH 148/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 0aa00968094..62534f000be 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -112,7 +112,7 @@ Refer to [_[supplement] Use rclcpp::WaitSet_](./02-supp-wait_set.md) for more de #### 1.1 Obtain Serialized Message from Subscription -ROS 2 provides Serialized Message function which supports communication with arbitrary message types as explained in [Class SerializedMessage](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1SerializedMessage.html). It is used by `topic_state_monitor` in Autoware. +ROS 2 provides Serialized Message function which supports communication with arbitrary message types as described in [_Class SerializedMessage_](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1SerializedMessage.html). It is used by `topic_state_monitor` in Autoware. You need to use `take_serialized()` method instead of `take()` method to obtain a message of Serialized Message type from Subscription object. Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener_serialized_message.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener_serialized_message.cpp). From e21c35ed027627025fc7449f71245d93e21573b1 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:14:41 +0900 Subject: [PATCH 149/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 62534f000be..dca8818b45c 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -113,7 +113,7 @@ Refer to [_[supplement] Use rclcpp::WaitSet_](./02-supp-wait_set.md) for more de #### 1.1 Obtain Serialized Message from Subscription ROS 2 provides Serialized Message function which supports communication with arbitrary message types as described in [_Class SerializedMessage_](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1SerializedMessage.html). It is used by `topic_state_monitor` in Autoware. -You need to use `take_serialized()` method instead of `take()` method to obtain a message of Serialized Message type from Subscription object. +You have to use the `take_serialized()` method instead of the `take()` method to obtain a `rclcpp::SerializedMessage` based message from a subscription. Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener_serialized_message.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener_serialized_message.cpp). From 3f5873efd834510311c373bbe971ee04811a7b67 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:15:24 +0900 Subject: [PATCH 150/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index dca8818b45c..55dca0260f3 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -115,7 +115,7 @@ Refer to [_[supplement] Use rclcpp::WaitSet_](./02-supp-wait_set.md) for more de ROS 2 provides Serialized Message function which supports communication with arbitrary message types as described in [_Class SerializedMessage_](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1SerializedMessage.html). It is used by `topic_state_monitor` in Autoware. You have to use the `take_serialized()` method instead of the `take()` method to obtain a `rclcpp::SerializedMessage` based message from a subscription. -Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener_serialized_message.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener_serialized_message.cpp). +Here is a sample code snippet from [_ros2_subscription_examples/simple_examples/src/timer_listener_serialized_message.cpp_](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener_serialized_message.cpp). ```c++ // receive the serialized message. From 06d1bf3a9a2a4bb35bd7867174e1b7c32aebe6d7 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:16:43 +0900 Subject: [PATCH 151/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/index.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 55dca0260f3..ac73bb48be1 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -127,7 +127,8 @@ Here is a sample code snippet from [_ros2_subscription_examples/simple_examples/ } ``` -In the code above, `msg` is created by `create_serialized_message()` to store a received message, whose type is `std::shared_ptr`. You can obtain a message of Serialized Message type by `take_serialized()` method. Note that `take_serialized()` method needs reference type data as its first argument therefore you need to convert `msg` type using `*`. + +In the code above, `msg` is created by `create_serialized_message()` to store a received message, whose type is `std::shared_ptr`. You can obtain a message of type `rclcpp::SerializedMessage` using the `take_serialized()` method. Note that the `take_serialized()` method needs reference type data as its first argument. Since `msg` is a pointer, `*msg` should be passed as the first argument to the `take_serialized(). !!! Note ROS 2's `rclcpp` supports `rclcpp::LoanedMessage` as well as `rclcpp::SerializedMessage`. If [zero copy communication via loaned messages](https://design.ros2.org/articles/zero_copy.html) is introduced to Autoware, `take_loaned()` method should be used for communication via loaned messages instead. In this document, the explanation of `take_loaned()` method is omitted because it is not used for Autoware in the present (May. 2024). From f957d55f41e62a837279ad9f661586fbd99481fa Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 14 May 2024 01:17:07 +0000 Subject: [PATCH 152/225] style(pre-commit): autofix --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 1 - 1 file changed, 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index ac73bb48be1..c8ddb39969f 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -127,7 +127,6 @@ Here is a sample code snippet from [_ros2_subscription_examples/simple_examples/ } ``` - In the code above, `msg` is created by `create_serialized_message()` to store a received message, whose type is `std::shared_ptr`. You can obtain a message of type `rclcpp::SerializedMessage` using the `take_serialized()` method. Note that the `take_serialized()` method needs reference type data as its first argument. Since `msg` is a pointer, `*msg` should be passed as the first argument to the `take_serialized(). !!! Note From fb13ce0172641038b9a7048d7d764658590804d8 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:17:59 +0900 Subject: [PATCH 153/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index c8ddb39969f..d40b428be49 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -129,7 +129,7 @@ Here is a sample code snippet from [_ros2_subscription_examples/simple_examples/ In the code above, `msg` is created by `create_serialized_message()` to store a received message, whose type is `std::shared_ptr`. You can obtain a message of type `rclcpp::SerializedMessage` using the `take_serialized()` method. Note that the `take_serialized()` method needs reference type data as its first argument. Since `msg` is a pointer, `*msg` should be passed as the first argument to the `take_serialized(). -!!! Note +!!! note ROS 2's `rclcpp` supports `rclcpp::LoanedMessage` as well as `rclcpp::SerializedMessage`. If [zero copy communication via loaned messages](https://design.ros2.org/articles/zero_copy.html) is introduced to Autoware, `take_loaned()` method should be used for communication via loaned messages instead. In this document, the explanation of `take_loaned()` method is omitted because it is not used for Autoware in the present (May. 2024). ### 2. Obtain multiple data stored in Subscription Queue From 41f9f19e7ba7063559ec4662def324623b0b5665 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:18:46 +0900 Subject: [PATCH 154/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/index.md | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index d40b428be49..9a3638e6694 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -130,7 +130,9 @@ Here is a sample code snippet from [_ros2_subscription_examples/simple_examples/ In the code above, `msg` is created by `create_serialized_message()` to store a received message, whose type is `std::shared_ptr`. You can obtain a message of type `rclcpp::SerializedMessage` using the `take_serialized()` method. Note that the `take_serialized()` method needs reference type data as its first argument. Since `msg` is a pointer, `*msg` should be passed as the first argument to the `take_serialized(). !!! note -ROS 2's `rclcpp` supports `rclcpp::LoanedMessage` as well as `rclcpp::SerializedMessage`. If [zero copy communication via loaned messages](https://design.ros2.org/articles/zero_copy.html) is introduced to Autoware, `take_loaned()` method should be used for communication via loaned messages instead. In this document, the explanation of `take_loaned()` method is omitted because it is not used for Autoware in the present (May. 2024). + + ROS 2's `rclcpp` supports both `rclcpp::LoanedMessage` and `rclcpp::SerializedMessage`. If [_zero copy communication via loaned messages_](https://design.ros2.org/articles/zero_copy.html) is introduced to Autoware, `take_loaned()` method should be used for communication via loaned messages instead. In this document, the explanation of the `take_loaned()` method is omitted because it is not used for Autoware in this time (May. 2024). + ### 2. Obtain multiple data stored in Subscription Queue From 29e0b336007faac489e4067e5e3c9282cad05b0a Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 14 May 2024 01:19:13 +0000 Subject: [PATCH 155/225] style(pre-commit): autofix --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 1 - 1 file changed, 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 9a3638e6694..593a29f434b 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -133,7 +133,6 @@ In the code above, `msg` is created by `create_serialized_message()` to store a ROS 2's `rclcpp` supports both `rclcpp::LoanedMessage` and `rclcpp::SerializedMessage`. If [_zero copy communication via loaned messages_](https://design.ros2.org/articles/zero_copy.html) is introduced to Autoware, `take_loaned()` method should be used for communication via loaned messages instead. In this document, the explanation of the `take_loaned()` method is omitted because it is not used for Autoware in this time (May. 2024). - ### 2. Obtain multiple data stored in Subscription Queue The subscription object can hold multiple messages in its queue if multiple queue size is configured with QoS setting. The conventional manner with callback function usage force a callback function to run per message. In other words, there is a constraints; a single cycle of callback function processes a single message . Note that in the conventional manner if there are one or more messages in the subscription queue, the oldest one is taken and a thread is assigned to execute a callback function, which continues until the queue becomes empty. From aa50c53cd039450fea987c3c1af700b1feb4bf8b Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:20:57 +0900 Subject: [PATCH 156/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 593a29f434b..dc5fd858588 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -135,7 +135,7 @@ In the code above, `msg` is created by `create_serialized_message()` to store a ### 2. Obtain multiple data stored in Subscription Queue -The subscription object can hold multiple messages in its queue if multiple queue size is configured with QoS setting. The conventional manner with callback function usage force a callback function to run per message. In other words, there is a constraints; a single cycle of callback function processes a single message . Note that in the conventional manner if there are one or more messages in the subscription queue, the oldest one is taken and a thread is assigned to execute a callback function, which continues until the queue becomes empty. +A subscription object can hold multiple messages in its queue if multiple queue size is configured with the QoS setting. The conventional manner using callback function forces a callback function to be executed per message. In other words, there is a constraint; a single cycle of callback function processes a single message . Note that with the conventional manner, if there are one or more messages in the subscription queue, the oldest one is taken and a thread is assigned to execute a callback function, which continues until the queue is empty. `take()` method would mitigate the constraint. `take()` method can be called in multiple iterations, so that single cycle of callback function processes multiple messages taken by `take()` methods. Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_batch_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_batch_listener.cpp) in which `take()` method is called consecutively. From 1d082e5bf7a4c6042e55afaae86de066d17b4369 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:21:48 +0900 Subject: [PATCH 157/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index dc5fd858588..479163c4b4b 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -136,7 +136,7 @@ In the code above, `msg` is created by `create_serialized_message()` to store a ### 2. Obtain multiple data stored in Subscription Queue A subscription object can hold multiple messages in its queue if multiple queue size is configured with the QoS setting. The conventional manner using callback function forces a callback function to be executed per message. In other words, there is a constraint; a single cycle of callback function processes a single message . Note that with the conventional manner, if there are one or more messages in the subscription queue, the oldest one is taken and a thread is assigned to execute a callback function, which continues until the queue is empty. -`take()` method would mitigate the constraint. `take()` method can be called in multiple iterations, so that single cycle of callback function processes multiple messages taken by `take()` methods. +The `take()` method would alleviate this limitation. The `take()` method can be called in multiple iterations, so that a single cycle of the callback function processes multiple messages taken by `take()` methods. Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_batch_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_batch_listener.cpp) in which `take()` method is called consecutively. From 5f4faae565347d38ab40d40cd3fe52388ad1eea7 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:22:37 +0900 Subject: [PATCH 158/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 479163c4b4b..0298a5ff776 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -138,7 +138,7 @@ In the code above, `msg` is created by `create_serialized_message()` to store a A subscription object can hold multiple messages in its queue if multiple queue size is configured with the QoS setting. The conventional manner using callback function forces a callback function to be executed per message. In other words, there is a constraint; a single cycle of callback function processes a single message . Note that with the conventional manner, if there are one or more messages in the subscription queue, the oldest one is taken and a thread is assigned to execute a callback function, which continues until the queue is empty. The `take()` method would alleviate this limitation. The `take()` method can be called in multiple iterations, so that a single cycle of the callback function processes multiple messages taken by `take()` methods. -Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_batch_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_batch_listener.cpp) in which `take()` method is called consecutively. +Here is a sample code, taken from [ros2_subscription_examples/simple_examples/src/timer_batch_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_batch_listener.cpp) which calls the `take()` method in a single cycle of a callback function. ```c++ std_msgs::msg::String msg; From e4d4f79013ede0ce651d210e236d4cd24f679548 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:23:34 +0900 Subject: [PATCH 159/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 0298a5ff776..86df8d866eb 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -149,7 +149,7 @@ Here is a sample code, taken from [ros2_subscription_examples/simple_examples/sr RCLCPP_INFO(this->get_logger(), "I heard: [%s]", msg.data.c_str()); ``` -In the code above, `while(sub->take(msg, msg_info))` continues to take messages from the subscription queue until the queue becomes empty. While a message is taken, the message is processed each by each. +In the code above, `while(sub->take(msg, msg_info))` continues to take messages from the subscription queue until the queue is empty. Each message taken is processed per iteration. Note that you need to determine size of a subscription queue considering both frequency of a callback function and that of a message reception. For example, if a callback function is invoked at 10Hz and topic messages are received at 50Hz, the size of the subscription queue must be at least 5 not to lose received messages. Assigning a thread to execute a callback function per message will cause performance overhead. You can use the manner introduced in this section to avoid the unexpected overhead. From 56a0e071378b94e97b3e75f98c0b0e5041bdd73a Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:24:25 +0900 Subject: [PATCH 160/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 86df8d866eb..753edc7befc 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -150,7 +150,7 @@ Here is a sample code, taken from [ros2_subscription_examples/simple_examples/sr ``` In the code above, `while(sub->take(msg, msg_info))` continues to take messages from the subscription queue until the queue is empty. Each message taken is processed per iteration. -Note that you need to determine size of a subscription queue considering both frequency of a callback function and that of a message reception. For example, if a callback function is invoked at 10Hz and topic messages are received at 50Hz, the size of the subscription queue must be at least 5 not to lose received messages. +Note that you must determine size of a subscription queue by considering both frequency of a callback function and frequency of a message reception. For example, if a callback function is invoked at 10Hz and topic messages are received at 50Hz, the size of the subscription queue must be at least 5 to avoid losing received messages. Assigning a thread to execute a callback function per message will cause performance overhead. You can use the manner introduced in this section to avoid the unexpected overhead. The manner will be effective if there is a large difference between reception frequency and consumption frequency. For example, even if a message, like a CAN message, is received at higher than 100 Hz, a user logic consumes messages at slower frequency like 10 Hz. In such case, the user logic should retrieve the required number of messages with `take()` method to avoid the unexpected overhead. From a9a84ba067bad7930ba76b3c5f932a3ff261ff16 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:25:20 +0900 Subject: [PATCH 161/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 753edc7befc..9ca4cc62f4a 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -153,7 +153,7 @@ In the code above, `while(sub->take(msg, msg_info))` continues to take messages Note that you must determine size of a subscription queue by considering both frequency of a callback function and frequency of a message reception. For example, if a callback function is invoked at 10Hz and topic messages are received at 50Hz, the size of the subscription queue must be at least 5 to avoid losing received messages. Assigning a thread to execute a callback function per message will cause performance overhead. You can use the manner introduced in this section to avoid the unexpected overhead. -The manner will be effective if there is a large difference between reception frequency and consumption frequency. For example, even if a message, like a CAN message, is received at higher than 100 Hz, a user logic consumes messages at slower frequency like 10 Hz. In such case, the user logic should retrieve the required number of messages with `take()` method to avoid the unexpected overhead. +The manner will be effective when there is a large difference between reception frequency and consumption frequency. For example, even if a message, such as a CAN message, is received at higher than 100 Hz, a user logic consumes messages at slower frequency such as 10 Hz. In such a case, the user logic should retrieve the required number of messages with the `take()` method to avoid the unexpected overhead. ### 3. Obtain data by calling `Subscription->take` and then call a callback function From a0410cd952e4ab378e98e2b293c8490ee9bde2ee Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 14 May 2024 01:25:33 +0000 Subject: [PATCH 162/225] style(pre-commit): autofix --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 9ca4cc62f4a..39723d1f6b7 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -150,7 +150,7 @@ Here is a sample code, taken from [ros2_subscription_examples/simple_examples/sr ``` In the code above, `while(sub->take(msg, msg_info))` continues to take messages from the subscription queue until the queue is empty. Each message taken is processed per iteration. -Note that you must determine size of a subscription queue by considering both frequency of a callback function and frequency of a message reception. For example, if a callback function is invoked at 10Hz and topic messages are received at 50Hz, the size of the subscription queue must be at least 5 to avoid losing received messages. +Note that you must determine size of a subscription queue by considering both frequency of a callback function and frequency of a message reception. For example, if a callback function is invoked at 10Hz and topic messages are received at 50Hz, the size of the subscription queue must be at least 5 to avoid losing received messages. Assigning a thread to execute a callback function per message will cause performance overhead. You can use the manner introduced in this section to avoid the unexpected overhead. The manner will be effective when there is a large difference between reception frequency and consumption frequency. For example, even if a message, such as a CAN message, is received at higher than 100 Hz, a user logic consumes messages at slower frequency such as 10 Hz. In such a case, the user logic should retrieve the required number of messages with the `take()` method to avoid the unexpected overhead. From e056f69671bfe12427da7717999dbff87b2c27dd Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:26:02 +0900 Subject: [PATCH 163/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 39723d1f6b7..6a030dfd40a 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -158,7 +158,7 @@ The manner will be effective when there is a large difference between reception ### 3. Obtain data by calling `Subscription->take` and then call a callback function You can combine the `take()` (strictly `take_type_erased()`) method and the callback function to process received messages in a consistent way. Using this combination does not require waking up a thread. -Here is a sample code excerpted from [ros2_subscription_examples/simple_examples/src/timer_listener_using_callback.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener_using_callback.cpp). +Here is a sample code snippet from [_ros2_subscription_examples/simple_examples/src/timer_listener_using_callback.cpp_](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener_using_callback.cpp). ```c++ auto msg = sub_->create_message(); From 37a3d0ada72407c7f15ead9b5eb335c651add468 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:27:45 +0900 Subject: [PATCH 164/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 6a030dfd40a..8583615bdfd 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -168,7 +168,7 @@ Here is a sample code snippet from [_ros2_subscription_examples/simple_examples/ ``` -In the code above, a message is taken by `take_type_erased()` method before calling a registered callback function via `handle_message()` method. Note that you need to use `take_type_erased()` instead of `take()`. `take_type_erased()` needs `void` type data as its first argument. You need to use `get()` method to convert `msg` whose type is `shared_ptr` to `void` type. Then `handle_message()` method is called with the obtained message. A registered callback function is called inside of `handle_message()`. +In the code above, a message is taken by the `take_type_erased()` method before a registered callback function is called via the `handle_message()` method. Note that you must use `take_type_erased()` instead of `take()`. `take_type_erased()` needs `void` type data as its first argument. You must use the `get()` method to convert `msg` whose type is `shared_ptr` to `void` type. Then the `handle_message()` method is called with the obtained message. A registered callback function is called within `handle_message()`. You don't need to take care of message type which is passed to `take_type_erased()` and `handle_message()`. You can define the message variable as `auto msg = sub_->create_message();`. You can also refer to [API document](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1SubscriptionBase.html#_CPPv4N6rclcpp16SubscriptionBase16take_type_erasedEPvRN6rclcpp11MessageInfoE) as for `create_message()`, `take_type_erased()` and `handle_message()`. From 23606b3c5069bd503f92a8e5c03b6827a8dc9703 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 14 May 2024 01:28:09 +0000 Subject: [PATCH 165/225] style(pre-commit): autofix --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 8583615bdfd..8325344a87e 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -168,7 +168,7 @@ Here is a sample code snippet from [_ros2_subscription_examples/simple_examples/ ``` -In the code above, a message is taken by the `take_type_erased()` method before a registered callback function is called via the `handle_message()` method. Note that you must use `take_type_erased()` instead of `take()`. `take_type_erased()` needs `void` type data as its first argument. You must use the `get()` method to convert `msg` whose type is `shared_ptr` to `void` type. Then the `handle_message()` method is called with the obtained message. A registered callback function is called within `handle_message()`. +In the code above, a message is taken by the `take_type_erased()` method before a registered callback function is called via the `handle_message()` method. Note that you must use `take_type_erased()` instead of `take()`. `take_type_erased()` needs `void` type data as its first argument. You must use the `get()` method to convert `msg` whose type is `shared_ptr` to `void` type. Then the `handle_message()` method is called with the obtained message. A registered callback function is called within `handle_message()`. You don't need to take care of message type which is passed to `take_type_erased()` and `handle_message()`. You can define the message variable as `auto msg = sub_->create_message();`. You can also refer to [API document](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1SubscriptionBase.html#_CPPv4N6rclcpp16SubscriptionBase16take_type_erasedEPvRN6rclcpp11MessageInfoE) as for `create_message()`, `take_type_erased()` and `handle_message()`. From e514b8a43a95e1c07494cb744dc02ca9bf544917 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:28:36 +0900 Subject: [PATCH 166/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 8325344a87e..0e41bc14d63 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -170,7 +170,7 @@ Here is a sample code snippet from [_ros2_subscription_examples/simple_examples/ In the code above, a message is taken by the `take_type_erased()` method before a registered callback function is called via the `handle_message()` method. Note that you must use `take_type_erased()` instead of `take()`. `take_type_erased()` needs `void` type data as its first argument. You must use the `get()` method to convert `msg` whose type is `shared_ptr` to `void` type. Then the `handle_message()` method is called with the obtained message. A registered callback function is called within `handle_message()`. You don't need to take care of message type which is passed to `take_type_erased()` and `handle_message()`. You can define the message variable as `auto msg = sub_->create_message();`. -You can also refer to [API document](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1SubscriptionBase.html#_CPPv4N6rclcpp16SubscriptionBase16take_type_erasedEPvRN6rclcpp11MessageInfoE) as for `create_message()`, `take_type_erased()` and `handle_message()`. +You can also refer to [the API document](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1SubscriptionBase.html#_CPPv4N6rclcpp16SubscriptionBase16take_type_erasedEPvRN6rclcpp11MessageInfoE) as for `create_message()`, `take_type_erased()` and `handle_message()`. ### 4. Obtain data by a callback function From d644f5a556c6f7af8ed456aebf6f802c6c9672be Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:29:19 +0900 Subject: [PATCH 167/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 0e41bc14d63..f8795b41ce0 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -174,7 +174,7 @@ You can also refer to [the API document](http://docs.ros.org/en/humble/p/rclcpp/ ### 4. Obtain data by a callback function -A conventional manner used typically in ROS 2 application, a message reference using a callback function, is available. If you don't use a callback group with `automatically_add_to_executor_with_node = false`, a registered callback function is called automatically by Executor when a topic message is received. +A conventional manner, typically used in ROS 2 application, is a message reference using a callback function, is available. If you don't use a callback group with `automatically_add_to_executor_with_node = false`, a registered callback function will be called automatically by an executor when a topic message is received. One of advantages of this manner is you don't need to take care whether a topic message is passed through inter-process or intra-process. Remind that `take()` can only be used in case of inter-process communication via DDS, while another manner provided by `rclcpp` can be used for intra-process communication via `rclcpp`. ## Appendix From 412aaf11ee6d2d517855c729c69ab52d8ea57ac2 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:30:04 +0900 Subject: [PATCH 168/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index f8795b41ce0..c452b515da2 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -175,7 +175,7 @@ You can also refer to [the API document](http://docs.ros.org/en/humble/p/rclcpp/ ### 4. Obtain data by a callback function A conventional manner, typically used in ROS 2 application, is a message reference using a callback function, is available. If you don't use a callback group with `automatically_add_to_executor_with_node = false`, a registered callback function will be called automatically by an executor when a topic message is received. -One of advantages of this manner is you don't need to take care whether a topic message is passed through inter-process or intra-process. Remind that `take()` can only be used in case of inter-process communication via DDS, while another manner provided by `rclcpp` can be used for intra-process communication via `rclcpp`. +One of the advantages of this manner is that you don't have to take care whether a topic message is passed through inter-process or intra-process. Remember that `take()` can only be used for inter-process communication via DDS, while another manner provided by `rclcpp` can be used for intra-process communication via `rclcpp`. ## Appendix From bdc80a0cb004fe9195b021969c79e7913b313c82 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:30:55 +0900 Subject: [PATCH 169/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index c452b515da2..e744ab1b893 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -179,7 +179,7 @@ One of the advantages of this manner is that you don't have to take care whether ## Appendix -A callback function is used to obtain a topic message in many of ROS 2 applications as if it is a rule or a custom. As this document page explained, you can use `Subscription->take()` method to obtain a topic message without calling a subscription callback function. +A callback function is used to obtain a topic message in many of ROS 2 applications. It is as like a rule or a custom. As this document page explains, you can use the `Subscription->take()` method to obtain a topic message without calling a subscription callback function. This manner is also documented in [Template Class Subscription — rclcpp 16.0.8 documentation](https://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1Subscription.html#_CPPv4N6rclcpp12Subscription4takeER14ROSMessageTypeRN6rclcpp11MessageInfoE). Many of ROS 2 users may be afraid to use the `take()` method because they may not be so familiar with it and there is a lack of documentation about `take()`, but it is widely used in the `rclcpp::Executor` implementation as shown in [_rclcpp/executor.cpp_](https://github.com/ros2/rclcpp/blob/47c977d1bc82fc76dd21f870bcd3ea473eca2f59/rclcpp/src/rclcpp/executor.cpp#L643-L648) shown below. So it turns out that you are indirectly using the `take()` method, whether you know it or not. From acc19316921fbd503c1d06d2cb3988ece8641669 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 10:31:32 +0900 Subject: [PATCH 170/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index e744ab1b893..7e5eb3946e4 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -180,7 +180,7 @@ One of the advantages of this manner is that you don't have to take care whether ## Appendix A callback function is used to obtain a topic message in many of ROS 2 applications. It is as like a rule or a custom. As this document page explains, you can use the `Subscription->take()` method to obtain a topic message without calling a subscription callback function. -This manner is also documented in [Template Class Subscription — rclcpp 16.0.8 documentation](https://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1Subscription.html#_CPPv4N6rclcpp12Subscription4takeER14ROSMessageTypeRN6rclcpp11MessageInfoE). +This manner is also documented in [_Template Class Subscription — rclcpp 16.0.8 documentation_](https://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1Subscription.html#_CPPv4N6rclcpp12Subscription4takeER14ROSMessageTypeRN6rclcpp11MessageInfoE). Many of ROS 2 users may be afraid to use the `take()` method because they may not be so familiar with it and there is a lack of documentation about `take()`, but it is widely used in the `rclcpp::Executor` implementation as shown in [_rclcpp/executor.cpp_](https://github.com/ros2/rclcpp/blob/47c977d1bc82fc76dd21f870bcd3ea473eca2f59/rclcpp/src/rclcpp/executor.cpp#L643-L648) shown below. So it turns out that you are indirectly using the `take()` method, whether you know it or not. From 551ade2c44d7f2ee271e5b971b3e6ce4173b241c Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:26:37 +0900 Subject: [PATCH 171/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 7e5eb3946e4..5c8bd382fad 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -193,7 +193,7 @@ Many of ROS 2 users may be afraid to use the `take()` method because they may no [&]() {subscription->handle_message(message, message_info);}); ``` -!!!Note +!!!note Strictly speaking, `take_type_erased()` method is called in the Executor, but not `take()` method. But `take_type_erased()` is the embodiment of `take()`, while `take()` internally calls `take_type_erased()`. From b7fc45cff307e1b25b2419073868e804471cdabb Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:27:52 +0900 Subject: [PATCH 172/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/index.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 5c8bd382fad..1168837f2e3 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -194,7 +194,8 @@ Many of ROS 2 users may be afraid to use the `take()` method because they may no ``` !!!note -Strictly speaking, `take_type_erased()` method is called in the Executor, but not `take()` method. + + Strictly speaking, the `take_type_erased()` method is called in the executor, but not the `take()` method. But `take_type_erased()` is the embodiment of `take()`, while `take()` internally calls `take_type_erased()`. If Executor is programmed to call a callback function, Executor itself determines when to do it. Because Executor calls a callback function with best-effort policy basically, it can occur that a message is not referred to or processed when it is needed in a node. Therefore it is desirable to call `take()` method directly **to ensue that a message is referred to or processed at the intended time.** From 5efdab123c92a203339cda40eb9bb94efd51ba05 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 14 May 2024 02:28:14 +0000 Subject: [PATCH 173/225] style(pre-commit): autofix --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 1 + 1 file changed, 1 insertion(+) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 1168837f2e3..caa9904cc44 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -196,6 +196,7 @@ Many of ROS 2 users may be afraid to use the `take()` method because they may no !!!note Strictly speaking, the `take_type_erased()` method is called in the executor, but not the `take()` method. + But `take_type_erased()` is the embodiment of `take()`, while `take()` internally calls `take_type_erased()`. If Executor is programmed to call a callback function, Executor itself determines when to do it. Because Executor calls a callback function with best-effort policy basically, it can occur that a message is not referred to or processed when it is needed in a node. Therefore it is desirable to call `take()` method directly **to ensue that a message is referred to or processed at the intended time.** From 1abf20f315dce901836a23a2a2bc84845b66bd44 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:29:15 +0900 Subject: [PATCH 174/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/index.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index caa9904cc44..4636741f597 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -197,6 +197,7 @@ Many of ROS 2 users may be afraid to use the `take()` method because they may no Strictly speaking, the `take_type_erased()` method is called in the executor, but not the `take()` method. -But `take_type_erased()` is the embodiment of `take()`, while `take()` internally calls `take_type_erased()`. + But `take_type_erased()` is the embodiment of `take()`, while `take()` internally calls `take_type_erased()`. + If Executor is programmed to call a callback function, Executor itself determines when to do it. Because Executor calls a callback function with best-effort policy basically, it can occur that a message is not referred to or processed when it is needed in a node. Therefore it is desirable to call `take()` method directly **to ensue that a message is referred to or processed at the intended time.** From 060c91442f2d7d81871c2e0b961e180b8c4bddd7 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:29:44 +0900 Subject: [PATCH 175/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 4636741f597..0dca1e2bb3a 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -200,4 +200,4 @@ Many of ROS 2 users may be afraid to use the `take()` method because they may no But `take_type_erased()` is the embodiment of `take()`, while `take()` internally calls `take_type_erased()`. -If Executor is programmed to call a callback function, Executor itself determines when to do it. Because Executor calls a callback function with best-effort policy basically, it can occur that a message is not referred to or processed when it is needed in a node. Therefore it is desirable to call `take()` method directly **to ensue that a message is referred to or processed at the intended time.** +If `rclcpp::Executor` based object, an executor, is programmed to call a callback function, the executor itself determines when to do it. Because the executor is essentially calling a best-effort callback function, the message is not guaranteed to be necessarily referenced or processed even though it is received. Therefore it is desirable to call the `take()` method directly to ensure that a message is referenced or processed at the intended time. From aac9166aaa2b852487b3265c2e574f15ff3751d2 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 14 May 2024 02:30:12 +0000 Subject: [PATCH 176/225] style(pre-commit): autofix --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 1 - 1 file changed, 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 0dca1e2bb3a..6bc5514038f 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -199,5 +199,4 @@ Many of ROS 2 users may be afraid to use the `take()` method because they may no But `take_type_erased()` is the embodiment of `take()`, while `take()` internally calls `take_type_erased()`. - If `rclcpp::Executor` based object, an executor, is programmed to call a callback function, the executor itself determines when to do it. Because the executor is essentially calling a best-effort callback function, the message is not guaranteed to be necessarily referenced or processed even though it is received. Therefore it is desirable to call the `take()` method directly to ensure that a message is referenced or processed at the intended time. From 9cdd0721fe1d69ea546d50e91fb4aff31bf9de5f Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:31:47 +0900 Subject: [PATCH 177/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../topic-message-handling/01-supp-intra-process-comm.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index 2de3f5ae0f3..39dd5fa28c8 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -17,7 +17,7 @@ std::shared_ptr data = waitable.take_data(); waitable.execute(data); ``` -Here is a sample program in [ros2_subscription_examples/intra_process_talker_listener/src/timer_listener_intra_process.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/intra_process_talker_listener/src/timer_listener_intra_process.cpp). +Here is a sample program in [_ros2_subscription_examples/intra_process_talker_listener/src/timer_listener_intra_process.cpp at main · takam5f2/ros2_subscription_examples_](https://github.com/takam5f2/ros2_subscription_examples/blob/main/intra_process_talker_listener/src/timer_listener_intra_process.cpp). You can run the program as below. If you set `true` to `use_intra_process_comms`, intra-process communication is performed, while if you set `false`, inter-process communication is performed. ```console From 6be6160037bc99e7dedc82ee0271ca9e778f7fd7 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:32:17 +0900 Subject: [PATCH 178/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../topic-message-handling/01-supp-intra-process-comm.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md index 39dd5fa28c8..e2fcd9ae495 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md @@ -2,7 +2,7 @@ ## Topic message handling in intra-process communication -`rclcpp` supports intra-process communication. As explained in [Topic message handling guideline](index.md), `take()` method can not be used in the case of intra-process communication. `take()` can not return a topic message which is received through inter-process communication. +`rclcpp` supports intra-process communication. As explained in [_Topic message handling guideline_](index.md), `take()` method can not be used in the case of intra-process communication. `take()` can not return a topic message which is received through inter-process communication. However, methods for intra-process communication are provided, similar to the methods for inter-process communication described in [_obtain data by calling Subscription->take and then call a callback function_](./index.md#3-obtain-data-by-calling-subscription-take-and-then-call-a-callback-function). `take_data()` method is provided to obtain a received data in the case of intra-process communication and the received data must be processed through `execute()` method. The return value of `take_data()` is based on the complicated data structure, `execute()` method should be used along with `take_data()` method. Refer to [_Template Class SubscriptionIntraProcess — rclcpp 16.0.8 documentation_](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1experimental_1_1SubscriptionIntraProcess.html#_CPPv4N6rclcpp12experimental24SubscriptionIntraProcess9take_dataEv) for `take_data()` and `execute()` for more detail. From 8977a7e65ce620ccbe8cf05d8e49fb172ea19d31 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:32:57 +0900 Subject: [PATCH 179/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index 8fe7f7d437e..b9d784b3bd8 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -2,7 +2,7 @@ ## What is `rclcpp::WaitSet` -As explained in [_call take() method of Subscription object_](./index.md#call-take-method-of-subscription-object), `take()` method is irreversible. Once `take()` method is executed, a state of a subscription object changes. Because there is no undo operation against `take()` method, the subscription object can not be restored to its previous state. You can use `rclcpp::WaitSet` before calling `take()` to check the arrival of an incoming message in the subscription queue. +As explained in [_call take() method of Subscription object_](./index.md#call-take-method-of-subscription-object), the `take()` method is irreversible. Once the `take()` method is executed, a state of a subscription object changes. Because there is no undo operation against the `take()` method, the subscription object can not be restored to its previous state. You can use the `rclcpp::WaitSet` before calling the `take()` to check the arrival of an incoming message in the subscription queue. The following sample code shows how `wait_set_.wait()` tells you that a message has already been received and can be obtained by `take()`. ```c++ From 93b8d69db00ca6f10773e7278895a3bb7a89e754 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:33:29 +0900 Subject: [PATCH 180/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index b9d784b3bd8..55b8d9e65ce 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -3,7 +3,7 @@ ## What is `rclcpp::WaitSet` As explained in [_call take() method of Subscription object_](./index.md#call-take-method-of-subscription-object), the `take()` method is irreversible. Once the `take()` method is executed, a state of a subscription object changes. Because there is no undo operation against the `take()` method, the subscription object can not be restored to its previous state. You can use the `rclcpp::WaitSet` before calling the `take()` to check the arrival of an incoming message in the subscription queue. -The following sample code shows how `wait_set_.wait()` tells you that a message has already been received and can be obtained by `take()`. +The following sample code shows how the `wait_set_.wait()` tells you that a message has already been received and can be obtained by the `take()`. ```c++ auto wait_result = wait_set_.wait(std::chrono::milliseconds(0)); From 7f15ca276fbec14b2d76e77a0dd874b43851bfea Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:34:20 +0900 Subject: [PATCH 181/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index 55b8d9e65ce..6e6e9a39c28 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -14,7 +14,7 @@ The following sample code shows how the `wait_set_.wait()` tells you that a mess RCLCPP_INFO(this->get_logger(), "I heard: [%s]", msg.data.c_str()); ``` -A single `rclcpp::WaitSet` object is able to observe multiple subscription objects. If there are multiple subscriptions for different topics, you can check arrival of incoming messages per subscription. Algorithms used in the field of autonomous robot requires multiple incoming messages, like sensor data or actuation state. Using `rclcpp::WaitSet` for the multiple subscriptions, they are able to check whether of not required messages have arrived without taking any message. +A single `rclcpp::WaitSet` object is able to observe multiple subscription objects. If there are multiple subscriptions for different topics, you can check the arrival of incoming messages per subscription. Algorithms used in the field of autonomous robots requires multiple incoming messages, such as sensor data or actuation state. Using `rclcpp::WaitSet` for the multiple subscriptions, they are able to check whether or not required messages have arrived without taking any message. ```c++ auto wait_result = wait_set_.wait(std::chrono::milliseconds(0)); From 8c1bcb62b9f63dc8c20454a4b8e18b589b9e85b2 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:34:54 +0900 Subject: [PATCH 182/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index 6e6e9a39c28..5ed6c52c616 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -30,7 +30,7 @@ A single `rclcpp::WaitSet` object is able to observe multiple subscription objec } ``` -In the code above, unless `rclcpp::WaitSet` is used, it is impossible to verify arrival of all needed messages without changing state of the subscription objects. +In the code above, unless `rclcpp::WaitSet` is used, it is impossible to verify the arrival of all needed messages without changing state of the subscription objects. ## Coding manner From 0210c99df94bf475b66f246657dd8db920e23077 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:35:29 +0900 Subject: [PATCH 183/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index 5ed6c52c616..42f6458fd21 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -34,7 +34,7 @@ In the code above, unless `rclcpp::WaitSet` is used, it is impossible to verify ## Coding manner -This section explains the coding manner using `rclcpp::WaitSet` with a sample code below. +This section explains how to code using `rclcpp::WaitSet` with a sample code below. - [ros2_subscription_examples/waitset_examples/src/talker_triple.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/talker_triple.cpp) - it publishes `/chatter` per one second, `/slower_chatter` per two seconds, and `/slowest_chatter` per three seconds periodically From 51c1a6663e1f537927b6ef954041518dfae2544a Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:36:20 +0900 Subject: [PATCH 184/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index 42f6458fd21..f944f785939 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -36,7 +36,7 @@ In the code above, unless `rclcpp::WaitSet` is used, it is impossible to verify This section explains how to code using `rclcpp::WaitSet` with a sample code below. -- [ros2_subscription_examples/waitset_examples/src/talker_triple.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/talker_triple.cpp) +- [_ros2_subscription_examples/waitset_examples/src/talker_triple.cpp at main · takam5f2/ros2_subscription_examples_](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/talker_triple.cpp) - it publishes `/chatter` per one second, `/slower_chatter` per two seconds, and `/slowest_chatter` per three seconds periodically - [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp) - it queries `WaitSet` per one second and if there is a message available, it obtains the message by `take()` From 817caa2913b74b6459f7c67853c8b8675a7a5971 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:37:01 +0900 Subject: [PATCH 185/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index f944f785939..fd144cb3fb2 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -37,7 +37,7 @@ In the code above, unless `rclcpp::WaitSet` is used, it is impossible to verify This section explains how to code using `rclcpp::WaitSet` with a sample code below. - [_ros2_subscription_examples/waitset_examples/src/talker_triple.cpp at main · takam5f2/ros2_subscription_examples_](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/talker_triple.cpp) - - it publishes `/chatter` per one second, `/slower_chatter` per two seconds, and `/slowest_chatter` per three seconds periodically + - It periodically publishes `/chatter` every second, `/slower_chatter` every two seconds, and `/slowest_chatter` every three seconds. - [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp) - it queries `WaitSet` per one second and if there is a message available, it obtains the message by `take()` - it has each subscription for `/chatter` `/slower_chatter`, and `/slower_chatter` From 7bb4253691d1b66dd0339a2def8924847e117185 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 14 May 2024 02:37:24 +0000 Subject: [PATCH 186/225] style(pre-commit): autofix --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index fd144cb3fb2..c6cf9b92334 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -37,7 +37,7 @@ In the code above, unless `rclcpp::WaitSet` is used, it is impossible to verify This section explains how to code using `rclcpp::WaitSet` with a sample code below. - [_ros2_subscription_examples/waitset_examples/src/talker_triple.cpp at main · takam5f2/ros2_subscription_examples_](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/talker_triple.cpp) - - It periodically publishes `/chatter` every second, `/slower_chatter` every two seconds, and `/slowest_chatter` every three seconds. + - It periodically publishes `/chatter` every second, `/slower_chatter` every two seconds, and `/slowest_chatter` every three seconds. - [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp) - it queries `WaitSet` per one second and if there is a message available, it obtains the message by `take()` - it has each subscription for `/chatter` `/slower_chatter`, and `/slower_chatter` From 047503481c088656c4e8973445138596bcdd54ea Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:38:18 +0900 Subject: [PATCH 187/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index c6cf9b92334..863e714871b 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -38,7 +38,7 @@ This section explains how to code using `rclcpp::WaitSet` with a sample code bel - [_ros2_subscription_examples/waitset_examples/src/talker_triple.cpp at main · takam5f2/ros2_subscription_examples_](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/talker_triple.cpp) - It periodically publishes `/chatter` every second, `/slower_chatter` every two seconds, and `/slowest_chatter` every three seconds. -- [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp) +- [_ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples_](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp) - it queries `WaitSet` per one second and if there is a message available, it obtains the message by `take()` - it has each subscription for `/chatter` `/slower_chatter`, and `/slower_chatter` From 426507de626544adef4bbeddd7427dbfcd1bbbf4 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:38:56 +0900 Subject: [PATCH 188/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index 863e714871b..5295baef848 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -39,7 +39,7 @@ This section explains how to code using `rclcpp::WaitSet` with a sample code bel - [_ros2_subscription_examples/waitset_examples/src/talker_triple.cpp at main · takam5f2/ros2_subscription_examples_](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/talker_triple.cpp) - It periodically publishes `/chatter` every second, `/slower_chatter` every two seconds, and `/slowest_chatter` every three seconds. - [_ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples_](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp) - - it queries `WaitSet` per one second and if there is a message available, it obtains the message by `take()` + - It queries `WaitSet` per one second and if there is a message available, it obtains the message with `take()` - it has each subscription for `/chatter` `/slower_chatter`, and `/slower_chatter` Following three steps are needed to use `WaitSet`. From caff81e963757b02063fab7c5f895203ebe9e2e2 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:39:44 +0900 Subject: [PATCH 189/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index 5295baef848..a45983c05b4 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -40,7 +40,7 @@ This section explains how to code using `rclcpp::WaitSet` with a sample code bel - It periodically publishes `/chatter` every second, `/slower_chatter` every two seconds, and `/slowest_chatter` every three seconds. - [_ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples_](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp) - It queries `WaitSet` per one second and if there is a message available, it obtains the message with `take()` - - it has each subscription for `/chatter` `/slower_chatter`, and `/slower_chatter` + - It has three subscriptions for `/chatter` `/slower_chatter`, and `/slower_chatter` Following three steps are needed to use `WaitSet`. From 160addaccd693d77d717262467debef3f1fb422f Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:40:17 +0900 Subject: [PATCH 190/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index a45983c05b4..c801fe2f8e1 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -42,7 +42,7 @@ This section explains how to code using `rclcpp::WaitSet` with a sample code bel - It queries `WaitSet` per one second and if there is a message available, it obtains the message with `take()` - It has three subscriptions for `/chatter` `/slower_chatter`, and `/slower_chatter` -Following three steps are needed to use `WaitSet`. +The following three steps are required to use `rclcpp::WaitSet`. ### 1. Declare and initialize `WaitSet` From c4b3428ee5584ae57609ae243bd643e0c77f631a Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:40:53 +0900 Subject: [PATCH 191/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index c801fe2f8e1..e8079e901f7 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -46,7 +46,7 @@ The following three steps are required to use `rclcpp::WaitSet`. ### 1. Declare and initialize `WaitSet` -You need to declare WaitSet variable first to use. +You must first instantiate a `rclcpp::WaitSet` based object. Below is excerption from [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp). ```c++ From 22e9ac8f8a3b07c42853f12f7315083efd220d09 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:41:30 +0900 Subject: [PATCH 192/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index e8079e901f7..ad08a38015e 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -47,7 +47,7 @@ The following three steps are required to use `rclcpp::WaitSet`. ### 1. Declare and initialize `WaitSet` You must first instantiate a `rclcpp::WaitSet` based object. -Below is excerption from [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp). +Below is a snippet from [_ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples_](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp). ```c++ rclcpp::WaitSet wait_set_; From c639722dafbd852300f7218a954c47bf20877af1 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:42:02 +0900 Subject: [PATCH 193/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index ad08a38015e..a4c5e6155bd 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -53,7 +53,7 @@ Below is a snippet from [_ros2_subscription_examples/waitset_examples/src/timer_ rclcpp::WaitSet wait_set_; ``` -The `rclcpp::WaitSet` object can be configured during runtime. It is not thread-safe as explained in[_API specification of `rclcpp::WaitSet`_](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1ad6fb19c154de27e92430309d2da25ac3.html) +There are several types of classes similar to the `rclcpp::WaitSet`. The `rclcpp::WaitSet` object can be configured during runtime. It is not thread-safe as explained in the [_API specification of `rclcpp::WaitSet`_](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1ad6fb19c154de27e92430309d2da25ac3.html) Thread-safe `WaitSet` are prepared by the `rclcpp` package as listed below. - [Typedef rclcpp::ThreadSafeWaitSet](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1acaec573e71549fd3078644e18e7f7127.html) From 24563bbd8804df1feda0bab452cf76b46b24e548 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:44:37 +0900 Subject: [PATCH 194/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index a4c5e6155bd..870c301ab8e 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -54,7 +54,7 @@ rclcpp::WaitSet wait_set_; ``` There are several types of classes similar to the `rclcpp::WaitSet`. The `rclcpp::WaitSet` object can be configured during runtime. It is not thread-safe as explained in the [_API specification of `rclcpp::WaitSet`_](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1ad6fb19c154de27e92430309d2da25ac3.html) -Thread-safe `WaitSet` are prepared by the `rclcpp` package as listed below. +The thread-safe classes that are replacements for `rclcpp::WaitSet' are provided by the `rclcpp' package as listed below. - [Typedef rclcpp::ThreadSafeWaitSet](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1acaec573e71549fd3078644e18e7f7127.html) - Subscription, Timer, and so on can be registered to WaitSet only in thread-safe state From 2c1589a63a223ea4ecd6d377f0492b80fe72778e Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:45:13 +0900 Subject: [PATCH 195/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index 870c301ab8e..95681e30758 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -56,7 +56,7 @@ rclcpp::WaitSet wait_set_; There are several types of classes similar to the `rclcpp::WaitSet`. The `rclcpp::WaitSet` object can be configured during runtime. It is not thread-safe as explained in the [_API specification of `rclcpp::WaitSet`_](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1ad6fb19c154de27e92430309d2da25ac3.html) The thread-safe classes that are replacements for `rclcpp::WaitSet' are provided by the `rclcpp' package as listed below. -- [Typedef rclcpp::ThreadSafeWaitSet](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1acaec573e71549fd3078644e18e7f7127.html) +- [_Typedef rclcpp::ThreadSafeWaitSet_](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1acaec573e71549fd3078644e18e7f7127.html) - Subscription, Timer, and so on can be registered to WaitSet only in thread-safe state - sample code is here: [examples/rclcpp/wait_set/src/thread_safe_wait_set.cpp at rolling · ros2/examples](https://github.com/ros2/examples/blob/rolling/rclcpp/wait_set/src/thread_safe_wait_set.cpp) - [Typedef rclcpp::StaticWaitSet](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1adb06acf4a5723b1445fa6ed4e8f73374.html) From aec27816683a05258bfe0ca055fca7243bb5606c Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 14 May 2024 02:45:36 +0000 Subject: [PATCH 196/225] style(pre-commit): autofix --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index 95681e30758..d3adcf3e5ef 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -54,7 +54,7 @@ rclcpp::WaitSet wait_set_; ``` There are several types of classes similar to the `rclcpp::WaitSet`. The `rclcpp::WaitSet` object can be configured during runtime. It is not thread-safe as explained in the [_API specification of `rclcpp::WaitSet`_](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1ad6fb19c154de27e92430309d2da25ac3.html) -The thread-safe classes that are replacements for `rclcpp::WaitSet' are provided by the `rclcpp' package as listed below. +The thread-safe classes that are replacements for `rclcpp::WaitSet' are provided by the`rclcpp' package as listed below. - [_Typedef rclcpp::ThreadSafeWaitSet_](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1acaec573e71549fd3078644e18e7f7127.html) - Subscription, Timer, and so on can be registered to WaitSet only in thread-safe state From 7924922aa12925c4523db0f6b0491df392f2201a Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:46:37 +0900 Subject: [PATCH 197/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index d3adcf3e5ef..680dd6343ea 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -57,7 +57,7 @@ There are several types of classes similar to the `rclcpp::WaitSet`. The `rclcpp The thread-safe classes that are replacements for `rclcpp::WaitSet' are provided by the`rclcpp' package as listed below. - [_Typedef rclcpp::ThreadSafeWaitSet_](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1acaec573e71549fd3078644e18e7f7127.html) - - Subscription, Timer, and so on can be registered to WaitSet only in thread-safe state + - Subscription, timer, etc. can only be registered to `ThreadSafeWaitSet` only in thread-safe state - sample code is here: [examples/rclcpp/wait_set/src/thread_safe_wait_set.cpp at rolling · ros2/examples](https://github.com/ros2/examples/blob/rolling/rclcpp/wait_set/src/thread_safe_wait_set.cpp) - [Typedef rclcpp::StaticWaitSet](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1adb06acf4a5723b1445fa6ed4e8f73374.html) - Subscription, Timer, and so on can be registered to WaitSet only at initialization From d9e8972ba4ee4edb3d5536d91b3c6d76920c87d0 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:47:15 +0900 Subject: [PATCH 198/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index 680dd6343ea..812a2ed27ad 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -58,7 +58,7 @@ The thread-safe classes that are replacements for `rclcpp::WaitSet' are provided - [_Typedef rclcpp::ThreadSafeWaitSet_](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1acaec573e71549fd3078644e18e7f7127.html) - Subscription, timer, etc. can only be registered to `ThreadSafeWaitSet` only in thread-safe state - - sample code is here: [examples/rclcpp/wait_set/src/thread_safe_wait_set.cpp at rolling · ros2/examples](https://github.com/ros2/examples/blob/rolling/rclcpp/wait_set/src/thread_safe_wait_set.cpp) + - Sample code is here: [examples/rclcpp/wait_set/src/thread_safe_wait_set.cpp at rolling · ros2/examples](https://github.com/ros2/examples/blob/rolling/rclcpp/wait_set/src/thread_safe_wait_set.cpp) - [Typedef rclcpp::StaticWaitSet](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1adb06acf4a5723b1445fa6ed4e8f73374.html) - Subscription, Timer, and so on can be registered to WaitSet only at initialization - here are sample codes: From 66b43801ec7e8b2d512515354858a71ca2cc04c0 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:47:50 +0900 Subject: [PATCH 199/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index 812a2ed27ad..8733602033f 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -59,7 +59,7 @@ The thread-safe classes that are replacements for `rclcpp::WaitSet' are provided - [_Typedef rclcpp::ThreadSafeWaitSet_](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1acaec573e71549fd3078644e18e7f7127.html) - Subscription, timer, etc. can only be registered to `ThreadSafeWaitSet` only in thread-safe state - Sample code is here: [examples/rclcpp/wait_set/src/thread_safe_wait_set.cpp at rolling · ros2/examples](https://github.com/ros2/examples/blob/rolling/rclcpp/wait_set/src/thread_safe_wait_set.cpp) -- [Typedef rclcpp::StaticWaitSet](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1adb06acf4a5723b1445fa6ed4e8f73374.html) +- [_Typedef rclcpp::StaticWaitSet_](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1adb06acf4a5723b1445fa6ed4e8f73374.html) - Subscription, Timer, and so on can be registered to WaitSet only at initialization - here are sample codes: - [ros2_subscription_examples/waitset_examples/src/timer_listener_twin_static.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_twin_static.cpp) From 5bac419828c21418c6dd061189c7779666d5c830 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:48:26 +0900 Subject: [PATCH 200/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index 8733602033f..f4446728cff 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -61,7 +61,7 @@ The thread-safe classes that are replacements for `rclcpp::WaitSet' are provided - Sample code is here: [examples/rclcpp/wait_set/src/thread_safe_wait_set.cpp at rolling · ros2/examples](https://github.com/ros2/examples/blob/rolling/rclcpp/wait_set/src/thread_safe_wait_set.cpp) - [_Typedef rclcpp::StaticWaitSet_](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1adb06acf4a5723b1445fa6ed4e8f73374.html) - Subscription, Timer, and so on can be registered to WaitSet only at initialization - - here are sample codes: + - Here are sample code: - [ros2_subscription_examples/waitset_examples/src/timer_listener_twin_static.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_twin_static.cpp) - [examples/rclcpp/wait_set/src/static_wait_set.cpp at rolling · ros2/examples](https://github.com/ros2/examples/blob/rolling/rclcpp/wait_set/src/static_wait_set.cpp) From d16ccc70d6f41577624dc2e39b444a61448e88f9 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:49:00 +0900 Subject: [PATCH 201/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index f4446728cff..d370300d03a 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -60,7 +60,7 @@ The thread-safe classes that are replacements for `rclcpp::WaitSet' are provided - Subscription, timer, etc. can only be registered to `ThreadSafeWaitSet` only in thread-safe state - Sample code is here: [examples/rclcpp/wait_set/src/thread_safe_wait_set.cpp at rolling · ros2/examples](https://github.com/ros2/examples/blob/rolling/rclcpp/wait_set/src/thread_safe_wait_set.cpp) - [_Typedef rclcpp::StaticWaitSet_](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1adb06acf4a5723b1445fa6ed4e8f73374.html) - - Subscription, Timer, and so on can be registered to WaitSet only at initialization + - Subscription, timer, etc. can be registered to `rclcpp::StaticWaitSet` only at initialization - Here are sample code: - [ros2_subscription_examples/waitset_examples/src/timer_listener_twin_static.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_twin_static.cpp) - [examples/rclcpp/wait_set/src/static_wait_set.cpp at rolling · ros2/examples](https://github.com/ros2/examples/blob/rolling/rclcpp/wait_set/src/static_wait_set.cpp) From f93307a32f59efa019f9b80821e442473b36578a Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:49:34 +0900 Subject: [PATCH 202/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index d370300d03a..cb0fe6dda32 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -62,7 +62,7 @@ The thread-safe classes that are replacements for `rclcpp::WaitSet' are provided - [_Typedef rclcpp::StaticWaitSet_](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1adb06acf4a5723b1445fa6ed4e8f73374.html) - Subscription, timer, etc. can be registered to `rclcpp::StaticWaitSet` only at initialization - Here are sample code: - - [ros2_subscription_examples/waitset_examples/src/timer_listener_twin_static.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_twin_static.cpp) + - [_ros2_subscription_examples/waitset_examples/src/timer_listener_twin_static.cpp at main · takam5f2/ros2_subscription_examples_](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_twin_static.cpp) - [examples/rclcpp/wait_set/src/static_wait_set.cpp at rolling · ros2/examples](https://github.com/ros2/examples/blob/rolling/rclcpp/wait_set/src/static_wait_set.cpp) ### 2. Register trigger (Subscription, Timer, and so on) to `WaitSet` From 2e6a6ba2442815fa35530e668c8f0e5aeb74ec3a Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:50:09 +0900 Subject: [PATCH 203/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index cb0fe6dda32..6e91d3c3d02 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -63,7 +63,7 @@ The thread-safe classes that are replacements for `rclcpp::WaitSet' are provided - Subscription, timer, etc. can be registered to `rclcpp::StaticWaitSet` only at initialization - Here are sample code: - [_ros2_subscription_examples/waitset_examples/src/timer_listener_twin_static.cpp at main · takam5f2/ros2_subscription_examples_](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_twin_static.cpp) - - [examples/rclcpp/wait_set/src/static_wait_set.cpp at rolling · ros2/examples](https://github.com/ros2/examples/blob/rolling/rclcpp/wait_set/src/static_wait_set.cpp) + - [_examples/rclcpp/wait_set/src/static_wait_set.cpp at rolling · ros2/examples_](https://github.com/ros2/examples/blob/rolling/rclcpp/wait_set/src/static_wait_set.cpp) ### 2. Register trigger (Subscription, Timer, and so on) to `WaitSet` From e07e3077b10581d1ea89037b6d085952426f5e23 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:50:46 +0900 Subject: [PATCH 204/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index 6e91d3c3d02..0a32538617b 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -67,7 +67,7 @@ The thread-safe classes that are replacements for `rclcpp::WaitSet' are provided ### 2. Register trigger (Subscription, Timer, and so on) to `WaitSet` -You need to register a trigger to `WaitSet`. +You need to register a trigger to the `rclcpp::WaitSet` based object. Below is excerption from [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp) ```c++ From f6dfe4bdeaeca8c8efebd8b3e0d5509438a063b4 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:51:24 +0900 Subject: [PATCH 205/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index 0a32538617b..4eb4709b2b3 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -68,7 +68,7 @@ The thread-safe classes that are replacements for `rclcpp::WaitSet' are provided ### 2. Register trigger (Subscription, Timer, and so on) to `WaitSet` You need to register a trigger to the `rclcpp::WaitSet` based object. -Below is excerption from [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp) +The following is a snippet from [_ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples_](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp) ```c++ subscriptions_array_[0] = create_subscription("chatter", qos, not_executed_callback, subscription_options); From 04063eb402dec2f332ff07cf35d9e663b9ccf57b Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:51:59 +0900 Subject: [PATCH 206/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index 4eb4709b2b3..f2087b29d20 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -81,7 +81,7 @@ The following is a snippet from [_ros2_subscription_examples/waitset_examples/sr } ``` -In the code above, created subscriptions are registered to the `wait_set_` object by `add_subscription()` method. +In the code above, the `add_subscription()` method registers the created subscriptions with the `wait_set_' object. `rclcpp::WaitSet`-based object basically handles objects each of which have a corresponding callback function. Not only `Subscription` based objects, but `Timer`, `Service` or `Action` based objects can be observed by `rclcpp::WaitSet`-based object. A single `WaitSet` object accepts mixture of different types of objects. A sample code to register Timer trigger is here. From 57d34273ceb2096f78c98629e5618185694c61eb Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 14 May 2024 02:52:23 +0000 Subject: [PATCH 207/225] style(pre-commit): autofix --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index f2087b29d20..990a56df729 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -82,7 +82,7 @@ The following is a snippet from [_ros2_subscription_examples/waitset_examples/sr ``` In the code above, the `add_subscription()` method registers the created subscriptions with the `wait_set_' object. -`rclcpp::WaitSet`-based object basically handles objects each of which have a corresponding callback function. Not only `Subscription` based objects, but `Timer`, `Service` or `Action` based objects can be observed by `rclcpp::WaitSet`-based object. A single `WaitSet` object accepts mixture of different types of objects. +`rclcpp::WaitSet`-based object basically handles objects each of which have a corresponding callback function. Not only`Subscription`based objects, but`Timer`,`Service`or`Action`based objects can be observed by`rclcpp::WaitSet`-based object. A single`WaitSet` object accepts mixture of different types of objects. A sample code to register Timer trigger is here. ```c++ From 0eda179dd39d832d468ba10830dbf0f3dafec913 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:53:31 +0900 Subject: [PATCH 208/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index 990a56df729..207b8466dd5 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -83,7 +83,7 @@ The following is a snippet from [_ros2_subscription_examples/waitset_examples/sr In the code above, the `add_subscription()` method registers the created subscriptions with the `wait_set_' object. `rclcpp::WaitSet`-based object basically handles objects each of which have a corresponding callback function. Not only`Subscription`based objects, but`Timer`,`Service`or`Action`based objects can be observed by`rclcpp::WaitSet`-based object. A single`WaitSet` object accepts mixture of different types of objects. -A sample code to register Timer trigger is here. +A sample code for registering timer triggers can be found here. ```c++ wait_set_.add_timer(much_slower_timer_); From 2b2100de27c568d1fdfe695fe0ce271af4ae73bd Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:54:07 +0900 Subject: [PATCH 209/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index 207b8466dd5..ddab955d266 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -89,7 +89,7 @@ A sample code for registering timer triggers can be found here. wait_set_.add_timer(much_slower_timer_); ``` -A trigger can be registered at declaration and initialization as [https://github.com/ros2/examples/blob/rolling/rclcpp/wait_set/src/wait_set_topics_and_timer.cpp#L66](https://github.com/ros2/examples/blob/rolling/rclcpp/wait_set/src/wait_set_topics_and_timer.cpp#L66). +A trigger can be registered at declaration and initialization as described in [_wait_set_topics_and_timer.cpp from the examples_](https://github.com/ros2/examples/blob/rolling/rclcpp/wait_set/src/wait_set_topics_and_timer.cpp#L66). ### 3. Verify WaitSet result From 196ff010cb52b05c16da08bd43d3b78293b288a7 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:54:46 +0900 Subject: [PATCH 210/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index ddab955d266..15c21af36c4 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -93,7 +93,7 @@ A trigger can be registered at declaration and initialization as described in [_ ### 3. Verify WaitSet result -The data structure of testing result returned from `WaitSet` is nested. +The data structure of the test result returned from the `rclcpp::WaitSet` is nested. You can find `WaitSet` result by the following 2 steps; 1. Verify if any trigger has been invoked From 71d093a8f66003c5a26a9955c8ff044336e673ef Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:55:19 +0900 Subject: [PATCH 211/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index 15c21af36c4..df565bfa185 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -94,7 +94,7 @@ A trigger can be registered at declaration and initialization as described in [_ ### 3. Verify WaitSet result The data structure of the test result returned from the `rclcpp::WaitSet` is nested. -You can find `WaitSet` result by the following 2 steps; +You can find the `WaitSet` result by the following 2 steps; 1. Verify if any trigger has been invoked 2. Verify if a specified trigger has been invoked From f9a93333d0d906dc9a9ba1e44dc107bcc2306f07 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:55:55 +0900 Subject: [PATCH 212/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index df565bfa185..71da811686a 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -97,7 +97,7 @@ The data structure of the test result returned from the `rclcpp::WaitSet` is nes You can find the `WaitSet` result by the following 2 steps; 1. Verify if any trigger has been invoked -2. Verify if a specified trigger has been invoked +2. Verify if a specified trigger has been triggered For step 1., here is a sample code excerpted from [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp). From 5c5cab1fd119bd23311bfd2ae2443c1de2134d78 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:56:21 +0900 Subject: [PATCH 213/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index 71da811686a..0323094bab5 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -99,7 +99,7 @@ You can find the `WaitSet` result by the following 2 steps; 1. Verify if any trigger has been invoked 2. Verify if a specified trigger has been triggered -For step 1., here is a sample code excerpted from [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp). +For step 1, here is a sample code taken from [_ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples_](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp). ```c++ auto wait_result = wait_set_.wait(std::chrono::milliseconds(0)); From 2ba7162e85fcc22fe7cc23b71b79144f49aa16e8 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:56:47 +0900 Subject: [PATCH 214/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index 0323094bab5..dba1b405ed3 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -111,8 +111,8 @@ For step 1, here is a sample code taken from [_ros2_subscription_examples/waitse } ``` -In the code above, `auto wait_result = wait_set_.wait(std::chrono::milliseconds(0))` tests whether any trigger in `wait_set_` has been invoked. The argument to the `wait()` method is duration for timeout. If it is greater than 0 milliseconds or seconds, this method will wait for message reception until timeout. -If `wait_result.kind() == rclcpp::WaitResultKind::Ready` is `true`, any trigger has been invoked. +In the code above, `auto wait_result = wait_set_.wait(std::chrono::milliseconds(0))` tests if a trigger in `wait_set_' has been called. The argument to the `wait()` method is the timeout duration. If it is greater than 0 milliseconds or seconds, this method will wait for a message to be received until the timeout expires. +If `wait_result.kind() == rclcpp::WaitResultKind::Ready` is `true`, then any trigger has been invoked. For step 2., here is a sample code excerpted from [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp). From f30f5d8d98afe0c7dd2bb5e61f743781d35fef99 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:57:09 +0900 Subject: [PATCH 215/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index dba1b405ed3..0d483a9c9b9 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -114,7 +114,7 @@ For step 1, here is a sample code taken from [_ros2_subscription_examples/waitse In the code above, `auto wait_result = wait_set_.wait(std::chrono::milliseconds(0))` tests if a trigger in `wait_set_' has been called. The argument to the `wait()` method is the timeout duration. If it is greater than 0 milliseconds or seconds, this method will wait for a message to be received until the timeout expires. If `wait_result.kind() == rclcpp::WaitResultKind::Ready` is `true`, then any trigger has been invoked. -For step 2., here is a sample code excerpted from [ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp). +For step 2, here is a sample code taken from [_ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples_](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp). ```c++ for (size_t i = 0; i < subscriptions_num; i++) { From fd035aba18279a4ebcbb30fe71425be979bc5243 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 11:57:40 +0900 Subject: [PATCH 216/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index 0d483a9c9b9..2e070149498 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -126,4 +126,4 @@ For step 2, here is a sample code taken from [_ros2_subscription_examples/waitse RCLCPP_INFO(this->get_logger(), "I heard: [%s]", msg.data.c_str()); ``` -In the code above, `wait_result.get_wait_set().get_rcl_wait_set().subscriptions[i]` indicates whether each individual trigger has been invoked or not. The result is stored to `subscriptions` array. The order in `subscriptions` array is the same as the order in which triggers are registered. +In the code above, `wait_result.get_wait_set().get_rcl_wait_set().subscriptions[i]` indicates whether each individual trigger has been invoked or not. The result is stored in the `subscriptions` array. The order in the `subscriptions` array is the same as the order in which the triggers are registered. From 78609e0a83c8d7192d66f14813b48005f5163f8f Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 14 May 2024 02:58:25 +0000 Subject: [PATCH 217/225] style(pre-commit): autofix --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index 2e070149498..118d73827d3 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -111,8 +111,8 @@ For step 1, here is a sample code taken from [_ros2_subscription_examples/waitse } ``` -In the code above, `auto wait_result = wait_set_.wait(std::chrono::milliseconds(0))` tests if a trigger in `wait_set_' has been called. The argument to the `wait()` method is the timeout duration. If it is greater than 0 milliseconds or seconds, this method will wait for a message to be received until the timeout expires. -If `wait_result.kind() == rclcpp::WaitResultKind::Ready` is `true`, then any trigger has been invoked. +In the code above, `auto wait_result = wait_set_.wait(std::chrono::milliseconds(0))` tests if a trigger in `wait_set_' has been called. The argument to the`wait()`method is the timeout duration. If it is greater than 0 milliseconds or seconds, this method will wait for a message to be received until the timeout expires. +If `wait_result.kind() == rclcpp::WaitResultKind::Ready`is`true`, then any trigger has been invoked. For step 2, here is a sample code taken from [_ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples_](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp). From 08865bc38164d38575e6b0e4c89e2a935e336ae6 Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Tue, 14 May 2024 14:12:49 +0900 Subject: [PATCH 218/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Takayuki AKAMINE <38586589+takam5f2@users.noreply.github.com> --- .../ros-nodes/topic-message-handling/index.md | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 6bc5514038f..90d18d2d610 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -102,9 +102,7 @@ When `take(msg, msg_info)` is called, if the size of the subscription queue is g !!! note - You can check the presence of incoming message with the returned value of `take()` method. However, you have to take care of the destructive nature of the take() method. The `take()` method modifies the subscription queue. Also, the `take()` method is irreversible and there is no undo operation against the `take()` method. Checking the incoming message with only the `take()` method always changes the subscription queue. If you want to check without changing the subscription queue, rclcpp::WaitSet is recommended. - -Refer to [_[supplement] Use rclcpp::WaitSet_](./02-supp-wait_set.md) for more detail. + You can check the presence of incoming message with the returned value of `take()` method. However, you have to take care of the destructive nature of the take() method. The `take()` method modifies the subscription queue. Also, the `take()` method is irreversible and there is no undo operation against the `take()` method. Checking the incoming message with only the `take()` method always changes the subscription queue. If you want to check without changing the subscription queue, rclcpp::WaitSet is recommended. Refer to [_[supplement] Use rclcpp::WaitSet_](./02-supp-wait_set.md) for more detail. !!! note From 16c064bc6dcddfbb15d5904f867c6ea127c7662c Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 14 May 2024 05:13:12 +0000 Subject: [PATCH 219/225] style(pre-commit): autofix --- .../ros-nodes/topic-message-handling/02-supp-wait_set.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md index 118d73827d3..5d10bd03ea6 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md @@ -112,7 +112,7 @@ For step 1, here is a sample code taken from [_ros2_subscription_examples/waitse ``` In the code above, `auto wait_result = wait_set_.wait(std::chrono::milliseconds(0))` tests if a trigger in `wait_set_' has been called. The argument to the`wait()`method is the timeout duration. If it is greater than 0 milliseconds or seconds, this method will wait for a message to be received until the timeout expires. -If `wait_result.kind() == rclcpp::WaitResultKind::Ready`is`true`, then any trigger has been invoked. +If`wait_result.kind() == rclcpp::WaitResultKind::Ready`is`true`, then any trigger has been invoked. For step 2, here is a sample code taken from [_ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples_](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp). From 17401127b205a4230d8c5fb3cd05b0bea3b288be Mon Sep 17 00:00:00 2001 From: ohsawa1204 Date: Tue, 14 May 2024 14:58:57 +0900 Subject: [PATCH 220/225] docs(topic-message-handling): some fixes Signed-off-by: ohsawa1204 --- .../ros-nodes/topic-message-handling/.pages | 4 +-- .../ros-nodes/topic-message-handling/index.md | 14 ++++----- ...ess-comm.md => supp-intra-process-comm.md} | 0 .../{02-supp-wait_set.md => supp-wait_set.md} | 30 ++++++++++--------- 4 files changed, 25 insertions(+), 23 deletions(-) rename docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/{01-supp-intra-process-comm.md => supp-intra-process-comm.md} (100%) rename docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/{02-supp-wait_set.md => supp-wait_set.md} (78%) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/.pages b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/.pages index 69029377561..2037f34e646 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/.pages +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/.pages @@ -1,4 +1,4 @@ nav: - index.md - - 01-supp-intra-process-comm.md - - 02-supp-wait_set.md + - supp-intra-process-comm.md + - supp-wait_set.md diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 90d18d2d610..2e08dc5b3ef 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -54,8 +54,8 @@ You can see an example of the typical use of `take()` method in [_ros2_subscript #### Prevent calling a callback function To prevent a callback function from being called automatically, the callback function has to belong a callback group whose callback functions are not added to any executor. -According to the [API specification of `create_subscription`](http://docs.ros.org/en/iron/p/rclcpp/generated/classrclcpp_1_1Node.html), registering a callback function to a `rclcpp::Subscription` based object is mandatory even if the callback function has no operation. -Here is a sample code snippet from [ros2_subscription_examples/simple_examples/src/timer_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp). +According to the [_API specification of `create_subscription`_](http://docs.ros.org/en/iron/p/rclcpp/generated/classrclcpp_1_1Node.html), registering a callback function to a `rclcpp::Subscription` based object is mandatory even if the callback function has no operation. +Here is a sample code snippet from [_ros2_subscription_examples/simple_examples/src/timer_listener.cpp_](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp). ```c++ rclcpp::CallbackGroup::SharedPtr cb_group_not_executed = this->create_callback_group( @@ -85,7 +85,7 @@ When `automatically_add_to_executor_with_node` is set to `true`, callback functi #### Call `take()` method of Subscription object To take a topic message from the `Subscription` based object, the `take()` method is called at the expected time. -Here is a sample code snippet from [_ros2_subscription_examples/simple_examples/src/timer_listener.cpp_](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp) using `take()` method is used. +Here is a sample code snippet from [_ros2_subscription_examples/simple_examples/src/timer_listener.cpp_](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_listener.cpp) using `take()` method. ```c++ std_msgs::msg::String msg; @@ -102,11 +102,11 @@ When `take(msg, msg_info)` is called, if the size of the subscription queue is g !!! note - You can check the presence of incoming message with the returned value of `take()` method. However, you have to take care of the destructive nature of the take() method. The `take()` method modifies the subscription queue. Also, the `take()` method is irreversible and there is no undo operation against the `take()` method. Checking the incoming message with only the `take()` method always changes the subscription queue. If you want to check without changing the subscription queue, rclcpp::WaitSet is recommended. Refer to [_[supplement] Use rclcpp::WaitSet_](./02-supp-wait_set.md) for more detail. + You can check the presence of incoming message with the returned value of `take()` method. However, you have to take care of the destructive nature of the take() method. The `take()` method modifies the subscription queue. Also, the `take()` method is irreversible and there is no undo operation against the `take()` method. Checking the incoming message with only the `take()` method always changes the subscription queue. If you want to check without changing the subscription queue, rclcpp::WaitSet is recommended. Refer to [_[supplement] Use rclcpp::WaitSet_](./supp-wait_set.md) for more detail. !!! note - The `take()` method is supported to only obtain a message which is passed through DDS as an inter-process communication. You must not use it for an intra-process communication because intra-process communication is based on another software stack of `rclcpp`. Refer to [_[supplement] Obtain a received message through intra-process communication_](./01-supp-intra-process-comm.md) in case of intra-process communication. + The `take()` method is supported to only obtain a message which is passed through DDS as an inter-process communication. You must not use it for an intra-process communication because intra-process communication is based on another software stack of `rclcpp`. Refer to [_[supplement] Obtain a received message through intra-process communication_](./supp-intra-process-comm.md) in case of intra-process communication. #### 1.1 Obtain Serialized Message from Subscription @@ -136,7 +136,7 @@ In the code above, `msg` is created by `create_serialized_message()` to store a A subscription object can hold multiple messages in its queue if multiple queue size is configured with the QoS setting. The conventional manner using callback function forces a callback function to be executed per message. In other words, there is a constraint; a single cycle of callback function processes a single message . Note that with the conventional manner, if there are one or more messages in the subscription queue, the oldest one is taken and a thread is assigned to execute a callback function, which continues until the queue is empty. The `take()` method would alleviate this limitation. The `take()` method can be called in multiple iterations, so that a single cycle of the callback function processes multiple messages taken by `take()` methods. -Here is a sample code, taken from [ros2_subscription_examples/simple_examples/src/timer_batch_listener.cpp](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_batch_listener.cpp) which calls the `take()` method in a single cycle of a callback function. +Here is a sample code, taken from [_ros2_subscription_examples/simple_examples/src/timer_batch_listener.cpp_](https://github.com/takam5f2/ros2_subscription_examples/blob/main/simple_examples/src/timer_batch_listener.cpp) which calls the `take()` method in a single cycle of a callback function. ```c++ std_msgs::msg::String msg; @@ -168,7 +168,7 @@ Here is a sample code snippet from [_ros2_subscription_examples/simple_examples/ In the code above, a message is taken by the `take_type_erased()` method before a registered callback function is called via the `handle_message()` method. Note that you must use `take_type_erased()` instead of `take()`. `take_type_erased()` needs `void` type data as its first argument. You must use the `get()` method to convert `msg` whose type is `shared_ptr` to `void` type. Then the `handle_message()` method is called with the obtained message. A registered callback function is called within `handle_message()`. You don't need to take care of message type which is passed to `take_type_erased()` and `handle_message()`. You can define the message variable as `auto msg = sub_->create_message();`. -You can also refer to [the API document](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1SubscriptionBase.html#_CPPv4N6rclcpp16SubscriptionBase16take_type_erasedEPvRN6rclcpp11MessageInfoE) as for `create_message()`, `take_type_erased()` and `handle_message()`. +You can also refer to [_the API document_](http://docs.ros.org/en/humble/p/rclcpp/generated/classrclcpp_1_1SubscriptionBase.html#_CPPv4N6rclcpp16SubscriptionBase16take_type_erasedEPvRN6rclcpp11MessageInfoE) as for `create_message()`, `take_type_erased()` and `handle_message()`. ### 4. Obtain data by a callback function diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/supp-intra-process-comm.md similarity index 100% rename from docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/01-supp-intra-process-comm.md rename to docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/supp-intra-process-comm.md diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/supp-wait_set.md similarity index 78% rename from docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md rename to docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/supp-wait_set.md index 5d10bd03ea6..6caa8fffb5b 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/02-supp-wait_set.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/supp-wait_set.md @@ -53,17 +53,19 @@ Below is a snippet from [_ros2_subscription_examples/waitset_examples/src/timer_ rclcpp::WaitSet wait_set_; ``` -There are several types of classes similar to the `rclcpp::WaitSet`. The `rclcpp::WaitSet` object can be configured during runtime. It is not thread-safe as explained in the [_API specification of `rclcpp::WaitSet`_](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1ad6fb19c154de27e92430309d2da25ac3.html) -The thread-safe classes that are replacements for `rclcpp::WaitSet' are provided by the`rclcpp' package as listed below. - -- [_Typedef rclcpp::ThreadSafeWaitSet_](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1acaec573e71549fd3078644e18e7f7127.html) - - Subscription, timer, etc. can only be registered to `ThreadSafeWaitSet` only in thread-safe state - - Sample code is here: [examples/rclcpp/wait_set/src/thread_safe_wait_set.cpp at rolling · ros2/examples](https://github.com/ros2/examples/blob/rolling/rclcpp/wait_set/src/thread_safe_wait_set.cpp) -- [_Typedef rclcpp::StaticWaitSet_](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1adb06acf4a5723b1445fa6ed4e8f73374.html) - - Subscription, timer, etc. can be registered to `rclcpp::StaticWaitSet` only at initialization - - Here are sample code: - - [_ros2_subscription_examples/waitset_examples/src/timer_listener_twin_static.cpp at main · takam5f2/ros2_subscription_examples_](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_twin_static.cpp) - - [_examples/rclcpp/wait_set/src/static_wait_set.cpp at rolling · ros2/examples_](https://github.com/ros2/examples/blob/rolling/rclcpp/wait_set/src/static_wait_set.cpp) +??? note + + There are several types of classes similar to the `rclcpp::WaitSet`. The `rclcpp::WaitSet` object can be configured during runtime. It is not thread-safe as explained in the [_API specification of `rclcpp::WaitSet`_](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1ad6fb19c154de27e92430309d2da25ac3.html) + The thread-safe classes that are replacements for `rclcpp::WaitSet' are provided by the`rclcpp' package as listed below. + + - [_Typedef rclcpp::ThreadSafeWaitSet_](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1acaec573e71549fd3078644e18e7f7127.html) + - Subscription, timer, etc. can only be registered to `ThreadSafeWaitSet` only in thread-safe state + - Sample code is here: [examples/rclcpp/wait_set/src/thread_safe_wait_set.cpp at rolling · ros2/examples](https://github.com/ros2/examples/blob/rolling/rclcpp/wait_set/src/thread_safe_wait_set.cpp) + - [_Typedef rclcpp::StaticWaitSet_](https://docs.ros.org/en/ros2_packages/humble/api/rclcpp/generated/typedef_namespacerclcpp_1adb06acf4a5723b1445fa6ed4e8f73374.html) + - Subscription, timer, etc. can be registered to `rclcpp::StaticWaitSet` only at initialization + - Here are sample code: + - [_ros2_subscription_examples/waitset_examples/src/timer_listener_twin_static.cpp at main · takam5f2/ros2_subscription_examples_](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_twin_static.cpp) + - [_examples/rclcpp/wait_set/src/static_wait_set.cpp at rolling · ros2/examples_](https://github.com/ros2/examples/blob/rolling/rclcpp/wait_set/src/static_wait_set.cpp) ### 2. Register trigger (Subscription, Timer, and so on) to `WaitSet` @@ -81,8 +83,8 @@ The following is a snippet from [_ros2_subscription_examples/waitset_examples/sr } ``` -In the code above, the `add_subscription()` method registers the created subscriptions with the `wait_set_' object. -`rclcpp::WaitSet`-based object basically handles objects each of which have a corresponding callback function. Not only`Subscription`based objects, but`Timer`,`Service`or`Action`based objects can be observed by`rclcpp::WaitSet`-based object. A single`WaitSet` object accepts mixture of different types of objects. +In the code above, the `add_subscription()` method registers the created subscriptions with the `wait_set_` object. +A `rclcpp::WaitSet`-based object basically handles objects each of which has a corresponding callback function. Not only`Subscription`based objects, but also `Timer`,`Service`or`Action`based objects can be observed by a `rclcpp::WaitSet` based object. A single`rclcpp::WaitSet` object accepts mixture of different types of objects. A sample code for registering timer triggers can be found here. ```c++ @@ -111,7 +113,7 @@ For step 1, here is a sample code taken from [_ros2_subscription_examples/waitse } ``` -In the code above, `auto wait_result = wait_set_.wait(std::chrono::milliseconds(0))` tests if a trigger in `wait_set_' has been called. The argument to the`wait()`method is the timeout duration. If it is greater than 0 milliseconds or seconds, this method will wait for a message to be received until the timeout expires. +In the code above, `auto wait_result = wait_set_.wait(std::chrono::milliseconds(0))` tests if a trigger in `wait_set_` has been called. The argument to the`wait()`method is the timeout duration. If it is greater than 0 milliseconds or seconds, this method will wait for a message to be received until the timeout expires. If`wait_result.kind() == rclcpp::WaitResultKind::Ready`is`true`, then any trigger has been invoked. For step 2, here is a sample code taken from [_ros2_subscription_examples/waitset_examples/src/timer_listener_triple_async.cpp at main · takam5f2/ros2_subscription_examples_](https://github.com/takam5f2/ros2_subscription_examples/blob/main/waitset_examples/src/timer_listener_triple_async.cpp). From a9381c980d8e4a291d757c4b3548fec51c3a8afe Mon Sep 17 00:00:00 2001 From: ohsawa1204 <149702421+ohsawa1204@users.noreply.github.com> Date: Thu, 16 May 2024 15:02:03 +0900 Subject: [PATCH 221/225] Update docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 2e08dc5b3ef..9213741c254 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -5,7 +5,7 @@ Here is coding guideline for topic message handling in Autoware. It includes the recommended manner than conventional one, which is roughly explained in [_Discussions page_](https://github.com/orgs/autowarefoundation/discussions/4612). Refer to the page to understand the basic concept of the recommended manner. You can find sample source code in [_ros2_subscription_examples_](https://github.com/takam5f2/ros2_subscription_examples) referred from this document. -## Conventional message handling manner typically used +## Conventional message handling manner At first, let us see a conventional manner of handling messages that is commonly used. [_ROS 2 Tutorials_](https://docs.ros.org/en/rolling/Tutorials/Beginner-Client-Libraries/Writing-A-Simple-Cpp-Publisher-And-Subscriber.html#write-the-subscriber-node) is one of the most cited references for ROS 2 applications, including Autoware. From 7b98baa3ac28e8af2746395dcd1f7fb14efc98dd Mon Sep 17 00:00:00 2001 From: ohsawa1204 Date: Thu, 16 May 2024 16:21:52 +0900 Subject: [PATCH 222/225] docs(topic-message-handling): corrected as noted by mitsudome-r Signed-off-by: ohsawa1204 --- .../ros-nodes/topic-message-handling/index.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 9213741c254..070408609a1 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -198,3 +198,6 @@ Many of ROS 2 users may be afraid to use the `take()` method because they may no But `take_type_erased()` is the embodiment of `take()`, while `take()` internally calls `take_type_erased()`. If `rclcpp::Executor` based object, an executor, is programmed to call a callback function, the executor itself determines when to do it. Because the executor is essentially calling a best-effort callback function, the message is not guaranteed to be necessarily referenced or processed even though it is received. Therefore it is desirable to call the `take()` method directly to ensure that a message is referenced or processed at the intended time. + +See the following PR for an example of application to autoware.universe, if necessary. +[https://github.com/autowarefoundation/autoware.universe/pull/6702/files](https://github.com/autowarefoundation/autoware.universe/pull/6702/files) \ No newline at end of file From d42c75e67d2d69130c6b29b2c73515312037ebd0 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 16 May 2024 07:22:49 +0000 Subject: [PATCH 223/225] style(pre-commit): autofix --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 070408609a1..175eaeba9e4 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -200,4 +200,4 @@ Many of ROS 2 users may be afraid to use the `take()` method because they may no If `rclcpp::Executor` based object, an executor, is programmed to call a callback function, the executor itself determines when to do it. Because the executor is essentially calling a best-effort callback function, the message is not guaranteed to be necessarily referenced or processed even though it is received. Therefore it is desirable to call the `take()` method directly to ensure that a message is referenced or processed at the intended time. See the following PR for an example of application to autoware.universe, if necessary. -[https://github.com/autowarefoundation/autoware.universe/pull/6702/files](https://github.com/autowarefoundation/autoware.universe/pull/6702/files) \ No newline at end of file +[https://github.com/autowarefoundation/autoware.universe/pull/6702/files](https://github.com/autowarefoundation/autoware.universe/pull/6702/files) From a7bf42d674869d70940a17fd93feb74358abcedc Mon Sep 17 00:00:00 2001 From: ohsawa1204 Date: Thu, 16 May 2024 21:13:30 +0900 Subject: [PATCH 224/225] docs(topic-message-handling): minor change Signed-off-by: ohsawa1204 --- .../ros-nodes/topic-message-handling/index.md | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 175eaeba9e4..905c99c34c8 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -199,5 +199,9 @@ Many of ROS 2 users may be afraid to use the `take()` method because they may no If `rclcpp::Executor` based object, an executor, is programmed to call a callback function, the executor itself determines when to do it. Because the executor is essentially calling a best-effort callback function, the message is not guaranteed to be necessarily referenced or processed even though it is received. Therefore it is desirable to call the `take()` method directly to ensure that a message is referenced or processed at the intended time. -See the following PR for an example of application to autoware.universe, if necessary. -[https://github.com/autowarefoundation/autoware.universe/pull/6702/files](https://github.com/autowarefoundation/autoware.universe/pull/6702/files) +--- + +As of May 2024, the recommended manners are beginning to be used in Autoware Universe. +See the following PR if you want an example in Autoware Universe. + + [_feat(tier4_autoware_utils, obstacle_cruise): change to read topic by polling #6702_](https://github.com/autowarefoundation/autoware.universe/pull/6702) \ No newline at end of file From 47eaf3efdb32446f3ca198af24b8064014d8fd24 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 16 May 2024 12:14:05 +0000 Subject: [PATCH 225/225] style(pre-commit): autofix --- .../coding-guidelines/ros-nodes/topic-message-handling/index.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md index 905c99c34c8..27c651cfc05 100644 --- a/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md +++ b/docs/contributing/coding-guidelines/ros-nodes/topic-message-handling/index.md @@ -204,4 +204,4 @@ If `rclcpp::Executor` based object, an executor, is programmed to call a callbac As of May 2024, the recommended manners are beginning to be used in Autoware Universe. See the following PR if you want an example in Autoware Universe. - [_feat(tier4_autoware_utils, obstacle_cruise): change to read topic by polling #6702_](https://github.com/autowarefoundation/autoware.universe/pull/6702) \ No newline at end of file +[_feat(tier4_autoware_utils, obstacle_cruise): change to read topic by polling #6702_](https://github.com/autowarefoundation/autoware.universe/pull/6702)