You're reading the documentation for a development version. For the latest released version, please have a look at Jazzy.

Migrating a C++ Package Example

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 ROS rolling.

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:

$ 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:

<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
  <name>talker</name>
  <version>0.0.0</version>
  <description>talker</description>
  <maintainer email="gerkey@osrfoundation.org">Brian Gerkey</maintainer>
  <license>Apache-2.0</license>
  <buildtool_depend>catkin</buildtool_depend>
  <depend>roscpp</depend>
  <depend>std_msgs</depend>
</package>

src/talker/CMakeLists.txt:

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:

#include <sstream>
#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<std_msgs::String>("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:

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:

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:

//#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:

//#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:

//  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.

//  ros::Publisher chatter_pub = n.advertise<std_msgs::String>("chatter", 1000);
//  ros::Rate loop_rate(10);
  auto chatter_pub = node->create_publisher<std_msgs::msg::String>("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 concept overview.

The creation of the outgoing message is different in the namespace:

//  std_msgs::String msg;
  std_msgs::msg::String msg;

In place of ros::ok(), we call rclcpp::ok():

//  while (ros::ok())
  while (rclcpp::ok())

Inside the publishing loop, we access the data field as before:

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.

//    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 ..

//    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:

//    ros::spinOnce();
    rclcpp::spin_some(node);

Sleeping using the rate object is unchanged.

Putting it all together, the new talker.cpp looks like this:

#include <sstream>
// #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<std_msgs::String>("chatter", 1000);
//  ros::Rate loop_rate(10);
  auto chatter_pub = node->create_publisher<std_msgs::msg::String>("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:

<!-- delete this -->
<buildtool_depend>catkin</buildtool_depend>`

Add a new dependency on ament_cmake_ros:

<buildtool_depend>ament_cmake_ros</buildtool_depend>

ROS 2 C++ libraries use rclcpp instead of roscpp.

Delete the dependency on roscpp:

<!-- delete this -->
<depend>roscpp</depend>

Add a dependency on rclcpp:

<depend>rclcpp</depend>

Add an <export> section to tell colcon the package is an ament_cmake package instead of a catkin package.

<export>
  <build_type>ament_cmake</build_type>
</export>

Your package.xml now looks like this:

<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
  <name>talker</name>
  <version>0.0.0</version>
  <description>talker</description>
  <maintainer email="gerkey@osrfoundation.org">Brian Gerkey</maintainer>
  <license>Apache-2.0</license>
  <buildtool_depend>ament_cmake</buildtool_depend>
  <depend>rclcpp</depend>
  <depend>std_msgs</depend>
  <export>
    <build_type>ament_cmake</build_type>
  </export>
</package>

Changing the CMake code

Require a newer version of CMake so that ament_cmake functions work correctly.

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.

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.

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.

ament_package()

Make the target_link_libraries call modern CMake targets provided by rclcpp and std_msgs.

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.

target_include_directories(talker PUBLIC
   "$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
   "$<INSTALL_INTERFACE:include/${PROJECT_NAME}>")

Change the call to install() so that the talker executable is installed into a project specific directory.

install(TARGETS talker
  DESTINATION lib/${PROJECT_NAME})

The new CMakeLists.txt looks like this:

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
   "$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
   "$<INSTALL_INTERFACE:include/${PROJECT_NAME}>")
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:

. ~/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:

. ~/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 Migrating C++ Packages reference page to help you migrate your own C++ packages from ROS 1 to ROS 2.