Skip to content

Commit aa8b926

Browse files
Add chain tutorial python (#219) (#225)
(cherry picked from commit b64e5ef) Signed-off-by: EsipovPA <[email protected]> Co-authored-by: Pavel Esipov <[email protected]>
1 parent 86e135c commit aa8b926

File tree

5 files changed

+399
-19
lines changed

5 files changed

+399
-19
lines changed

doc/Tutorials/Cache-Cpp.rst

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@ If you have not done so already `create a workspace <https://docs.ros.org/en/rol
1919
1. Create a Basic Node with Includes
2020
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2121

22-
Let's assume, you've already created an empty ROS package for C++.
22+
Let's assume, you've already created an empty ROS 2 package for C++.
2323
The next step is to create a new C++ file inside your package, e.g., ``cache_tutorial.cpp``, and create an example node:
2424

2525
.. code-block:: C++

doc/Tutorials/Chain-Cpp.rst

Lines changed: 7 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@ If you have not done so already `create a workspace <https://docs.ros.org/en/rol
2424
1. Create a Basic Node with Includes
2525
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2626

27-
Let's assume, you've already created an empty ROS package for C++.
27+
Let's assume, you've already created an empty ROS 2 package for C++.
2828
The next step is to create a new C++ file inside your package, e.g., ``chain_tutorial.cpp``, and write an example code:
2929

3030
.. code-block:: C++
@@ -68,10 +68,6 @@ The next step is to create a new C++ file inside your package, e.g., ``chain_tut
6868
);
6969
}
7070

71-
void counterCallback(const std_msgs::msg::String::ConstSharedPtr& _) {
72-
++counter_;
73-
}
74-
7571
size_t getCounterValue() {
7672
return counter_;
7773
}
@@ -232,10 +228,6 @@ Next we define a ``CounterFilter`` class.
232228
);
233229
}
234230

235-
void counterCallback(const std_msgs::msg::String::ConstSharedPtr& _) {
236-
++counter_;
237-
}
238-
239231
size_t getCounterValue() {
240232
return counter_;
241233
}
@@ -299,28 +291,28 @@ Now let's take a look at the ``ChainNode`` constructor
299291
chain_filter_(subscriber_filter_)
300292
{
301293
auto qos = rclcpp::QoS(10);
302-
294+
303295
subscriber_filter_.subscribe(this, TUTORIAL_TOPIC_NAME, qos);
304-
296+
305297
// Set up the chain of filters
306298
chain_filter_.addFilter(first_counter_);
307299
chain_filter_.addFilter(second_counter_);
308-
300+
309301
chain_filter_.registerCallback(
310302
std::bind(
311303
&ChainNode::chain_exit_callback,
312304
this,
313305
std::placeholders::_1
314306
)
315307
);
316-
308+
317309
publisher_ = create_publisher<std_msgs::msg::String>(TUTORIAL_TOPIC_NAME, qos);
318-
310+
319311
publisher_timer_ = this->create_wall_timer(
320312
1s,
321313
std::bind(&ChainNode::publisher_timer_callback, this)
322314
);
323-
315+
324316
query_timer_ = this->create_wall_timer(
325317
1s,
326318
std::bind(&ChainNode::query_timer_callback, this)

0 commit comments

Comments
 (0)