Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion doc/Tutorials/Cache-Cpp.rst
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ If you have not done so already `create a workspace <https://docs.ros.org/en/rol
1. Create a Basic Node with Includes
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~

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

.. code-block:: C++
Expand Down
22 changes: 7 additions & 15 deletions doc/Tutorials/Chain-Cpp.rst
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ If you have not done so already `create a workspace <https://docs.ros.org/en/rol
1. Create a Basic Node with Includes
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~

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

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

void counterCallback(const std_msgs::msg::String::ConstSharedPtr& _) {
++counter_;
}

size_t getCounterValue() {
return counter_;
}
Expand Down Expand Up @@ -232,10 +228,6 @@ Next we define a ``CounterFilter`` class.
);
}

void counterCallback(const std_msgs::msg::String::ConstSharedPtr& _) {
++counter_;
}

size_t getCounterValue() {
return counter_;
}
Expand Down Expand Up @@ -299,28 +291,28 @@ Now let's take a look at the ``ChainNode`` constructor
chain_filter_(subscriber_filter_)
{
auto qos = rclcpp::QoS(10);

subscriber_filter_.subscribe(this, TUTORIAL_TOPIC_NAME, qos);

// Set up the chain of filters
chain_filter_.addFilter(first_counter_);
chain_filter_.addFilter(second_counter_);

chain_filter_.registerCallback(
std::bind(
&ChainNode::chain_exit_callback,
this,
std::placeholders::_1
)
);

publisher_ = create_publisher<std_msgs::msg::String>(TUTORIAL_TOPIC_NAME, qos);

publisher_timer_ = this->create_wall_timer(
1s,
std::bind(&ChainNode::publisher_timer_callback, this)
);

query_timer_ = this->create_wall_timer(
1s,
std::bind(&ChainNode::query_timer_callback, this)
Expand Down
Loading