../_images/tiagopro-icon.png ../_images/kangaroo-icon.png ../_images/tiago-icon.png ../_images/ari-icon.png ../_images/talos-icon.png ../_images/mobile-bases-icon.png

Tutorial: Build and run a new ROS package#

🏁 Goal of this tutorial

By the end of this tutorial, you will know how to develop a new ROS 2 package (C++ or Python) inside a Docker image.

Note

This page document ROS 2 programming, as found in PAL OS >= 24.06. If you are interested in ROS 1 development, check the ROS 1 documentation.

Pre-requisites#

You need to be already familiar with ROS: if not, check the ROS tutorials.

In particular, you might want to check the colcon documentation, ament_cmake and ament_python if you are new to ROS 2 compilation and building tools.

Setup#

This exercise can be done both in your development computer or inside the PAL docker container. During this tutorial we will be using the environment variables representing the ROS distribution and PAL distribution.

export PAL_DISTRO=alum
export ROS_DISTRO=humble

From your local environment create a new catkin workspace:

mkdir -p ~/example_ws/src

Now, let’s source the ROS environment depending on your development environment.

source /opt/ros/${ROS_DISTRO}/setup.bash

Create a ROS package#

cd /home/user/example_ws/src/
ros2 pkg create --build-type ament_cmake --license "Apache-2.0" --dependencies rclcpp std_msgs --node-name hello_world hello_world
cd hello_world

After running the command, your terminal will return the following :

going to create a new package
package name: hello_world
destination directory: /home/user/example_ws/src
package format: 3
version: 0.0.0
description: TODO: Package description
maintainer: ['user <user@todo.todo>']
licenses: ['Apache-2.0']
build type: ament_cmake
dependencies: ['rclcpp', 'std_msgs']
node_name: hello_world
creating folder ./hello_world
creating ./hello_world/package.xml
creating source and include folder
creating folder ./hello_world/src
creating folder ./hello_world/include/hello_world
creating ./hello_world/CMakeLists.txt
creating ./hello_world/src/hello_world.cpp

Implementing the node#

Configure the package depending on your language

In ROS 2, ament_cmake is default building tool, based on cmake.

In the following file we will be using ament_cmake_auto which is not well documented but you can find information on how to use it in the source code comments. This tools allow you to reduce boilerplate in cmake files.

Edit the CMakeLists.txt file with the following content:

CMakeLists.txt#
 1cmake_minimum_required(VERSION 3.8)
 2project(hello_world)
 3
 4if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
 5  add_compile_options(-Wall -Wextra -Wpedantic)
 6endif()
 7
 8# find dependencies
 9find_package(ament_cmake_auto REQUIRED)
10ament_auto_find_build_dependencies()
11
12ament_auto_add_executable(hello_world src/hello_world.cpp)
13target_compile_features(hello_world PUBLIC c_std_99 cxx_std_17)  # Require C99 and C++17
14
15if(BUILD_TESTING)
16  find_package(ament_lint_auto REQUIRED)
17  # the following line skips the linter which checks for copyrights
18  # comment the line when a copyright and license is added to all source files
19  set(ament_cmake_copyright_FOUND TRUE)
20  # the following line skips cpplint (only works in a git repo)
21  # comment the line when this package is in a git repo and when
22  # a copyright and license is added to all source files
23  set(ament_cmake_cpplint_FOUND TRUE)
24  ament_lint_auto_find_test_dependencies()
25endif()
26
27ament_auto_package()

From there you can add your different libraries in the package.xml and ament_cmake_auto would find them if required in your code.

Edit the src/hello_world.cpp file with the following content:

hello_world_node.cpp#
 1#include "rclcpp/rclcpp.hpp"
 2#include "std_msgs/msg/string.hpp"
 3
 4using namespace std::chrono_literals;
 5
 6/* This example creates a subclass of Node and uses std::bind() to register a
 7* member function as a callback from the timer. */
 8
 9class MinimalPublisher : public rclcpp::Node
10{
11  public:
12    MinimalPublisher()
13    : Node("minimal_publisher"), count_(0)
14    {
15      publisher_ = this->create_publisher<std_msgs::msg::String>("hello", 10);
16      timer_ = this->create_wall_timer(
17      500ms, std::bind(&MinimalPublisher::timer_callback, this));
18    }
19
20  private:
21    void timer_callback()
22    {
23      auto message = std_msgs::msg::String();
24      message.data = "Hello, world! " + std::to_string(count_++);
25      RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str());
26      publisher_->publish(message);
27    }
28    rclcpp::TimerBase::SharedPtr timer_;
29    rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_;
30    size_t count_;
31};
32
33int main(int argc, char **argv) {
34  rclcpp::init(argc, argv);
35  rclcpp::spin(std::make_shared<MinimalPublisher>());
36  rclcpp::shutdown();
37  return 0;
38}

Building the package#

Warning

Make sure to use a terminal where you did not source your workspace before building as mentionned in the documentation

Build the workspace in the same way, regardless if it is a Python or C++ script.

cd ~/example_ws
colcon build

Note

In order to avoid recompiling the whole workspace everytime you can run

colcon build --packages-up-to <package-name>

The expected output is shown below:

~/example_ws$ colcon build
Starting >>> hello_world
Finished <<< hello_world [1.29s]

Summary: 1 package finished [1.82s]

Note

If after compilation you have missing includes then you might want to run

rosdep install -iy --from-path PATH_TO_YOUR_WORKSPACE/src

Running node#

In order to run the node, you first need to export the ROS_DOMAIN_ID of the robot and source the workspace. See robot-communication-ros2 for more information.

export ROS_DOMAIN_ID=<YOUR_ROBOT_DOMAIN_ID>
source install/setup.bash
ros2 run hello_world hello_world

Check if the message is correctly published by opening a new terminal or a new docker instance.

export ROS_DOMAIN_ID=<YOUR_ROBOT_DOMAIN_ID>
ros2 topic echo /hello

Next steps#