Skip to content


ardupilot  None  ros2  dds  micro ros  xrce  lua  sitl  scripts  plugin  gazebo  garden  SITL  debug  mavlink  gimbal  rangefinder  pymavlink  mavros  distance sensor  system_time  timesync  ardurover  script  cheat sheet  wireshark  mavproxy  mission planner  pixhawk  cpp  index  cmake  gtest  ctest  demo  101  variables  cpack  deb  package  dpkg  eigen  linear algebra  c++  format  fmt  smart pointers  data structure  map  container  multithreading  spdlog  cyclonedds  eprosima  fastdds  aptly  apt  repository  repo  local  mirror  encryption  pgp  docker  arm  qemu  state  networking  network  template  python  app  devcontainer  gui  tutorial  tips  volume  mount  compose  multi-stage  stage  docker compose  microsoft  dotnet  .net  c#  vscode  git  branch  tag  bundle  backup  hooks  pre-commit  submodules  marpit  presentation  marp  markdown  mermaid  mkdocs  video  ffmpeg  gstreamer  cheat-sheet  sdp  nvidia  opencv  appsrc  appsink  acceleration  va-api  intel  v4l2loopback  pipe  compositor  alpha  shmsink  shmsrc  intersink  intersrc  tee  queue  udp  stream  klv  misb  mpeg-ts  gst  mpeg  metadata  binding  gi  kml  geo  gis  spatial  gdal  ogr  raster  vector  qgc  qgroundcontrol  snippets  cheat Sheet  asyncio  event  future  thread  task  can  canbus  click  cli  cupy  numpy  gpu  dataclass  slots  dev container  fastapi  rest  uvicorn  debian  setup  stdeb  project  jupyter  widgets  interactive  plot  matplotlib  ipywidgets  3d  subplot  open3d  point cloud  packaging  pyproject  pipx  package manager  black  isort  templates  cookiecutter  docs  project document  docstrings  flake8  linter  git-hook  mypy  unittest  pytest  pylint  from a-z  fixture  scope  logging  pytest.ini  mock  parameterize  enum  flag  iterator  generator  yaml  yml  logging config  tuple  namedtuple  typing  annotation  generic  literal  protocol  self  typed dict  typevar  pyzmq  zmq  msgpack  slam  cartographer  slam_toolbox  build system  colcon  action  namespace  remap  control2  diff-drive  ignition  ros2_control  effort  velocity  gdb  mix  multi language  qos  plugins  ros  pub  sub  msg  node  time  rclcpp  parameters  zero-copy  shm  loan message  rmw  image  large message  discovery  zenoh  bridge  zenoh-plugin-ros2dds  pico  algorithm  calibration  diff  pid  dev  colcon_cd  clean  custom  bloom  rpi  core  settings  behavior  py_trees  bt  behavior_trees  blackboard  visualization  debugging  diagnostic  DiagnosticTask  rclpy  tutorials  diagnostics  math  ned  enu  coordinate  apm  rat_runtime_monitor  bag  rosbag  rosbags  tools  smach  state machine  yasmin  web  rosbridge  vue  profile  gazebo-classic  launch  spawn  model  cook  camera  sensors  gps  imu  ray  gazebo_ros_ray_sensor  lidar  ultrsonic  range  ultrasonic  gazebo classic  wrench  gazebo_ros_state  gz  sdf  world  vscode tips  gazebogz-sim-joint-position-controller-system  simulation  ros_gz_bridge  ign  xacro  diff_drive  odom  odometry  joint_state  argument  OpaqueFunction  DeclareLaunchArgument  LaunchConfiguration  tmux  tmuxp  nav  nav2  turtlebot  perception  tf  vision  cv_bridge  setup.py  name  test  goal abort  cancel goal  action client  action server  custom messages  executor  MultiThreadedExecutor  SingleThreadedExecutor  lifecycle  parameter  param  dynamic-reconfigure  get  global server  persist_parameter  service  client  package.xml  msgs  executers  rep  rqt  humble  rviz  rviz2  pose  marker  tf2  static  graphro  local_setup  rosdep  project settings  vcstool  urdf  robot_state_publisher  urdf_to_graphiz  joint  link  robotics  path planning  trajectory  speed  filters  control  kalman_filter  kalman  filter  pcl  fusing  foc  bldc  arduino  drv8313  simple foc  quaternions  euler  rotation  code  extensions  remote  cache  offline  ssh  tasks  json  schema  server  deep learning  ai  beginner  regression  reinforcement learning  q learning  gym  gymnasium  deepsort  onnx  inference  build  source  wheel  cuda  siam-mask  tracking  segmentation  yolo  ultralytics  yolov8  jetson  tensorrt  rest api  js  javascript  async  alpine.js  mqtt  nano  terabee  i2c  l6234  blink  platformio  lw20  benewake  TF03  serial  tf_mini  libs  cross-compiler  esp32  idf  esp-idf  rtos  hello world  mp6050  mpu9250  mpu6050  embedded  kconfig  semaphore  mutex  timer  adafruit  sensor  mb1202  uart  tfmini  gpio  raspberry pi  arducam  lidat  ubuntu  stm32  nucleo  mbed  blue pill  swd  library  teensy  microros  udev  rule  usb  micro python  pymakr  config  material  workshope  classic  texture  topic  gzstring  position  force  joints  loop device  rootfs  linux  rm  sudo  sudoers  nopasswd  visudo  shell  key  gpg  sign  commands  update-alternative  debconf  dpkg-show  dpkg-reconfigure  debconf-communicate  ip  ss  netstat  systemd  socat  tc  mtu  select  projects  courses to follow  matrix  graphics  2d  course  storm32  deploy  drone  quad  uav  geometric control  se3  so3  joint_states  JointState  Header  rrbot  JointTrajectory  gazebo_ros_joint_pose_trajectory  vrx  buoyancy 

ROS2 FastDDS discovery with xml profile


Objective#

  • Show ROS node normal discovery behavior
  • Unicast discovery: Set Node discovery protocol to unicast

For each ROS 2 process running on a computer, one DDS “participant” is created Each DDS participant takes up two unicast ports on the computer.

  • Discovery Unicast port: for discovery / meta-traffic
  • User Unicast port: for user traffic port

ROS2 Node demo#

  • Run Pub/Sub nodes
  • Check open ports
  • Analyze discovery data with wireshark

Domain_ID

Nodes run on domain 0

usage
ros2 run demo_nodes_cpp talker
sudo lsof -i -P -n | grep UDP | grep talker
#
talker    877967            user    9u  IPv4 72699380      0t0  UDP *:7400 
talker    877967            user   10u  IPv4 72699382      0t0  UDP *:7412 
talker    877967            user   12u  IPv4 72699383      0t0  UDP *:7413 
talker    877967            user   14u  IPv4 72699385      0t0  UDP *:60083

The Node/Participant publish multicast discovery data each 3 sec, on port 7400

Multiple node#

terminal1
ros2 run demo_nodes_cpp talker
terminal2
ros2 run demo_nodes_cpp listener

multiple node

if we run more the one node, each of them send multicast discovery data on the the domain port 7400

lsof
sudo lsof -i -P -n | grep UDP | grep 'list\|talker' 
talker    883188            user    9u  IPv4 72872989      0t0  UDP *:7400 
talker    883188            user   10u  IPv4 72872991      0t0  UDP *:7412 
talker    883188            user   12u  IPv4 72872992      0t0  UDP *:7413 
talker    883188            user   14u  IPv4 72872994      0t0  UDP *:34513 
talker    883188            user   15u  IPv4 72872995      0t0  UDP 192.168.1.221:35422 
listener  883200            user    9u  IPv4 72864737      0t0  UDP *:7400 
listener  883200            user   10u  IPv4 72864740      0t0  UDP *:7414 
listener  883200            user   12u  IPv4 72864742      0t0  UDP *:7415 
listener  883200            user   14u  IPv4 72864744      0t0  UDP *:37961 
listener  883200            user   15u  IPv4 72864745      0t0  UDP 192.168.1.221:43254 

Disabled multicast discovery#

To disabled multicast discovery data we need to use fastdds custom profile,
We set the profile by FASTRTPS_DEFAULT_PROFILES_FILE environment variable that point to the profile file

  • The profile disabled multicast discovery
  • Set Node sending discovery unicast data to it’s config peers
usage demo
export FASTRTPS_DEFAULT_PROFILES_FILE="$(pwd)/STATIC_profile.xml"
ros2 run demo_nodes_cpp talker

demo#

Run Pub/Talker#

To disabled Node/Participant we need to tale the node where to find the other peer

  • Start nodes on domain_id=0
  • Set the Publisher/Talker node participant number to 20
  • Set the Subscriber/Listener peer node participant number to 22

UNICAST_PROFILE_W.xml
<?xml version="1.0" encoding="UTF-8" ?>
<profiles xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles">
    <participant profile_name="disable_multicast" is_default_profile="true">
        <rtps>
            <participantID>20</participantID>
            <builtin>
                <metatrafficUnicastLocatorList>
                    <locator/>
                </metatrafficUnicastLocatorList>
                <initialPeersList>
                    <locator>
                        <udpv4>
                            <address>127.0.0.1</address>
                            <port>7454</port>
                        </udpv4>
                    </locator>
                </initialPeersList>
            </builtin>
        </rtps>
    </participant>
</profiles>
terminal1
source /opt/ros/humble/setup.bash
export FASTRTPS_DEFAULT_PROFILES_FILE="$(pwd)/UNICAST_PROFILE_W.xml"
ros2 run demo_nodes_cpp talker
sudo lsof -i -P -n | grep UDP | grep 'list\|talker'
talker    881133            user    9u  IPv4 72808683      0t0  UDP *:7450 
talker    881133            user   10u  IPv4 72808684      0t0  UDP *:7451 
talker    881133            user   12u  IPv4 72808686      0t0  UDP *:56018

We can see that no multicast domain is open, and the node open ports 7450, 7451 according to the domain port calculator

terminal2
source /opt/ros/humble/setup.bash
export FASTRTPS_DEFAULT_PROFILES_FILE="$(pwd)/UNICAST_PROFILE_R.xml"
ros2 run demo_nodes_cpp listener

The node send its discovery data to other peer declare at the xml profile in 3 sec interval

for know the peer not running and we got icmp port unreachable message

Running both node#

  • Both node send discovery data in 3 sec interval to each other
sudo lsof -i -P -n | grep UDP | grep 'list\|talker'
talker    881133            user    9u  IPv4 72808683      0t0  UDP *:7450 
talker    881133            user   10u  IPv4 72808684      0t0  UDP *:7451 
talker    881133            user   12u  IPv4 72808686      0t0  UDP *:56018 
talker    881133            user   13u  IPv4 72808687      0t0  UDP 192.168.1.221:42527 
listener  881878            user    9u  IPv4 72822584      0t0  UDP *:7454 
listener  881878            user   10u  IPv4 72822585      0t0  UDP *:7455 
listener  881878            user   12u  IPv4 72822587      0t0  UDP *:51421 
listener  881878            user   13u  IPv4 72822588      0t0  UDP 192.168.1.221:52642 

Profiles#

Publisher/Talker#

UNICAST_PROFILE_W.xml
<?xml version="1.0" encoding="UTF-8" ?>
<profiles xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles">
    <participant profile_name="disable_multicast" is_default_profile="true">
        <rtps>
            <participantID>20</participantID>
            <builtin>

                <metatrafficUnicastLocatorList>
                    <locator/>
                </metatrafficUnicastLocatorList>
                <initialPeersList>
                    <locator>
                        <udpv4>
                            <address>127.0.0.1</address>
                            <port>7454</port>
                        </udpv4>
                    </locator>
                </initialPeersList>
            </builtin>
        </rtps>
    </participant>
</profiles>

Subscriber/Listener#

UNICAST_PROFILE_R.xml
<?xml version="1.0" encoding="UTF-8" ?>
<profiles xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles">
    <participant profile_name="disable_multicast" is_default_profile="true">
        <rtps>
            <participantID>22</participantID>
            <builtin>
                <metatrafficUnicastLocatorList>
                    <locator/>
                </metatrafficUnicastLocatorList>
                <initialPeersList>
                    <locator>
                        <udpv4>
                            <address>127.0.0.1</address>
                            <port>7450</port>
                        </udpv4>
                    </locator>
                </initialPeersList>
            </builtin>
        </rtps>
    </participant>
</profiles>

Reference#