tier4/CalibrationTools

Interactive Calibrator dies after startup

FranzAlbers opened this issue · 9 comments

Hello,
first of all, thanks for releasing the CalibrationTools! We've been looking for a calibration toolbox for our research vehicle that works with Autoware/ROS2 for quite some time before these tools were released and I think this could be exactly what we were looking for.

So far, we've adapted the aip_xx1 launch files of the extrinsic_calibration_manager to our sensor setup and crafted some Lidartags. But until now, we weren't successful in calibrating our lidar and camera sensors yet. We've decided to do the interactive calibration first because it seems simpler than the tag_based calibration.

We're trying to do the interactive calibration for the sensors of our vehicle online without recording a rosbag2 before. For that, we run our sensors using an adapted version of tier4_sensing.launch and we launch an initial guess for the tf tree of our vehicle using an adapted version of tier4_vehicle.launch. We use the following command for starting the interactive calibration:

ros2 launch extrinsic_calibration_manager calibration.launch.xml mode:=interactive sensor_model:=nissan_leaf_sensor_kit vehicle_model:=nissan_leaf camera_name:=camera_front logging_simulator:=false

The interactive calibration tool displays for a really short time a camera image and dies after less than one second. During this time, it can be seen that the status is 'Waiting for Calibration' and the TF Source is set to 'Initial /tf' (but the TF Source also sometimes seems to be empty with no other modifications done).
Here's the output:

albers@leaf-pc:~$ ros2 launch extrinsic_calibration_manager calibration.launch.xml mode:=interactive sensor_model:=nissan_leaf_sensor_kit vehicle_model:=nissan_leaf camera_name:=camera_front logging_simulator:=false
[INFO] [launch]: All log files can be found below /home/albers/.ros/log/2022-10-24-13-51-11-031738-leaf-pc-54816
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [static_transform_publisher-1]: process started with pid [54824]
[INFO] [extrinsic_calibration_client-2]: process started with pid [54826]
[INFO] [extrinsic_calibration_manager-3]: process started with pid [54828]
[INFO] [interactive_calibrator-4]: process started with pid [54830]
[INFO] [camera_intrinsics_optimizer.py-5]: process started with pid [54832]
[static_transform_publisher-1] [WARN 1666612276.838619172] []: Old-style arguments are deprecated; see --help for new-style arguments (parse_args() at ./src/static_transform_broadcaster_program.cpp:258)
[static_transform_publisher-1] [INFO 1666612276.875305045] [map2base_link]: Spinning until stopped - publishing transform
[static_transform_publisher-1] translation: ('0.000000', '0.000000', '0.000000')
[static_transform_publisher-1] rotation: ('0.000000', '0.000000', '0.000000', '1.000000')
[static_transform_publisher-1] from 'map' to 'base_link' (main() at ./src/static_transform_broadcaster_program.cpp:397)
[extrinsic_calibration_manager-3] [INFO 1666612277.883119915] [sensor_kit.extrinsic_calibration_manager]: Waiting for service: camera_front/camera_link (calibrationRequestCallback() at /home/albers/autoware/src/autoware/calibration_tools/sensor/extrinsic_calibration_manager/src/extrinsic_calibration_manager_node.cpp:73)
[extrinsic_calibration_manager-3] [INFO 1666612278.852749775] [sensor_kit.extrinsic_calibration_manager]: Call service: camera_front/camera_link (calibrationRequestCallback() at /home/albers/autoware/src/autoware/calibration_tools/sensor/extrinsic_calibration_manager/src/extrinsic_calibration_manager_node.cpp:93)
[interactive_calibrator-4] QPaintDevice: Cannot destroy paint device that is being painted
[interactive_calibrator-4] QPaintDevice: Cannot destroy paint device that is being painted
[ERROR] [interactive_calibrator-4]: process has died [pid 54830, exit code -11, cmd '/home/albers/autoware/install/extrinsic_interactive_calibrator/lib/extrinsic_interactive_calibrator/interactive_calibrator --ros-args -r __node:=interactive_calibrator -r __ns:=/sensor_kit/sensor_kit_base_link/camera_front/camera_link --params-file /tmp/launch_params_04negb1a --params-file /tmp/launch_params_eb38c1w9 -r pointcloud:=/sensing/lidar/os2/points -r image:=/sensing/camera/camera_front/image_raw/compressed -r camera_info:=/sensing/camera/camera_front/camera_info -r calibration_points_input:=calibration_points'].
[extrinsic_calibration_manager-3] [INFO 1666612283.852965599] [sensor_kit.extrinsic_calibration_manager]: Waiting for responses... (calibrationRequestCallback() at /home/albers/autoware/src/autoware/calibration_tools/sensor/extrinsic_calibration_manager/src/extrinsic_calibration_manager_node.cpp:106)

The interactive_calibrator does not die if disable displaying the pointcloud before launching the initial tf tree, so apparently there seems to be something wrong with displaying the point cloud in the interactive_calibrator.
Downsampling the point cloud by a factor of 10 does not fix the issue. We use an Ouster OS2 Lidar (64 Rays*1024 points per revolution at 20 Hertz).

Without displaying the point cloud we were able to calibrate our sensors.

Hello,
Thank you for giving our tool a try !

We would be delighted to guide you through your experience with the repository and welcome any feedback.

With respect to the issue at hand, it seems the rendering is dying, which makes it a little more difficult to debug since I moved those computations to another thread.

One way to check the reason behind this is first to render using the main Qt thread and then using a breakpoint.
This can be done via:

  • Commenting this line
  • Using debugpy
  • Attaching a debuger (I usually attach the vscode debuger)

Having said that, my impression is that the initial tf (assuming it is way off the right one) triggers a bad computation (NaN or similar) which kills the program. From my side, I will attempt running the tools with several of these situations and come back to you. I neither this, nor my previous suggestion works for you, I can also try checking it with your data, if your organization is ok with that.

Thank you very much for the quick help!

I'll see what I can find out about the error with the debugger and will come back to this issue afterward.

I think the initial tf was probably not bad enough to kill the app. It was rather close to the calibrated one.
I've uploaded a screenshot showing the initial calibration and also a short bag recorded with our setup in case you want to check with our data under the following link:
https://tu-dortmund.sciebo.de/s/AlS2rqxNimoCYPR

Thank you for sharing your data.
I took a look, and the error happens due to the format of the pointcloud (we have mostly used velodyne and pandar).

As a temporary fix, in the file:

sensor/extrinsic_interactive_calibrator/extrinsic_interactive_calibrator/ros_interface.py

please modify the

points[...,0] = pc_data['x']
points[...,1] = pc_data['y']
points[...,2] = pc_data['z']
points[...,3] = pc_data['intensity'] if 'intensity' in pc_data.dtype.names \
   else np.zeros_like(pc_data['x'])

to

points[...,0] = pc_data['x']
points[...,1] = pc_data['y']
points[...,2] = pc_data['z']
points[...,3] = pc_data['intensity'] if 'intensity' in pc_data.dtype.names \
   else np.zeros_like(pc_data['x'])

points = points.reshape(-1, points.shape[-1])

The results should be as follows:

Screenshot from 2022-10-25 00-05-45

I will push a formal fix in a few days, hopefully with the launcher to make the lidartag also work.
Let me know if the hotfix works for you in the meantime !

As an additional update, I was able to run the lidartag with your lidar by writing the appropiate launch file

File: src/vendor/lidartag/launch/lidartag_ouster_os2.launch.xml

<launch>

  <arg name="pointcloud_topic" default="/pointcloud_raw" />
  <arg name="use_intensity_channel" default="true" />
  <arg name="launch_pandar_driver" default="false" />

  <include file="$(find-pkg-share lidartag)/launch/lidartag_master.launch.xml" >

    <arg name="pointcloud_topic" value="$(var pointcloud_topic)" />
    <arg name="use_intensity_channel" value="$(var use_intensity_channel)" />
    <arg name="beam_number" value="64" />

    <!-- list for marker sizes -->
    <arg name="tag_size_list" value="[0.55]" />

    <!-- Tunable for PoI clustering -->
    <arg name="nearby_factor" value="4.0" />
    <arg name="linkage_tunable" value="0.25" />

    <!-- SQRT2 / 4 ==  0.35355339059-->
    <arg name="clearance" value="0.35355339059" />

    <!-- Tunable for cluster validation -->
    <arg name="max_outlier_ratio" value="0.25" />

    <arg name="cluster_min_index" value="0" />
    <arg name="cluster_max_index" value="10000" />
    <arg name="cluster_min_points_size" value="0" />
    <arg name="cluster_max_points_size" value="10000" />
    <arg name="pcl_visualize_cluster" value="false" />

  </include>

  <include if="$(var launch_pandar_driver)" file="$(find-pkg-share pandar_pointcloud)/launch/pandar_cloud.launch.xml" >
    <arg name="override_timestamp" value="true"/>
  </include>

</launch>

*Note: I just used a rough estimate for your tag size

Thank you very much for the fix, it works like a charm!

Our next step is indeed to run the tag_based calibration. Thanks for the launch file!
In my tries so far I was able to run the lidartag packages as well, but the /lidartag/detections_array is empty, so it seems like we don't get any detections so far.
I'm on the CalibrationTools humble branch with the launch file (adapted to our pointcloud topic) being the only modifications.
Do you have any idea what I'm missing here?

Our markers have an outside edge length of 0.61m, good guess.

Hi,
Good to know that it works for you know.

The lidartag is a tricky node to debug.
In general, among the topics that you can see in the rviz profile, I would recommend you to take a look at Colored cluster and Cluster info: detail code. These show the shape of the presumed tags when they are clustered, and the detection status of each of these clusters. The meaning of these codes can be found in the types header from the lidartag package.
However, you do not need to dig that deep for an initial test, as I explain below.

Using the launch file I sent you (plus using the correct tag size), the middle and right tags are detected.

camera_lidar_calibration

Steps to reproduce:

  • Used your calibration_tools/sensor/extrinsic_calibration_manager/launch/nissan_leaf_sensor_kit/tag_based_sensor_kit.launch.xml and the provided lidartag launch file
  • Decompressed the image on my end. We are using an apriltag wrapper that requires the decompressed image (we plan to change this, but still are discussing some aspects)
  • Run the tag based calibration: ros2 launch extrinsic_calibration_manager calibration.launch.xml mode:=tag_based sensor_model:=nissan_leaf_sensor_kit vehicle_model:=nissan_leaf camera_name:=camera_front logging_simulator:=false

General comments:

  • The left tag is missing points at times, and the intensity channel is just not clear enough (this changes by vendor, so it is kind of difficult to make it work universally). For this tag, I recommend you that you adjust it so it is perpendicular to the lidar (improves the quality of the intensity).
  • In order to avoid possible problems with the background, I would recommend you put more space between the tags and the wall.
  • The data from this lidar presents some levels of noise that make it not converge with the current parameters (this again, is lidar specific, so we tune certain parameters per lidar). In this case, to test things, I would recommend setting the parameter <param name="lidartag_max_convergence_transl_dot" value="0.03" /> to 0.15 in the meantime (autoware/calibration_tools/sensor/extrinsic_tag_based_calibrator/launch/tag_calibrator.launch.xml).
  • In our experience, using 3 tags is the bare minimum for a decent calibration (assuming the intrinsics are correct). In practice we use only one tag, but move it to aroung 9~15 locations to take more samples.

Let us know how it goes !

Thank you very much for your help, for the valuable additional information, and also for pushing the fix for our lidar!
I think this really helps us to get the tag-based calibration running.

I haven't had the time to try this yet, because I'm having a few days off. But I'll definitely try it afterward!

@FranzAlbers

Seeing that the original issue has been solved I would like to close this issue. Is that ok with you?
(I will close it If we do not receive any reaction in about a week)

Sorry for the late reply. The issue is solved and can indeed be closed.

Thank you very much also for your further comments, these really helped a lot, @knzo25!