ROS2 Guidelines

Packages

Structure

my_package
β”œβ”€β”€ config
β”‚   └── params.yml
β”œβ”€β”€ include
β”‚   β”œβ”€β”€ lib
β”‚   β”‚   └── my_library.h
β”‚   └── my_node.h
β”œβ”€β”€ launch
β”‚   └── my_launch_file.py
β”œβ”€β”€ lib
β”‚   └── my_library.cpp
β”œβ”€β”€ src
β”‚   β”œβ”€β”€ my_node.cpp
β”‚   └── node_composition.cpp
β”œβ”€β”€ CMakeLists.txt
└── package.xml

config and lib directories are only needed if you use parameters, or make a custom library.

Composition

Write your nodes as components! This means in your my_node.cpp file, you will just have your node class, and no main function. See this tutorial for more information.

You will have a node composition file (or multiple?), that should use executors to instantiate each node. See this page on executors.

Example node_composition.cpp

#include <memory>

#include "my_package/my_component.hpp"
#include "rclcpp/rclcpp.hpp"

int main(int argc, char *argv[]) 
{
  setvbuf(stdout, NULL, _IONBF, BUFSIZ); // log messages immediately instead of buffering

  rclcpp::init(argc, argv);

  rclcpp::executors::SingleThreadedExecutor exec;
  rclcpp::NodeOptions options;

  auto my_component = std::make_shared<perception::MyComponent>(options);
  exec.add_node(my_component);
  exec.spin();

  rclcpp::shutdown();

  return 0;
}

Custom Interfaces

If you create custom interfaces (messages, services, actions), you should create a separate package for them. This is due to CMake dependency issues with building messages in the same packages that uses them. There are suggested work arounds online, I havenn't been able to get any to work.

For example, if your package is called my_package, you will create another package called my_package_interfaces and use msg, srv, and action directories for your interfaces.

Parameter Files

Example

my_package:
  ros__parameters:
    props_radii: "{marker: 0.6, buoy: 0.15}"
    min_lidar_dist: 0.1
    max_lidar_dist: 29.0
    min_points_in_segment: 6
    max_radius_diff: 0.1
    lidar_fov: 90.0

Launch Files

Rules

  • You must set a log level launch argument - see example. This allows us to control the log level from the launch file, and the terminal.

  • If using parameters, you must pass them to your node from your launch file.

Basic Example

import os
from launch import LaunchDescription
from launch_ros.actions import Node
from ament_index_python import get_package_share_directory
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration

def generate_launch_description():
    config = os.path.join(
        get_package_share_directory('my_package'),
        'config',
        'params.yaml'
        )

    log_level_launch_arg = DeclareLaunchArgument(
        'log_level',
        default_value='info'
    )

    return LaunchDescription([
        log_level_launch_arg,
        Node(
            package='perception',
            executable='node_composition',
            namespace='',
            output='screen',
            parameters=[config], 
            arguments=['--ros-args', '--log-level', LaunchConfiguration('log_level')]
        ),
    ])

Nodes

  • Each node is a class. Use header files.

  • Setup subscribers and publishers in class constructor

  • Write nodes as components

  • If you have a lot of complex functions - move them to a library

  • Throttle log messages that are very frequent, or set to DEBUG.

How to get parameters to your node

See lidar_prop_detector_component.cpp for an example. //TODO ADD LINK TO FILE

We need to inherit from rclcpp and make our own node class and add these functions in, but for now you can do the following.

  1. Add to your node's header file:

  template <typename T>
  void getParam(std::string param_name, T& param, T default_value, std::string desc)
  {
    auto param_desc = rcl_interfaces::msg::ParameterDescriptor{};
    param_desc.description = desc;
    this->declare_parameter<T>(param_name, default_value, param_desc);
    this->get_parameter(param_name, param);
    std::string param_log_output = param_name + ": " + std::to_string(param);
    RCLCPP_INFO(this->get_logger(), param_log_output.c_str()); 

    return;
  }
  1. Create member variables for each parameter starting with p_.

  2. Inside your node's constructor:

Call getParam() for each param you have:

LidarPropDetector::getParam<double>("max_lidar_dist", p_max_lidar_dist_, 0.0, "Maximum accepted range of lidar readings in m");
LidarPropDetector::getParam<double>("min_lidar_dist", p_min_lidar_dist_, 0.0, "Minimum accepted range of lidar readings in m");
LidarPropDetector::getParam<int>("min_points_in_segment", p_min_points_in_segment_, 0, "Minimum accepted points in a laser_segment");
LidarPropDetector::getParam<double>("max_radius_diff", p_max_radius_diff_, 0.0, "Maximum difference between measured and expected prop radii to consider a laser_segment a prop, in m");
LidarPropDetector::getParam<double>("lidar_fov", p_lidar_fov_, 0.0, "Lidar fov in degrees");

Set up your parameter callback:

 on_set_parameters_callback_handle_ = this->add_on_set_parameters_callback(std::bind(&LidarPropDetector::param_callback, this, std::placeholders::_1));
  1. Write your parameter callback

Example:

  rcl_interfaces::msg::SetParametersResult LidarPropDetector::param_callback(const std::vector<rclcpp::Parameter> &params)
  {
    rcl_interfaces::msg::SetParametersResult result;

    if (params[0].get_name() == "min_lidar_dist") { p_min_lidar_dist_ = params[0].as_double(); }
    else if (params[0].get_name() == "max_lidar_dist") { p_max_lidar_dist_ = params[0].as_double(); }
    else if (params[0].get_name() == "min_points_in_segment") { p_min_points_in_segment_ = params[0].as_int(); }
    else if (params[0].get_name() == "max_radius_diff") { p_max_radius_diff_ = params[0].as_double(); }
    else if (params[0].get_name() == "lidar_fov") { p_lidar_fov_ = params[0].as_double(); }
    else {
      RCLCPP_ERROR(this->get_logger(), "Invalid Param");
      result.successful = false;
      return result;
    }

    result.successful = true;
    return result;
  }

Last updated