Skip to content

Ground-Lidar calibration#

Overview#

Ground-Lidar Calibration method operates under the assumption that the area surrounding the vehicle can be represented as a flat surface. So, you must find as wide and flat a surface as possible for ROS 2 bag recording. The method then modifies the calibration transformation in a way that aligns the points corresponding to the ground within the point cloud with the XY plane of the base_link. This means that only the z, roll, and pitch values of the tf undergo calibration, while the remaining x, y, and yaw values must be calibrated using other methods, such as manual adjustment or mapping-based lidar-lidar calibration.

You need to apply this calibration method to each lidar separately, so our bag should contain all lidars to be calibrated.

We need a sample bag file for the ground-lidar calibration process which includes raw lidar topics.

ROS 2 Bag example of our ground-based calibration process for tutorial_vehicle
Files:             rosbag2_2023_09_05-11_23_50_0.db3
Bag size:          3.8 GiB
Storage id:        sqlite3
Duration:          112.702s
Start:             Sep  5 2023 11:23:51.105 (1693902231.105)
End:               Sep  5 2023 11:25:43.808 (1693902343.808)
Messages:          2256
Topic information: Topic: /sensing/lidar/front/pointcloud_raw | Type: sensor_msgs/msg/PointCloud2 | Count: 1128 | Serialization Format: cdr
                   Topic: /sensing/lidar/top/pointcloud_raw | Type: sensor_msgs/msg/PointCloud2 | Count: 1128 | Serialization Format: cdr

Ground-lidar calibration#

Creating launch files#

We will start with creating launch file four our own vehicle like the previous sections process:

cd <YOUR-OWN-AUTOWARE-DIRECTORY>/src/autoware/calibration_tools/sensor
cd extrinsic_calibration_manager/launch
cd <YOUR-OWN-SENSOR-KIT-NAME> # i.e. for our guide, it will ve cd tutorial_vehicle_sensor_kit which is created in manual calibration
touch ground_plane.launch.xml ground_plane_sensor_kit.launch.xml

We will be modifying these ground_plane.launch.xml and ground_plane_sensor_kit.launch.xml by using TIER IV's sample sensor kit aip_x1. So, you should copy the contents of these two files from aip_x1 to your created files.

Modifying launch files according to your sensor kit#

(Optionally) Let's start with adding vehicle_id and sensor model names: (Values are not important. These parameters will be overridden by launch arguments)

  <arg name="vehicle_id" default="default"/>

  <let name="sensor_model" value="aip_x1"/>
+ <?xml version="1.0" encoding="UTF-8"?>
+ <launch>
-   <arg name="vehicle_id" default="default"/>
+   <arg name="vehicle_id" default="<YOUR_VEHICLE_ID>"/>
+
-   <arg name="sensor_model" default="aip_x1"/>
+   <let name="sensor_model" value="<YOUR_SENSOR_KIT_NAME>"/>

The final version of the file (ground_plane.launch.xml) for tutorial_vehicle should be like this:

Sample ground_plane.launch.xml file for tutorial vehicle
<launch>
  <arg name="vehicle_id" default="tutorial_vehicle"/>
  <let name="sensor_model" value="tutorial_vehicle_sensor_kit"/>

  <group>
    <push-ros-namespace namespace="sensor_kit"/>
    <include file="$(find-pkg-share extrinsic_calibration_manager)/launch/$(var sensor_model)/ground_plane_sensor_kit.launch.xml">
      <arg name="vehicle_id" value="$(var vehicle_id)"/>
    </include>
  </group>
</launch>

After the completing of ground_plane.launch.xml file, we will be ready to implement ground_plane_sensor_kit.launch.xml for the own sensor model.

Optionally, (don't forget, these parameters will be overridden by launch arguments.) you can modify sensor_kit and vehicle_id as ground_plane.launch.xmlover this xml snippet: (You can change rviz_profile path after the saving rviz config as video which included at the end of the page)

+ <?xml version="1.0" encoding="UTF-8"?>
+ <launch>
-   <arg name="vehicle_id" default="default"/>
+   <arg name="vehicle_id" default="<YOUR_VEHICLE_ID>"/>
-   <arg name="sensor_model" default="aip_x1"/>
+   <let name="sensor_model" value="<YOUR_SENSOR_KIT_NAME>"/>
    <let name="base_frame" value="base_link"/>
    <let name="parent_frame" value="sensor_kit_base_link"/>

If you save rviz config file before for the ground-lidar calibration process:

- <let name="rviz_profile" value="$(find-pkg-share extrinsic_ground_plane_calibrator)/rviz/velodyne_top.rviz"/>
+ <let name="rviz_profile" value="$(find-pkg-share extrinsic_ground_plane_calibrator)/rviz/<YOUR-RVIZ-CONFIG>.rviz"/>

Then, we will add all our sensor frames on extrinsic_calibration_manager as child frames:

    <!-- extrinsic_calibration_manager -->
-   <node pkg="extrinsic_calibration_manager" exec="extrinsic_calibration_manager" name="extrinsic_calibration_manager" output="screen">
-     <param name="parent_frame" value="$(var parent_frame)"/>
-     <param name="child_frames" value="
-     [velodyne_top_base_link,
-     livox_front_left_base_link,
-     livox_front_center_base_link,
-     livox_front_right_base_link]"/>
-   </node>
+   <node pkg="extrinsic_calibration_manager" exec="extrinsic_calibration_manager" name="extrinsic_calibration_manager" output="screen">
+     <param name="parent_frame" value="$(var parent_frame)"/>
+     <!-- add your sensor frames here -->
+     <param name="child_frames" value="
+     [<YOUE_SENSOR_BASE_LINK>,
+     YOUE_SENSOR_BASE_LINK,
+     YOUE_SENSOR_BASE_LINK,
+     YOUE_SENSOR_BASE_LINK
+     ...]"/>
+   </node>

For tutorial_vehicle there are two lidar sensors (rs_helios_top and rs_bpearl_front), so it will be like this:

i.e extrinsic_calibration_manager child_frames for tutorial_vehicle
+   <!-- extrinsic_calibration_manager -->
+   <node pkg="extrinsic_calibration_manager" exec="extrinsic_calibration_manager" name="extrinsic_calibration_manager" output="screen">
+     <param name="parent_frame" value="$(var parent_frame)"/>
+     <!-- add your sensor frames here -->
+     <param name="child_frames" value="
+     [rs_helios_top_base_link,
+     rs_bpearl_front_base_link]"/>
+   </node>

After that we will add our lidar sensor configurations on ground-based calibrator, to do that we will add these lines our ground_plane_sensor_kit.launch.xml file:

-  <group>
-    <include file="$(find-pkg-share extrinsic_ground_plane_calibrator)/launch/calibrator.launch.xml">
-      <arg name="ns" value="$(var parent_frame)/velodyne_top_base_link"/>
-      <arg name="base_frame" value="$(var base_frame)"/>
-      <arg name="parent_frame" value="$(var parent_frame)"/>
-      <arg name="child_frame" value="velodyne_top_base_link"/>
-      <arg name="pointcloud_topic" value="/sensing/lidar/top/pointcloud_raw"/>
-    </include>
-  </group>
+  <group>
+   <include file="$(find-pkg-share extrinsic_ground_plane_calibrator)/launch/calibrator.launch.xml">
+     <arg name="ns" value="$(var parent_frame)/YOUR_SENSOR_BASE_LINK"/>
+     <arg name="base_frame" value="$(var base_frame)"/>
+     <arg name="parent_frame" value="$(var parent_frame)"/>
+     <arg name="child_frame" value="YOUR_SENSOR_BASE_LINK"/>
+     <arg name="pointcloud_topic" value="<YOUR_SENSOR_TOPIC_NAME>"/>
+   </include>
+ </group>
+  ...
+  ...
+  ...
+  ...
+  ...
+
i.e., launch calibrator.launch.xml for each tutorial_vehicle's lidar
  <!-- rs_helios_top_base_link: extrinsic_ground_plane_calibrator -->
  <group>
    <include file="$(find-pkg-share extrinsic_ground_plane_calibrator)/launch/calibrator.launch.xml">
      <arg name="ns" value="$(var parent_frame)/rs_helios_top_base_link"/>
      <arg name="base_frame" value="$(var base_frame)"/>
      <arg name="parent_frame" value="$(var parent_frame)"/>
      <arg name="child_frame" value="rs_helios_top_base_link"/>
      <arg name="pointcloud_topic" value="/sensing/lidar/top/pointcloud_raw"/>
    </include>
  </group>

  <!-- rs_bpearl_front_base_link: extrinsic_ground_plane_calibrator -->
  <group>
    <include file="$(find-pkg-share extrinsic_ground_plane_calibrator)/launch/calibrator.launch.xml">
      <arg name="ns" value="$(var parent_frame)/rs_bpearl_front_base_link"/>
      <arg name="base_frame" value="$(var base_frame)"/>
      <arg name="parent_frame" value="$(var parent_frame)"/>
      <arg name="child_frame" value="rs_bpearl_front_base_link"/>
      <arg name="pointcloud_topic" value="/sensing/lidar/front/pointcloud_raw"/>
    </include>
  </group>

  <node pkg="rviz2" exec="rviz2" name="rviz2" output="screen" args="-d $(var rviz_profile)" if="$(var calibration_rviz)"/>
</launch>

The ground_plane_sensor_kit.launch.xml launch file for tutorial_vehicle should be this:

Sample ground_plane_sensor_kit.launch.xml for tutorial_vehicle
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<arg name="vehicle_id" default="tutorial_vehicle"/>
<let name="sensor_model" value="tutorial_vehicle_sensor_kit"/>
<let name="base_frame" value="base_link"/>
<let name="parent_frame" value="sensor_kit_base_link"/>
<let name="rviz_profile" value="$(find-pkg-share extrinsic_ground_plane_calibrator)/rviz/velodyne_top.rviz"/>
<arg name="calibration_rviz" default="true"/>

  <!-- extrinsic_calibration_client -->
  <arg name="src_yaml" default="$(find-pkg-share individual_params)/config/$(var vehicle_id)/$(var sensor_model)/sensor_kit_calibration.yaml"/>
  <arg name="dst_yaml" default="$(env HOME)/sensor_kit_calibration.yaml"/>

  <node pkg="extrinsic_calibration_client" exec="extrinsic_calibration_client" name="extrinsic_calibration_client" output="screen">
    <param name="src_path" value="$(var src_yaml)"/>
    <param name="dst_path" value="$(var dst_yaml)"/>
  </node>

  <!-- extrinsic_calibration_manager -->
  <node pkg="extrinsic_calibration_manager" exec="extrinsic_calibration_manager" name="extrinsic_calibration_manager" output="screen">
    <param name="parent_frame" value="$(var parent_frame)"/>
    <param name="child_frames" value="
    [rs_helios_top_base_link,
    rs_bpearl_front_base_link]"/>
  </node>

  <!-- rs_helios_top_base_link: extrinsic_ground_plane_calibrator -->
  <group>
    <include file="$(find-pkg-share extrinsic_ground_plane_calibrator)/launch/calibrator.launch.xml">
      <arg name="ns" value="$(var parent_frame)/rs_helios_top_base_link"/>
      <arg name="base_frame" value="$(var base_frame)"/>
      <arg name="parent_frame" value="$(var parent_frame)"/>
      <arg name="child_frame" value="rs_helios_top_base_link"/>
      <arg name="pointcloud_topic" value="/sensing/lidar/top/pointcloud_raw"/>
    </include>
  </group>

  <!-- rs_bpearl_front_base_link: extrinsic_ground_plane_calibrator -->
  <group>
    <include file="$(find-pkg-share extrinsic_ground_plane_calibrator)/launch/calibrator.launch.xml">
      <arg name="ns" value="$(var parent_frame)/rs_bpearl_front_base_link"/>
      <arg name="base_frame" value="$(var base_frame)"/>
      <arg name="parent_frame" value="$(var parent_frame)"/>
      <arg name="child_frame" value="rs_bpearl_front_base_link"/>
      <arg name="pointcloud_topic" value="/sensing/lidar/front/pointcloud_raw"/>
    </include>
  </group>

  <node pkg="rviz2" exec="rviz2" name="rviz2" output="screen" args="-d $(var rviz_profile)" if="$(var calibration_rviz)"/>
</launch>

Ground plane-lidar calibration process with extrinsic ground-plane calibrator#

After completing mapping_based.launch.xml and mapping_based_sensor_kit.launch.xml launch files for own sensor kit; now we are ready to calibrate our lidars. First of all, we need to build extrinsic_calibration_manager package:

colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release --packages-select extrinsic_calibration_manager

So, we are ready to launch and use ground-based lidar-ground calibrator.

ros2 launch extrinsic_calibration_manager calibration.launch.xml mode:=ground_plane sensor_model:=<OWN-SENSOR-KIT> vehicle_model:=<OWN-VEHICLE-MODEL> vehicle_id:=<VEHICLE-ID>

For tutorial vehicle:

ros2 launch extrinsic_calibration_manager calibration.launch.xml mode:=ground_plane sensor_model:=tutorial_vehicle_sensor_kit vehicle_model:=tutorial_vehicle vehicle_id:=tutorial_vehicle

You will show the rviz2 screen with several configurations, you need to update it with your sensor information topics, sensor_frames and pointcloud_inlier_topics like the video, which included an end of the document. Also, you can save the rviz2 config on rviz directory, so you can use it later with modifying mapping_based_sensor_kit.launch.xml.

extrinsic_mapping_based_calibrator/
   └─ rviz/
+        └─ tutorial_vehicle_sensor_kit.rviz

Then play ROS 2 bag file, the calibration process will be started:

ros2 bag play <rosbag_path> --clock -l -r 0.2 \
--remap /tf:=/null/tf /tf_static:=/null/tf_static # if tf is recorded

Since the calibration process is done automatically, you can see the sensor_kit_calibration.yaml in your $HOME directory after the calibration process is complete.

Before Ground Plane - Lidar Calibration After Ground Plane - Lidar Calibration
before-ground-plane.png images/after-ground-plane.png

Here is the video for demonstrating the ground plane - lidar calibration process on tutorial_vehicle: