Replay MulRan to ROS2

This tutorial will guide you through the process of using MOLA to publish a sequence of the MulRan dataset ([KPC+20]) as ROS 2 topics, so they can be visualized in RViz, FoxGlove, or used in your own system.

Note

Users can also access to all MulRan dataset observations directly with the C++ API of mola::MulranDataset.


MOLA installation

This tutorial requires the installation of these MOLA packages: mola_demos, mola_input_mulran_dataset, mola_viz.

Following the default installation instructions is enough.


Dataset preparation

Download the MulRan dataset ([KPC+20]) from their website, and extract the files anywhere in your system such as the files layout is as expected by mola::MulranDataset.

Remember setting the environment variable MULRAN_BASE_DIR to the root directory of your dataset, for example:

export MULRAN_BASE_DIR=/home/myuser/mulran/

Launching the demo

To launch the demo, just run:

# Run the default KAIST01 sequence:
ros2 launch mola_demos ros-mulran-play.launch.py

# Or select another sequence:
ros2 launch mola_demos ros-mulran-play.launch.py  mulran_sequence:=DCC02

Under the hook

This demo comprises two main files:

  1. The MOLA system configuration file. It defines two MOLA modules: the MulRan input and the ROS2 bridge.

YAML listing

File: mulran_just_replay_to_ros2.yaml

# -----------------------------------------------------------------------------
#                        SLAM system definition for MOLA
#
# This file just replays (no SLAM) the raw data of a sequence of the Mulran dataset
# -----------------------------------------------------------------------------

modules:
  # =====================
  # MulranDataset
  # =====================
  - type: mola::MulranDataset
    name: dataset_input
    execution_rate: 20 # Hz
    #export_to_rawlog: mulran_${MULRAN_SEQ}.rawlog
    #verbosity_level: INFO
    gui_preview_sensors:
      - raw_sensor_label: lidar
        decimation: 1
        win_pos: 5 70 400 400
      - raw_sensor_label: gps
        decimation: 1
        win_pos: 5 400 400 400
      - raw_sensor_label: imu
        decimation: 10
        win_pos: 5 550 400 400
    params:
      base_dir: ${MULRAN_BASE_DIR}
      sequence: ${MULRAN_SEQ}
      time_warp_scale: 1.0
      start_paused: ${MOLA_DATASET_START_PAUSED|false}
      publish_lidar: true
      publish_ground_truth: true
      publish_imu: true
      publish_gps: true
      #lidar_to_ground_truth_1to1: false

# MOLA -> ROS 2 bridge  =====================
  - type: mola::BridgeROS2
    name: ros2_bridge
    # In OutputROS2, this execution rate (Hz) is not relevant.
    execution_rate: 20 # Hz
    #verbosity_level: INFO
    params:
      # Whenever a MOLA odometry/SLAM system publishes a new pose estimate
      # it will be forwarded to /tf as a transformation between: 
      # `reference_frame` -> `base_link_frame`
      base_link_frame: base_link
      reference_frame: map

      # If true, an nav_msgs/Odometry message will be also published
      # 
      publish_odometry_msgs_from_slam: true

      # Do not publish /tf from ground truth dataset observations:
      publish_tf_from_robot_pose_observations: false


  # =====================
  # MolaViz
  # =====================
  - name: viz
    type: mola::MolaViz
    #verbosity_level: DEBUG
    params: ~ # none
  1. The ROS 2 launch file. It invokes mola-cli and rviz2.

Launch file listing

File: ros-mulran-play.launch.py


# ROS 2 launch file

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


def generate_launch_description():
    myDir = get_package_share_directory("mola_demos")

    # args that can be set from the command line or a default will be used
    mulran_sequence_arg = DeclareLaunchArgument(
        "mulran_sequence", default_value="KAIST01")

    set_seq_env_var = SetEnvironmentVariable(
        name='MULRAN_SEQ', value=LaunchConfiguration('mulran_sequence'))

    mola_cli_node = Node(
        package='mola_launcher',
        executable='mola-cli',
        output='screen',
        arguments=[
                os.path.join(myDir, 'mola-cli-launchs', 'mulran_just_replay_to_ros2.yaml')]
    )

    rviz2_node = Node(
        package='rviz2',
        executable='rviz2',
        name='rviz2',
        arguments=[
                '-d', [os.path.join(myDir, 'rviz2', 'mulran.rviz')]]
    )

    return LaunchDescription([
        mulran_sequence_arg,
        set_seq_env_var,
        mola_cli_node,
        rviz2_node
    ])