FusionPortable V2

From Campus to Highway: A Unified Multi-Sensor Dataset for Generalized SLAM Across Diverse Platforms and Scalable Environments

News

Overview

Usage Steps

  1. Read through the overview of the FusionPortableV2 dataset: sensors, coordinate frames, and definitions of ROS topics and message.
  2. Download data from this link.
  3. Check examples of using the dataset from this link.

Sensors

Definitions of Coordinate Frame

Sensor Frame ID
3D LiDAR (Ouster OS1-128 and its internal IMU) ouster00, ouster00_imu
Left and Right Frame Camera (not vehicle-related sequeces) frame_cam00, frame_cam01
Left and Right Frame Camera (vehicle-related sequeces) vehicle_frame_cam00, vehicle_frame_cam01
Left and Right Event Camera event_cam00, event_cam01
Internal IMU of the Left and Right Event Camera event_cam00_imu, event_cam01_imu
IMU (STIM300) body_imu
INS (3DM-GQ7-GNSS/INS) 3dm_imu
Left and Right Wheel Encoder mini_hercules_wheel00, mini_hercules_wheel01
Legged Sensor of the Unitree Quadruped Robot unitree_body_imu, unitree_hip, unitree_thign, unitree_calf, unitree_foot

Explanation of ROS Topic and Message

ROS Message Type Explanation
Link
sensor_msgs/PointCloud2 A set of points is contained.
The timestamp of this message of the last point in a scan [link]
Each point is encoded with 3D coordinates (x, y, z), intensity, scanned timestamp (nanosecond), reflectivity, ring, ambient, and range
ROS PointCloud2 message
Ouster Point Definition
dvs_msgs/EventArray A set of events is contained.
Each event is encoded with pixel location (x, y), triggered timestamp (std_msgs/Time), and polarity
ROS EventArray
ROS Event
sensor_msgs/Imu ROS Imu
sensor_msgs/Image ROS Image
sensor_msgs/CompressedImage ROS CompressedImage
unitree_legged_msgs/MotorState The customized message defined by Unitree which provided motor states.
The unitree A1 has 12 motors. Details can be check at Section 1.4.1-1.4.2 of the Unitree A1 manual.
Unitree MotorState
unitree_legged_msgs/LowState The customized message defined by Unitree which provided contact states. Unitree LowState
sensor_msgs/JointState The ROS message records key information of the motor states and contact states. We have this definition of JointState:

For the ith motor (i<=12, indicating FR0, FR1, FR2, FL0, FL1, FL2, RR0, RR1, RR2, RL0, RL1, RL2):
JointState.position[i] = MotorState[i].q (motor current position [rad])
JointState.velocity[i] = MotorState[i].dq (motor current speed [rad/s])
JointState.effort[i] = MotorState[i].tauEst (current estimated output torque [N*m])

For the ith foot contact sensor (i<=4, indicating: FR_foot, FL_foot, RR_foot, RL_foot):
JointState.effort[i+12] = LowState[i].footForce

#FR0-FR2: Front-Right Hip, Front-Right Thigh, Front-Right Calf
#FL0-FL2: Front-Left Hip, Front-Left Thigh, Front-Left Calf
#RR0-RR2: Rear-Right Hip, Rear-Right Thigh, Rear-Right Calf
#RL0-RL2: Rear-Left Hip, Rear-Left Thigh, Rear-Left Calf
#FR_foot, FL_foot, RR_foot, RL_foot: Front-Right, Front-Left, Rear-Right, and Rear-Left Foot respectively
ROS JointState
Code1 and Code2 to define JointState.
sensor_msgs/Image ROS Image
nav_msgs/Odometry ROS Odometry

Various Platforms and Scenarios

Ground-Truth Devices

Third-View of Data Collection

Environment Platform Preview
Escalator
Handheld
Corridor Handheld
Underground Parking Lot Legged Robot
Campus UGV
Outdoor Parking Lot UGV

Dataset Details and Download

Click the below button for downloading the dataset

Sensor Calibration Tutorial

Click the below button for the tutorials of sensor calibration

Experiments

Click the below button for checking experimental results

Tools

The development tool can be used by clicking the button below

Known Issues

We have listed some knowns issues in our dataset:

  1. Some dynamic objects exist and not removed from the ground-truth maps. If you want the ``clear'' map for experiments, I recommend you to try the maps in FusionPortable first.

If you have any other issues, please report them on the repository:

FusionPortable-release works were used in the following papers. Please checkout these workds if you are interested. (Please contact us if you would like your work mentioned here).

Publications

  1. FusionPortableV2: A Unified Multi-Sensor Dataset for Generalized SLAM Across Diverse Platforms and Scalable Environments
    Hexiang Wei*, Jianhao Jiao*, Xiangcheng Hu, Jingwen Yu, Xupeng Xie, Jin Wu, Yilong Zhu, Yuxuan Liu, etc.
    Under Review
    [Arxiv]

Contact