Skip to content

Getting started

Prerequisite

  1. Install GLIM on your system following the installation section. Alternatively, you can also use prebuilt docker images.
  2. Download test data.
    ROS1: os1_128_01_downsampled.bag (515MB) or os1_128_01.bag (7.3GB)
    ROS2: os1_128_01_downsampled.tar.gz (426MB) or os1_128_01.tar.gz (3.2GB)

    Alternative links (Google Drive): ROS1 (downsampled, raw) ROS2 (downsampled, raw)

  3. Confirm the sensor configuration and ROS topic parameters are set as follows:

    glim/config/config.json
      "config_odometry": "config_odometry_gpu.json",
      "config_sub_mapping": "config_sub_mapping_gpu.json",
      "config_global_mapping": "config_global_mapping_gpu.json",
    glim/config/config_sensors.json
      "T_lidar_imu": [-0.006, 0.012, -0.008, 0, 0, 0, 1],
    glim/config/config_ros.json
      "imu_topic": "/os_cloud_node/imu",
      "points_topic": "/os_cloud_node/points",
    

Tip

If you want to try the CPU-based odometry estimation and global optimization, in config.json, set
"config_odometry" : "config_odometry_cpu.json",
"config_sub_mapping" : "config_sub_mapping_cpu.json",
"config_global_mapping" : "config_global_mapping_cpu.json",

Tip

If you want to try the LiDAR-only odometry estimation without IMU data, in config.json, set
"config_odometry" : "config_odometry_ct.json",
and, in config_sub_mapping_gpu.json and config_global_mapping_gpu.json, set
"enable_imu" : false

Executables

GLIM provides two ROS executables: glim_rosnode and glim_rosbag.

glim_rosnode

glim_rosnode launches GLIM as a standard ROS node that subscribes to points, imu, and image topics.

ROS1 command
# Start roscore
roscore
# Enable use_sim_time and launch GLIM as a standard ROS node on another terminal
rosparam set use_sim_time true
rosrun glim_ros glim_rosnode
# Play rosbag on yet another terminal
rosbag play --clock os1_128_01.bag
# Visualize on rviz (optional)
rviz -d glim_ros1/rviz/glim_ros.rviz
ROS2 command
ros2 run glim_ros glim_rosnode
ros2 bag play os1_128_01
rviz2 -d glim_ros2/rviz/glim_ros.rviz

glim_rosbag

glim_rosbag launches a mapping instance that directly reads data from rosbag. It automatically adjusts the playback speed while avoiding data drop to perform mapping in a minimum time.

ROS1 command
roscore
rosparam set use_sim_time true
rosrun glim_ros glim_rosbag os1_128_01.bag
ROS2 command
ros2 run glim_ros glim_rosbag os1_128_01

Configuration files

GLIM reads parameter settings from JSON files in a config root directory, which is set to glim/config by default. It first reads config.json that describes relative paths to submodule parameter files, and then reads parameters of submodules from specified configuration files. The config root directory can be changed by setting config_path ROS param when starting GLIM executables.

Note

If config_path starts with "/", the path is interpreted as an absolute path. Otherwise, config_path is interpreted as a path relative to glim directory.
realpath command is useful to run GLIM with local configuration files out of the package directory: (e.g., ros2 run glim_ros glim_rosnode --ros-args -p config_path:=$(realpath config))

Note

On ROS2, you need to run colcon build to apply changes of the configuration files in the package directory because ROS2 requires to place config files in the install directory. To avoid this, use --symlink-install option for colcon build.

Info

See Important parameters to understand parameters that should be fine-tuned.

Example

ROS1 command
# Load parameters from "glim/config/presets/gpu/config.json"
rosrun glim_ros glim_rosnode _config_path:=config/presets/gpu

# Load parameters from "/tmp/config/config.json"
rosrun glim_ros glim_rosnode _config_path:=/tmp/config

# Load parameters from "./config/config.json"
rosrun glim_ros glim_rosnode _config_path:=$(realpath ./config)
ROS2 command
# Load parameters from "glim/config/presets/gpu/config.json"
ros2 run glim_ros glim_rosnode --ros-args -p config_path:=config/presets/gpu

# Load parameters from "/tmp/config/config.json"
ros2 run glim_ros glim_rosnode --ros-args -p config_path:=/tmp/config

# Load parameters from "./config/config.json"
ros2 run glim_ros glim_rosnode --ros-args -p config_path:=$(realpath ./config)

Mapping result

The mapping result data (dump data) is saved in /tmp/dump when closing glim_rosnode or glim_rosbag. The dump data can be visualized and edited using the offline viewer (rosrun glim_ros offline_viewer).

Example dump data: dump_rosbag2_2024_04_16-14_17_01.tar.gz (trajectory errors injected for manual loop closure test)

Offline viewer (manual map editing and point cloud export)

# ROS1
rosrun glim_ros offline_viewer

# ROS2
ros2 run glim_ros offline_viewer

Open map

File -> Open Map -> Select a dump directory.

Create explicit loop constraints

  • Right click a submap sphere -> Loop begin -> Right click another submap sphere -> Loop end
  • Roughly align red and green point clouds -> Press Align to perform scan matching -> Press Create Factor if the alignment result is fine.

Create Plane-BA constraints

  • Right click a point on a flat surface -> Bundle Adjustment (Plane)
  • Adjust the sphere size so it covers sufficient points on the plane -> Create Factor

Export map point cloud (PLY format)

  • File -> Save -> Export Points

Setup your own sensor

See Sensor setup guide.