diff --git a/source/How-To-Guides/Migrating-from-ROS1.rst b/source/How-To-Guides/Migrating-from-ROS1.rst
index fb0adda96f..91e298d1af 100644
--- a/source/How-To-Guides/Migrating-from-ROS1.rst
+++ b/source/How-To-Guides/Migrating-from-ROS1.rst
@@ -10,6 +10,7 @@ If you are new to porting between ROS 1 and ROS 2, it is recommended to read thr
Migrating-from-ROS1/Migrating-Packages
Migrating-from-ROS1/Migrating-Package-XML
Migrating-from-ROS1/Migrating-Interfaces
+ Migrating-from-ROS1/Migrating-CPP-Package-Example
Migrating-from-ROS1/Migrating-CPP-Packages
Migrating-from-ROS1/Migrating-Python-Packages
Migrating-from-ROS1/Migrating-Launch-Files
diff --git a/source/How-To-Guides/Migrating-from-ROS1/Migrating-CPP-Package-Example.rst b/source/How-To-Guides/Migrating-from-ROS1/Migrating-CPP-Package-Example.rst
new file mode 100644
index 0000000000..68038da8e0
--- /dev/null
+++ b/source/How-To-Guides/Migrating-from-ROS1/Migrating-CPP-Package-Example.rst
@@ -0,0 +1,435 @@
+Migrating a C++ Package Example
+===============================
+
+.. contents:: Table of Contents
+ :depth: 2
+ :local:
+
+This example shows how to migrate an example C++ package from ROS 1 to ROS 2.
+
+Prerequisites
+-------------
+
+You need a working ROS 2 installation, such as :doc:`ROS {DISTRO} <../../Installation>`.
+
+The ROS 1 code
+--------------
+
+Say you have a ROS 1 package called ``talker`` that uses ``roscpp`` in one node, called ``talker``.
+This package is in a catkin workspace, located at ``~/ros1_talker``.
+
+Your ROS 1 workspace has the following directory layout:
+
+.. code-block:: bash
+
+ $ cd ~/ros1_talker
+ $ find .
+ .
+ ./src
+ ./src/talker
+ ./src/talker/package.xml
+ ./src/talker/CMakeLists.txt
+ ./src/talker/talker.cpp
+
+The files have the following content:
+
+``src/talker/package.xml``:
+
+.. code-block:: xml
+
+
+
+
+ talker
+ 0.0.0
+ talker
+ Brian Gerkey
+ Apache-2.0
+ catkin
+ roscpp
+ std_msgs
+
+
+``src/talker/CMakeLists.txt``:
+
+.. code-block:: cmake
+
+ cmake_minimum_required(VERSION 2.8.3)
+ project(talker)
+ find_package(catkin REQUIRED COMPONENTS roscpp std_msgs)
+ catkin_package()
+ include_directories(${catkin_INCLUDE_DIRS})
+ add_executable(talker talker.cpp)
+ target_link_libraries(talker ${catkin_LIBRARIES})
+ install(TARGETS talker
+ RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})
+
+``src/talker/talker.cpp``:
+
+.. code-block:: cpp
+
+ #include
+ #include "ros/ros.h"
+ #include "std_msgs/String.h"
+ int main(int argc, char **argv)
+ {
+ ros::init(argc, argv, "talker");
+ ros::NodeHandle n;
+ ros::Publisher chatter_pub = n.advertise("chatter", 1000);
+ ros::Rate loop_rate(10);
+ int count = 0;
+ std_msgs::String msg;
+ while (ros::ok())
+ {
+ std::stringstream ss;
+ ss << "hello world " << count++;
+ msg.data = ss.str();
+ ROS_INFO("%s", msg.data.c_str());
+ chatter_pub.publish(msg);
+ ros::spinOnce();
+ loop_rate.sleep();
+ }
+ return 0;
+ }
+
+Migrating to ROS 2
+------------------
+
+Let's start by creating a new workspace in which to work:
+
+.. code-block:: bash
+
+ mkdir ~/ros2_talker
+ cd ~/ros2_talker
+
+We'll copy the source tree from our ROS 1 package into that workspace, where we can modify it:
+
+.. code-block:: bash
+
+ mkdir src
+ cp -a ~/ros1_talker/src/talker src
+
+Now we'll modify the C++ code in the node.
+The ROS 2 C++ library, called ``rclcpp``, provides a different API from that
+provided by ``roscpp``.
+The concepts are very similar between the two libraries, which makes the changes
+reasonably straightforward to make.
+
+Included headers
+~~~~~~~~~~~~~~~~
+
+In place of ``ros/ros.h``, which gave us access to the ``roscpp`` library API, we
+need to include ``rclcpp/rclcpp.hpp``, which gives us access to the ``rclcpp``
+library API:
+
+.. code-block:: cpp
+
+ //#include "ros/ros.h"
+ #include "rclcpp/rclcpp.hpp"
+
+To get the ``std_msgs/String`` message definition, in place of
+``std_msgs/String.h``, we need to include ``std_msgs/msg/string.hpp``:
+
+.. code-block:: cpp
+
+ //#include "std_msgs/String.h"
+ #include "std_msgs/msg/string.hpp"
+
+Changing C++ library calls
+~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+Instead of passing the node's name to the library initialization call, we do
+the initialization, then pass the node name to the creation of the node object:
+
+.. code-block:: cpp
+
+ // ros::init(argc, argv, "talker");
+ // ros::NodeHandle n;
+ rclcpp::init(argc, argv);
+ auto node = rclcpp::Node::make_shared("talker");
+
+The creation of the publisher and rate objects looks pretty similar, with some
+changes to the names of namespace and methods.
+
+.. code-block:: cpp
+
+ // ros::Publisher chatter_pub = n.advertise("chatter", 1000);
+ // ros::Rate loop_rate(10);
+ auto chatter_pub = node->create_publisher("chatter",
+ 1000);
+ rclcpp::Rate loop_rate(10);
+
+To further control how message delivery is handled, a quality of service
+(``QoS``) profile could be passed in.
+The default profile is ``rmw_qos_profile_default``.
+For more details, see the
+`design document `__
+and :doc:`concept overview <../../Concepts/Intermediate/About-Quality-of-Service-Settings>`.
+
+The creation of the outgoing message is different in the namespace:
+
+.. code-block:: cpp
+
+ // std_msgs::String msg;
+ std_msgs::msg::String msg;
+
+In place of ``ros::ok()``, we call ``rclcpp::ok()``:
+
+.. code-block:: cpp
+
+ // while (ros::ok())
+ while (rclcpp::ok())
+
+Inside the publishing loop, we access the ``data`` field as before:
+
+.. code-block:: cpp
+
+ msg.data = ss.str();
+
+To print a console message, instead of using ``ROS_INFO()``, we use
+``RCLCPP_INFO()`` and its various cousins.
+The key difference is that ``RCLCPP_INFO()`` takes a Logger object as the first
+argument.
+
+.. code-block:: cpp
+
+ // ROS_INFO("%s", msg.data.c_str());
+ RCLCPP_INFO(node->get_logger(), "%s\n", msg.data.c_str());
+
+Change the publish call to use the ``->`` operator instead of ``.``.
+
+.. code-block:: cpp
+
+ // chatter_pub.publish(msg);
+ chatter_pub->publish(msg);
+
+Spinning (i.e., letting the communications system process any pending
+incoming/outgoing messages) is different in that the call now takes the node as
+an argument:
+
+.. code-block:: cpp
+
+ // ros::spinOnce();
+ rclcpp::spin_some(node);
+
+Sleeping using the rate object is unchanged.
+
+Putting it all together, the new ``talker.cpp`` looks like this:
+
+.. code-block:: cpp
+
+ #include
+ // #include "ros/ros.h"
+ #include "rclcpp/rclcpp.hpp"
+ // #include "std_msgs/String.h"
+ #include "std_msgs/msg/string.hpp"
+ int main(int argc, char **argv)
+ {
+ // ros::init(argc, argv, "talker");
+ // ros::NodeHandle n;
+ rclcpp::init(argc, argv);
+ auto node = rclcpp::Node::make_shared("talker");
+ // ros::Publisher chatter_pub = n.advertise("chatter", 1000);
+ // ros::Rate loop_rate(10);
+ auto chatter_pub = node->create_publisher("chatter", 1000);
+ rclcpp::Rate loop_rate(10);
+ int count = 0;
+ // std_msgs::String msg;
+ std_msgs::msg::String msg;
+ // while (ros::ok())
+ while (rclcpp::ok())
+ {
+ std::stringstream ss;
+ ss << "hello world " << count++;
+ msg.data = ss.str();
+ // ROS_INFO("%s", msg.data.c_str());
+ RCLCPP_INFO(node->get_logger(), "%s\n", msg.data.c_str());
+ // chatter_pub.publish(msg);
+ chatter_pub->publish(msg);
+ // ros::spinOnce();
+ rclcpp::spin_some(node);
+ loop_rate.sleep();
+ }
+ return 0;
+ }
+
+Change the ``package.xml``
+~~~~~~~~~~~~~~~~~~~~~~~~~~
+
+ROS 2 packages use CMake functions and macros from ``ament_cmake_ros`` instead of ``catkin``.
+Delete the dependency on ``catkin``:
+
+.. code-block::
+
+
+ catkin`
+
+Add a new dependency on ``ament_cmake_ros``:
+
+.. code-block:: xml
+
+ ament_cmake_ros
+
+ROS 2 C++ libraries use `rclcpp `__ instead of `roscpp `__.
+
+Delete the dependency on ``roscpp``:
+
+.. code-block::
+
+
+ roscpp
+
+Add a dependency on ``rclcpp``:
+
+.. code-block:: xml
+
+ rclcpp
+
+
+Add an ```` section to tell colcon the package is an ``ament_cmake`` package instead of a ``catkin`` package.
+
+.. code-block:: xml
+
+
+ ament_cmake
+
+
+Your ``package.xml`` now looks like this:
+
+.. code-block:: xml
+
+
+
+
+ talker
+ 0.0.0
+ talker
+ Brian Gerkey
+ Apache-2.0
+ ament_cmake
+ rclcpp
+ std_msgs
+
+ ament_cmake
+
+
+
+
+Changing the CMake code
+~~~~~~~~~~~~~~~~~~~~~~~
+
+Require a newer version of CMake so that ``ament_cmake`` functions work correctly.
+
+.. code-block::
+
+ cmake_minimum_required(VERSION 3.14.4)
+
+Use a newer C++ standard matching the version used by your target ROS distro in `REP 2000 `__.
+If you are using C++17, then set that version with the following snippet after the ``project(talker)`` call.
+Add extra compiler checks too because it is a good practice.
+
+.. code-block:: cmake
+
+ if(NOT CMAKE_CXX_STANDARD)
+ set(CMAKE_CXX_STANDARD 17)
+ endif()
+ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
+ add_compile_options(-Wall -Wextra -Wpedantic)
+ endif()
+
+Replace the ``find_package(catkin ...)`` call with individual calls for each dependency.
+
+.. code-block:: cmake
+
+ find_package(ament_cmake REQUIRED)
+ find_package(rclcpp REQUIRED)
+ find_package(std_msgs REQUIRED)
+
+Delete the call to ``catkin_package()``.
+Add a call to ``ament_package()`` at the bottom of the ``CMakeLists.txt``.
+
+.. code-block:: cmake
+
+ ament_package()
+
+Make the ``target_link_libraries`` call modern CMake targets provided by ``rclcpp`` and ``std_msgs``.
+
+.. code-block:: cmake
+
+ target_link_libraries(talker PUBLIC
+ rclcpp::rclcpp
+ ${std_msgs_TARGETS})
+
+Delete the call to ``include_directories()``.
+Add a call to ``target_include_directories()`` below ``add_executable(talker talker.cpp)``.
+Don't pass variables like ``rclcpp_INCLUDE_DIRS`` into ``target_include_directories()``.
+The include directories are already handled by calling ``target_link_libraries()`` with modern CMake targets.
+
+.. code-block:: cmake
+
+ target_include_directories(talker PUBLIC
+ "$"
+ "$")
+
+Change the call to ``install()`` so that the ``talker`` executable is installed into a project specific directory.
+
+.. code-block:: cmake
+
+ install(TARGETS talker
+ DESTINATION lib/${PROJECT_NAME})
+
+The new ``CMakeLists.txt`` looks like this:
+
+.. code-block:: cmake
+
+ cmake_minimum_required(VERSION 3.14.4)
+ project(talker)
+ if(NOT CMAKE_CXX_STANDARD)
+ set(CMAKE_CXX_STANDARD 17)
+ endif()
+ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
+ add_compile_options(-Wall -Wextra -Wpedantic)
+ endif()
+ find_package(ament_cmake REQUIRED)
+ find_package(rclcpp REQUIRED)
+ find_package(std_msgs REQUIRED)
+ add_executable(talker talker.cpp)
+ target_include_directories(talker PUBLIC
+ "$"
+ "$")
+ target_link_libraries(talker PUBLIC
+ rclcpp::rclcpp
+ ${std_msgs_TARGETS})
+ install(TARGETS talker
+ DESTINATION lib/${PROJECT_NAME})
+ ament_package()
+
+Building the ROS 2 code
+~~~~~~~~~~~~~~~~~~~~~~~
+
+We source an environment setup file (in this case the one generated by following
+the ROS 2 installation tutorial, which builds in ``~/ros2_ws``, then we build our
+package using ``colcon build``:
+
+.. code-block:: bash
+
+ . ~/ros2_ws/install/setup.bash
+ cd ~/ros2_talker
+ colcon build
+
+Running the ROS 2 node
+~~~~~~~~~~~~~~~~~~~~~~
+
+Because we installed the ``talker`` executable into the correct directory, after sourcing the
+setup file, from our install tree, we can invoke it by running:
+
+.. code-block:: bash
+
+ . ~/ros2_ws/install/setup.bash
+ ros2 run talker talker
+
+Conclusion
+----------
+
+You have learned how to migrate an example C++ ROS 1 package to ROS 2.
+Use the :doc:`Migrating C++ Packages reference page <./Migrating-CPP-Packages>` to help you migrate your own C++ packages from ROS 1 to ROS 2.
diff --git a/source/How-To-Guides/Migrating-from-ROS1/Migrating-CPP-Packages.rst b/source/How-To-Guides/Migrating-from-ROS1/Migrating-CPP-Packages.rst
index 8a0a076a32..94e099bed5 100644
--- a/source/How-To-Guides/Migrating-from-ROS1/Migrating-CPP-Packages.rst
+++ b/source/How-To-Guides/Migrating-from-ROS1/Migrating-CPP-Packages.rst
@@ -4,13 +4,17 @@
Contributing/Migration-Guide
The-ROS2-Project/Contributing/Migration-Guide
-Migrating C++ Packages
-======================
+Migrating C++ Packages Reference
+================================
.. contents:: Table of Contents
:depth: 2
:local:
+This page shows how to migrate parts of a C++ package from ROS 1 to ROS 2.
+If this is your first time migrating a C++ package, then read the :doc:`C++ migration example ` first.
+Afterwards, use this page as a reference while you migrate your own packages.
+
Build tool
----------
@@ -472,455 +476,3 @@ Replace:
* ``#include `` with ``#include ``
* ``boost::function`` with ``std::function``
-
-Example: Converting an existing ROS 1 package to ROS 2
-------------------------------------------------------
-
-Say you have a ROS 1 package called ``talker`` that uses ``roscpp`` in one node, called ``talker``.
-This package is in a catkin workspace, located at ``~/ros1_talker``.
-
-The ROS 1 code
-^^^^^^^^^^^^^^
-
-Your ROS 1 workspace has the following directory layout:
-
-.. code-block:: bash
-
- $ cd ~/ros1_talker
- $ find .
- .
- ./src
- ./src/talker
- ./src/talker/package.xml
- ./src/talker/CMakeLists.txt
- ./src/talker/talker.cpp
-
-The files have the following content:
-
-``src/talker/package.xml``:
-
-.. code-block:: xml
-
-
-
-
- talker
- 0.0.0
- talker
- Brian Gerkey
- Apache 2.0
- catkin
- roscpp
- std_msgs
-
-
-``src/talker/CMakeLists.txt``:
-
-.. code-block:: cmake
-
- cmake_minimum_required(VERSION 2.8.3)
- project(talker)
- find_package(catkin REQUIRED COMPONENTS roscpp std_msgs)
- catkin_package()
- include_directories(${catkin_INCLUDE_DIRS})
- add_executable(talker talker.cpp)
- target_link_libraries(talker ${catkin_LIBRARIES})
- install(TARGETS talker
- RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})
-
-``src/talker/talker.cpp``:
-
-.. code-block:: cpp
-
- #include
- #include "ros/ros.h"
- #include "std_msgs/String.h"
- int main(int argc, char **argv)
- {
- ros::init(argc, argv, "talker");
- ros::NodeHandle n;
- ros::Publisher chatter_pub = n.advertise("chatter", 1000);
- ros::Rate loop_rate(10);
- int count = 0;
- std_msgs::String msg;
- while (ros::ok())
- {
- std::stringstream ss;
- ss << "hello world " << count++;
- msg.data = ss.str();
- ROS_INFO("%s", msg.data.c_str());
- chatter_pub.publish(msg);
- ros::spinOnce();
- loop_rate.sleep();
- }
- return 0;
- }
-
-Building the ROS 1 code
-~~~~~~~~~~~~~~~~~~~~~~~
-
-We source an environment setup file (in this case for Noetic using bash), then we
-build our package using ``catkin_make install``:
-
-.. code-block:: bash
-
- . /opt/ros/noetic/setup.bash
- cd ~/ros1_talker
- catkin_make install
-
-Running the ROS 1 node
-~~~~~~~~~~~~~~~~~~~~~~
-
-If there's not already one running, we start a ``roscore``, first sourcing the
-setup file from our ``catkin`` install tree (the system setup file at
-``/opt/ros/noetic/setup.bash`` would also work here):
-
-.. code-block:: bash
-
- . ~/ros1_talker/install/setup.bash
- roscore
-
-In another shell, we run the node from the ``catkin`` install space using
-``rosrun``, again sourcing the setup file first (in this case it must be the one
-from our workspace):
-
-.. code-block:: bash
-
- . ~/ros1_talker/install/setup.bash
- rosrun talker talker
-
-Migrating to ROS 2
-^^^^^^^^^^^^^^^^^^
-
-Let's start by creating a new workspace in which to work:
-
-.. code-block:: bash
-
- mkdir ~/ros2_talker
- cd ~/ros2_talker
-
-We'll copy the source tree from our ROS 1 package into that workspace, where we can modify it:
-
-.. code-block:: bash
-
- mkdir src
- cp -a ~/ros1_talker/src/talker src
-
-Now we'll modify the C++ code in the node.
-The ROS 2 C++ library, called ``rclcpp``, provides a different API from that
-provided by ``roscpp``.
-The concepts are very similar between the two libraries, which makes the changes
-reasonably straightforward to make.
-
-Included headers
-~~~~~~~~~~~~~~~~
-
-In place of ``ros/ros.h``, which gave us access to the ``roscpp`` library API, we
-need to include ``rclcpp/rclcpp.hpp``, which gives us access to the ``rclcpp``
-library API:
-
-.. code-block:: cpp
-
- //#include "ros/ros.h"
- #include "rclcpp/rclcpp.hpp"
-
-To get the ``std_msgs/String`` message definition, in place of
-``std_msgs/String.h``, we need to include ``std_msgs/msg/string.hpp``:
-
-.. code-block:: cpp
-
- //#include "std_msgs/String.h"
- #include "std_msgs/msg/string.hpp"
-
-Changing C++ library calls
-~~~~~~~~~~~~~~~~~~~~~~~~~~
-
-Instead of passing the node's name to the library initialization call, we do
-the initialization, then pass the node name to the creation of the node object:
-
-.. code-block:: cpp
-
- // ros::init(argc, argv, "talker");
- // ros::NodeHandle n;
- rclcpp::init(argc, argv);
- auto node = rclcpp::Node::make_shared("talker");
-
-The creation of the publisher and rate objects looks pretty similar, with some
-changes to the names of namespace and methods.
-
-.. code-block:: cpp
-
- // ros::Publisher chatter_pub = n.advertise("chatter", 1000);
- // ros::Rate loop_rate(10);
- auto chatter_pub = node->create_publisher("chatter",
- 1000);
- rclcpp::Rate loop_rate(10);
-
-To further control how message delivery is handled, a quality of service
-(``QoS``) profile could be passed in.
-The default profile is ``rmw_qos_profile_default``.
-For more details, see the
-`design document `__
-and :doc:`concept overview <../../Concepts/Intermediate/About-Quality-of-Service-Settings>`.
-
-The creation of the outgoing message is different in the namespace:
-
-.. code-block:: cpp
-
- // std_msgs::String msg;
- std_msgs::msg::String msg;
-
-In place of ``ros::ok()``, we call ``rclcpp::ok()``:
-
-.. code-block:: cpp
-
- // while (ros::ok())
- while (rclcpp::ok())
-
-Inside the publishing loop, we access the ``data`` field as before:
-
-.. code-block:: cpp
-
- msg.data = ss.str();
-
-To print a console message, instead of using ``ROS_INFO()``, we use
-``RCLCPP_INFO()`` and its various cousins.
-The key difference is that ``RCLCPP_INFO()`` takes a Logger object as the first
-argument.
-
-.. code-block:: cpp
-
- // ROS_INFO("%s", msg.data.c_str());
- RCLCPP_INFO(node->get_logger(), "%s\n", msg.data.c_str());
-
-Change the publish call to use the ``->`` operator instead of ``.``.
-
-.. code-block:: cpp
-
- // chatter_pub.publish(msg);
- chatter_pub->publish(msg);
-
-Spinning (i.e., letting the communications system process any pending
-incoming/outgoing messages) is different in that the call now takes the node as
-an argument:
-
-.. code-block:: cpp
-
- // ros::spinOnce();
- rclcpp::spin_some(node);
-
-Sleeping using the rate object is unchanged.
-
-Putting it all together, the new ``talker.cpp`` looks like this:
-
-.. code-block:: cpp
-
- #include
- // #include "ros/ros.h"
- #include "rclcpp/rclcpp.hpp"
- // #include "std_msgs/String.h"
- #include "std_msgs/msg/string.hpp"
- int main(int argc, char **argv)
- {
- // ros::init(argc, argv, "talker");
- // ros::NodeHandle n;
- rclcpp::init(argc, argv);
- auto node = rclcpp::Node::make_shared("talker");
- // ros::Publisher chatter_pub = n.advertise("chatter", 1000);
- // ros::Rate loop_rate(10);
- auto chatter_pub = node->create_publisher("chatter", 1000);
- rclcpp::Rate loop_rate(10);
- int count = 0;
- // std_msgs::String msg;
- std_msgs::msg::String msg;
- // while (ros::ok())
- while (rclcpp::ok())
- {
- std::stringstream ss;
- ss << "hello world " << count++;
- msg.data = ss.str();
- // ROS_INFO("%s", msg.data.c_str());
- RCLCPP_INFO(node->get_logger(), "%s\n", msg.data.c_str());
- // chatter_pub.publish(msg);
- chatter_pub->publish(msg);
- // ros::spinOnce();
- rclcpp::spin_some(node);
- loop_rate.sleep();
- }
- return 0;
- }
-
-Change the ``package.xml``
-~~~~~~~~~~~~~~~~~~~~~~~~~~
-
-ROS 2 packages use CMake functions and macros from ``ament_cmake_ros`` instead of ``catkin``.
-Delete the dependency on ``catkin``:
-
-.. code-block::
-
-
- catkin`
-
-Add a new dependency on ``ament_cmake_ros``:
-
-.. code-block:: xml
-
- ament_cmake_ros
-
-ROS 2 C++ libraries use `rclcpp `__ instead of `roscpp `__.
-
-Delete the dependency on ``roscpp``:
-
-.. code-block::
-
-
- roscpp
-
-Add a dependency on ``rclcpp``:
-
-.. code-block:: xml
-
- rclcpp
-
-
-Add an ```` section to tell colcon the package is an ``ament_cmake`` package instead of a ``catkin`` package.
-
-.. code-block:: xml
-
-
- ament_cmake
-
-
-Your ``package.xml`` now looks like this:
-
-.. code-block:: xml
-
-
-
-
- talker
- 0.0.0
- talker
- Brian Gerkey
- Apache-2.0
- ament_cmake
- rclcpp
- std_msgs
-
- ament_cmake
-
-
-
-
-Changing the CMake code
-~~~~~~~~~~~~~~~~~~~~~~~
-
-Require a newer version of CMake so that ``ament_cmake`` functions work correctly.
-
-.. code-block::
-
- cmake_minimum_required(VERSION 3.14.4)
-
-Use a newer C++ standard matching the version used by your target ROS distro in `REP 2000 `__.
-If you are using C++17, then set that version with the following snippet after the ``project(talker)`` call.
-Add extra compiler checks too because it is a good practice.
-
-.. code-block:: cmake
-
- if(NOT CMAKE_CXX_STANDARD)
- set(CMAKE_CXX_STANDARD 17)
- endif()
- if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
- add_compile_options(-Wall -Wextra -Wpedantic)
- endif()
-
-Replace the ``find_package(catkin ...)`` call with individual calls for each dependency.
-
-.. code-block:: cmake
-
- find_package(ament_cmake REQUIRED)
- find_package(rclcpp REQUIRED)
- find_package(std_msgs REQUIRED)
-
-Delete the call to ``catkin_package()``.
-Add a call to ``ament_package()`` at the bottom of the ``CMakeLists.txt``.
-
-.. code-block:: cmake
-
- ament_package()
-
-Make the ``target_link_libraries`` call modern CMake targets provided by ``rclcpp`` and ``std_msgs``.
-
-.. code-block:: cmake
-
- target_link_libraries(talker PUBLIC
- rclcpp::rclcpp
- ${std_msgs_TARGETS})
-
-Delete the call to ``include_directories()``.
-Add a call to ``target_include_directories()`` below ``add_executable(talker talker.cpp)``.
-Don't pass variables like ``rclcpp_INCLUDE_DIRS`` into ``target_include_directories()``.
-The include directories are already handled by calling ``target_link_libraries()`` with modern CMake targets.
-
-.. code-block:: cmake
-
- target_include_directories(talker PUBLIC
- "$"
- "$")
-
-Change the call to ``install()`` so that the ``talker`` executable is installed into a project specific directory.
-
-.. code-block:: cmake
-
- install(TARGETS talker
- DESTINATION lib/${PROJECT_NAME})
-
-The new ``CMakeLists.txt`` looks like this:
-
-.. code-block:: cmake
-
- cmake_minimum_required(VERSION 3.14.4)
- project(talker)
- if(NOT CMAKE_CXX_STANDARD)
- set(CMAKE_CXX_STANDARD 17)
- endif()
- if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
- add_compile_options(-Wall -Wextra -Wpedantic)
- endif()
- find_package(ament_cmake REQUIRED)
- find_package(rclcpp REQUIRED)
- find_package(std_msgs REQUIRED)
- add_executable(talker talker.cpp)
- target_include_directories(talker PUBLIC
- "$"
- "$")
- target_link_libraries(talker PUBLIC
- rclcpp::rclcpp
- ${std_msgs_TARGETS})
- install(TARGETS talker
- DESTINATION lib/${PROJECT_NAME})
- ament_package()
-
-Building the ROS 2 code
-~~~~~~~~~~~~~~~~~~~~~~~
-
-We source an environment setup file (in this case the one generated by following
-the ROS 2 installation tutorial, which builds in ``~/ros2_ws``, then we build our
-package using ``colcon build``:
-
-.. code-block:: bash
-
- . ~/ros2_ws/install/setup.bash
- cd ~/ros2_talker
- colcon build
-
-Running the ROS 2 node
-~~~~~~~~~~~~~~~~~~~~~~
-
-Because we installed the ``talker`` executable into the correct directory, after sourcing the
-setup file, from our install tree, we can invoke it by running:
-
-.. code-block:: bash
-
- . ~/ros2_ws/install/setup.bash
- ros2 run talker talker