Skip to content

所有传感器的手动校准#

概述#

在本节中,我们将使用 Extrinsic Manual Calibration 用于传感器的外部校准.经过此过程,我们将无法获得用于最终使用的准确校准结果,但我们将对其他工具进行初步校准.例如,在 lidar-lidar 或 camera-lidar 校准阶段,我们需要进行初始校准,以获得准确和成功的校准结果.

我们需要一个用于校准过程的样品袋文件,其中包括原始激光雷达主题和照相机主题.下面显示了用于校准的 bag 文件示例:

??? 注意 我们校准过程的 ROS 2 Bag示例

```sh

Files:             rosbag2_2023_09_06-13_43_54_0.db3
Bag size:          18.3 GiB
Storage id:        sqlite3
Duration:          169.12s
Start:             Sep  6 2023 13:43:54.902 (1693997034.902)
End:               Sep  6 2023 13:46:43.914 (1693997203.914)
Messages:          8504
Topic information: Topic: /sensing/lidar/top/pointcloud_raw | Type: sensor_msgs/msg/PointCloud2 | Count: 1691 | Serialization Format: cdr
                   Topic: /sensing/lidar/front/pointcloud_raw | Type: sensor_msgs/msg/PointCloud2 | Count: 1691 | Serialization Format: cdr
                   Topic: /sensing/camera/camera0/image_rect | Type: sensor_msgs/msg/Image | Count: 2561 | Serialization Format: cdr
                   Topic: /sensing/camera/camera0/camera_info | Type: sensor_msgs/msg/CameraInfo | Count: 2561 | Serialization Format: cdr
```

基于手动的外部校准#

创建启动文件#

首先,我们将开始为 extrinsic_calibration_manager 包创建启动文件:

cd <YOUR-OWN-AUTOWARE-DIRECTORY>/src/autoware/calibration_tools/sensor
cd extrinsic_calibration_manager/launch
mkdir <YOUR-OWN-SENSOR-KIT-NAME> # i.e. for our guide, it will ve mkdir tutorial_vehicle_sensor_kit
cd <YOUR-OWN-SENSOR-KIT-NAME> # i.e. for our guide, it will ve cd tutorial_vehicle_sensor_kit
touch manual.launch.xml manual_sensor_kit.launch.xml manual_sensors.launch.xml

我们将修改这些 manual.launch.xml, manual_sensors.launch.xml and manual_sensor_kit.launch.xml 通过使用 TIER IV 的样品传感器套件 aip_x1 . 所以,您应该将这三个文件的内容从 aip_x1 复制到您创建的文件中.

根据您的传感器套件修改启动文件#

所以,我们可以开始修改 manual.launch.xml,请在您喜欢的文本编辑器(code、gedit 等)上打开此文件.(可选)让我们从添加 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 的文件的最终版本 (manual.launch.xml) 应如下所示:

??? 备注 教程战车的样本 manual.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"/>

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

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

</launch>

```

完成 manual.launch.xml 文件后,我们将准备好为自己的传感器模型的 sensor_kit_calibration.yaml 实现 manual_sensor_kit.launch.xml:

(可选)您还可以修改此 xml 代码段的 sensor_model 和 vehicle_id:

...
  <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>"/>
...

然后,我们将 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 有四个传感器(两个激光雷达、一个摄像头、一个 gnss/ins),所以它会像这样:

注意
+   <!-- 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,
+     camera0/camera_link,
+     gnss_link]"/>
+   </node>

最后,我们将为我们的传感器推出每帧手动校准器,请更新命名空间 (NS) 并在启动文件参数上 child_frame calibrator.launch.xml 参数:

-  <include file="$(find-pkg-share extrinsic_manual_calibrator)/launch/calibrator.launch.xml">
-    <arg name="ns" value="$(var parent_frame)/velodyne_top_base_link"/>
-    <arg name="parent_frame" value="$(var parent_frame)"/>
-    <arg name="child_frame" value="velodyne_top_base_link"/>
-  </include>
+  <!-- extrinsic_manual_calibrator -->
+  <include file="$(find-pkg-share extrinsic_manual_calibrator)/launch/calibrator.launch.xml">
+    <arg name="ns" value="$(var parent_frame)/<YOUR_SENSOR_BASE_LINK>"/>
+    <arg name="parent_frame" value="$(var parent_frame)"/>
+    <arg name="child_frame" value="<YOUR_SENSOR_BASE_LINK>""/>
+  </include>
+
+  ...
+  ...
+  ...
+  ...
+  ...
+

??? 注意 即,每个 tutorial_vehicle 的传感器套件 calibrator.launch.xml

```xml
+  <!-- extrinsic_manual_calibrator -->
+  <include file="$(find-pkg-share extrinsic_manual_calibrator)/launch/calibrator.launch.xml">
+    <arg name="ns" value="$(var parent_frame)/rs_helios_top_base_link"/>
+    <arg name="parent_frame" value="$(var parent_frame)"/>
+    <arg name="child_frame" value="rs_helios_top_base_link"/>
+  </include>
+
+  <include file="$(find-pkg-share extrinsic_manual_calibrator)/launch/calibrator.launch.xml">
+    <arg name="ns" value="$(var parent_frame)/rs_bpearl_front_base_link"/>
+    <arg name="parent_frame" value="$(var parent_frame)"/>
+    <arg name="child_frame" value="rs_bpearl_front_base_link"/>
+  </include>
+
+  <include file="$(find-pkg-share extrinsic_manual_calibrator)/launch/calibrator.launch.xml">
+    <arg name="ns" value="$(var parent_frame)/camera0/camera_link"/>
+    <arg name="parent_frame" value="$(var parent_frame)"/>
+    <arg name="child_frame" value="camera0/camera_link"/>
+  </include>
+
+  <include file="$(find-pkg-share extrinsic_manual_calibrator)/launch/calibrator.launch.xml">
+    <arg name="ns" value="$(var parent_frame)/gnss_link"/>
+    <arg name="parent_frame" value="$(var parent_frame)"/>
+    <arg name="child_frame" value="gnss_link"/>
+  </include>
+ </launch>
```

tutorial_vehicle manual_sensor_kit.launch.xml 的最终版本应如下所示:

??? 注意 tutorial_vehicle 的示例 manual_sensor_kit.launch.xml

```xml
<?xml version="1.0" encoding="UTF-8"?>
<launch>
    <arg name="vehicle_id" default="tutorial_vehicle"/> <!-- You can update with your own vehicle_id -->

    <let name="sensor_model" value="tutorial_vehicle_sensor_kit"/> <!-- You can update with your own sensor model -->
    <let name="parent_frame" value="sensor_kit_base_link"/>

    <!-- 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)"/>
        <!-- Please Update with your own sensor frames -->
        <param name="child_frames" value="
    [rs_helios_top_base_link,
    rs_bpearl_front_base_link,
    camera0/camera_link,
    gnss_link]"/>
    </node>

    <!-- extrinsic_manual_calibrator -->
    <!-- Please create a launch for all sensors that you used. -->
    <include file="$(find-pkg-share extrinsic_manual_calibrator)/launch/calibrator.launch.xml">
        <arg name="ns" value="$(var parent_frame)/rs_helios_top_base_link"/>
        <arg name="parent_frame" value="$(var parent_frame)"/>
        <arg name="child_frame" value="rs_helios_top_base_link"/>
    </include>

    <include file="$(find-pkg-share extrinsic_manual_calibrator)/launch/calibrator.launch.xml">
        <arg name="ns" value="$(var parent_frame)/rs_bpearl_front_base_link"/>
        <arg name="parent_frame" value="$(var parent_frame)"/>
        <arg name="child_frame" value="rs_bpearl_front_base_link"/>
    </include>

    <include file="$(find-pkg-share extrinsic_manual_calibrator)/launch/calibrator.launch.xml">
        <arg name="ns" value="$(var parent_frame)/camera0/camera_link"/>
        <arg name="parent_frame" value="$(var parent_frame)"/>
        <arg name="child_frame" value="camera0/camera_link"/>
    </include>

    <include file="$(find-pkg-share extrinsic_manual_calibrator)/launch/calibrator.launch.xml">
        <arg name="ns" value="$(var parent_frame)/gnss_link"/>
        <arg name="parent_frame" value="$(var parent_frame)"/>
        <arg name="child_frame" value="gnss_link"/>
    </include>
</launch>
```

您可以根据修改后的 sensors_calibration.yaml 文件更新 manual_sensors.launch.xml 文件.由于我们不会直接根据 tutorial_vehicle 中的 base_link 校准传感器,我们不会更改此文件.

使用外部手动校准器校准传感器#

完成 manual.launch.xml 并为 extrinsic_calibration_manager 包 manual_sensor_kit.launch xml 文件后,我们需要构建 package:

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

因此,我们已准备好启动和使用手动校准器:

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

对于教程车辆:

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

然后播放 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

您将向手动 rqt_reconfigure 窗口显示,我们将根据传感器的 RVIZ2 结果手动更新校准.

  • 刷新 按钮,然后按 全部展开 按钮.tutorial_vehicle 上的帧应如下所示:

forking-autoware_repository.png

  • 请在滤镜区域(即前、赫利俄斯等)中写下目标帧名称并选择 tunable_static_tf_broadcaster_node ,然后您可以在 RQT 面板上调整 tf_x、tf_y、tf_z、tf_roll、tf_pitch 和 tf_yaw 值.
  • 如果手动校正完成,您可以通过以下命令保存校准结果:
ros2 topic pub /done std_msgs/Bool "data: true"
  • 然后,您可以在 $HOME/*.yaml 中查看输出文件.

警告

在使用其他校准之前,初始校准过程可能很重要.我们将研究激光雷达-激光雷达校准 和相机-激光雷达校准.此时,很难校准两个帧完全相同的传感器,因此您应该找到 传感器之间的近似(不一定是完美的)校准对.

以下是演示 tutorial_vehicle 手动校准过程的视频: