地面激光雷达校准#
概述#
Ground-Lidar Calibration 方法在假设 车辆周围的区域可以表示为平面. 因此,您必须找到尽可能宽和平坦的表面以进行 ROS 2 包记录. 该方法然后修改校准变换以对齐点,对应于点云内的地面与 base_link 的 XY 平面.这意味着只有 tf 的 z、roll 和 pitch 值经过校准,其余的 X、Y 和 Yaw 值必须使用其他方法进行校准, 例如 手动调整 或 基于测绘的激光雷达-激光雷达校准.
您需要将此校准方法分别应用于每个激光雷达, 所以我们的包应该包含所有要校准的激光雷达.
我们需要一个用于地面激光雷达标定过程的样本包文件 其中包括原始 LiDAR 主题.
???注: 我们用于 tutorial_vehicle 的地面校准过程的 ROS 2 Bag 示例
```sh
Files: rosbag2_2023_09_05-11_23_50_0.db3
Bag size: 3.8 GiB
Storage id: sqlite3
Duration: 112.702s i
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
```
地面激光雷达校准#
创建启动文件#
我们将从创建启动文件 4 开始,我们自己的车辆,就像前面几节一样:
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
我们将使用 TIER IV 的样品传感器套件aip_x1修改这些 ground_plane.launch.xml 和 ground_plane_sensor_kit.launch.xml .
所以,您应该将这两个文件的内容从 aip_x1 复制到您创建的文件中.
根据您的传感器套件修改启动文件#
(可选)让我们从添加 vehicle_id 和 sensor model 名称开始:(值并不重要.这些参数将被 launch 参数覆盖)
<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>"/>
tutorial_vehicle 的文件 (ground_plane.launch.xml) 的最终版本应如下所示:
???note 教程战车的样本 ground_plane.launch.xml 文件
```xml
<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>
```
完成 ground_plane.launch.xml 文件后, 我们将准备好为自己的传感器模型实现ground_plane_sensor_kit.launch.xml.
(可选)(别忘了,这些参数将被 launch 参数覆盖.
您可以在此 XML 代码段上将 sensor_kit 和 vehicle_id 修改为 ground_plane.launch.xml:
(您可以将 rviz 配置保存为 video 后更改rviz_profile路径
包含在页面末尾)
+ <?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"/>
如果之前保存了 rviz 配置文件用于地面激光雷达校准过程:
- <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"/>
然后,我们将 extrinsic_calibration_manager 上的所有传感器帧添加为子帧:
<!-- 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>
对于 tutorial_vehicle 有两个激光雷达传感器(rs_helios_top 和 rs_bpearl_front),
所以它会是这样的:
??? 注意 即 extrinsic_calibration_manager child_frames for tutorial_vehicle
```xml
+ <!-- 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>
```
之后,我们将在地面校准器上添加我们的激光雷达传感器配置, 为此,我们将以下几行添加到 ground_plane_sensor_kit.launch.xml 文件中:
- <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>
+ ...
+ ...
+ ...
+ ...
+ ...
+
??? 注意 即,为每个 tutorial_vehicle 的激光雷达发射 calibrator.launch.xml
```xml
<!-- 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>
```
tutorial_vehicle 的 ground_plane_sensor_kit.launch.xml 启动文件应为:
??? 注意 tutorial_vehicle 的示例 ground_plane_sensor_kit.launch.xml
```xml
<?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>
```
使用外部接地平面校准器的接地平面激光雷达校准过程#
完成 mapping_based.launch.xml 后, mapping_based_sensor_kit.launch.xml 自己的传感器套件的启动文件;
现在我们准备好校准我们的激光雷达了.首先,我们需要构建 extrinsic_calibration_manager 包:
colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release --packages-select extrinsic_calibration_manager
因此,我们已经准备好启动和使用地基激光雷达-地面校准器.
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>
对于教程车辆:
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
您将显示具有多个配置的 rviz2 屏幕,你需要使用您的传感器信息主题更新它,sensor_frames 和 pointcloud_inlier_topics(如视频),其中包括文件的结尾.此外,您还可以将 rviz2 配置保存在 rviz 目录下.
因此,您可以稍后使用它来修改 mapping_based_sensor_kit.launch.xml .
extrinsic_mapping_based_calibrator/
└─ rviz/
+ └─ tutorial_vehicle_sensor_kit.rviz
然后播放 ROS 2 bag 文件,开始校准过程:
ros2 bag play <rosbag_path> --clock -l -r 0.2 --remap /tf:=/null/tf /tf_static:=/null/tf_static # if tf is recorded
由于校准过程是自动完成的, 校准过程完成后,您可以在 $HOME 目录中看到 sensor_kit_calibration.yaml.
| 地平面前 - 激光雷达校准 | 接地平面后 - 激光雷达校准 |
|---|---|
![]() |
![]() |
以下是演示 tutorial_vehicle 上接地平面 - 激光雷达标定过程的视频:

