tier4 / CalibrationTools

GNU General Public License v3.0
103 stars 37 forks source link

Interactive camera-lidar calibration tool error. Image output error #178

Closed hsule closed 5 days ago

hsule commented 1 month ago

Hello, we are trying to use camera-lidar calibration tool, and the image was strange as you can see in the picture below. image

We work on this commit since extrinsic_calibration_manager in document is not written in the latest commit.

The command we executed: ros2 launch extrinsic_calibration_manager calibration.launch.xml mode:=interactive sensor_model:=sample_sensor_kit vehicle_model:=sample_vehicle vehicle_id:=default camera_name:=zedxm ros2 bag play rosbag2_2024_07_15-22_20_30/ --clock -l -r 0.2

Bag info:

Files:             rosbag2_2024_07_15-22_20_30_0.db3
Bag size:          8.0 GiB
Storage id:        sqlite3
Duration:          109.947s
Start:             Jul 15 2024 22:20:31.284 (1721053231.284)
End:               Jul 15 2024 22:22:21.232 (1721053341.232)
Messages:          2853
Topic information: Topic: /sensing/lidar/concatenated/pointcloud | Type: sensor_msgs/msg/PointCloud2 | Count: 196 | Serialization Format: cdr
                   Topic: /sensing/camera/zedxm/zed_node/rgb/image_rect_color | Type: sensor_msgs/msg/Image | Count: 920 | Serialization Format: cdr
                   Topic: /sensing/camera/zedxm/zed_node/rgb/camera_info | Type: sensor_msgs/msg/CameraInfo | Count: 1737 | Serialization Format: cdr

TF transform: image

rqt_graph: image

We added some tf transformation between base_link to sensor_kit_base_link, sensor_kit_base_link to zedxm_camera_link.

knzo25 commented 1 month ago

Hi @hsule Thank you for using our tools. The phenomena with the image seems to be an encoding issue. If the projection looks weird, it could be a intrinsics/extrinsics issue. To provide more help we would need to take a look at the data itself (a few seconds of data would suffice)

hsule commented 1 month ago

Hello @knzo25 ,

Thank you for pointing out the encoding issue. We have resolved the error by modifying the code. we changed self.image_sync = self.bridge.imgmsg_to_cv2(self.image_sync) to self.image_sync = self.bridge.imgmsg_to_cv2(self.image_sync, "bgr8") here

knzo25 commented 1 month ago

@hsule Apologies for the delay. Since we do not plan to support old versions, I instead implemented the necessary glue for the interactive camera-lidar calibrator to be used in the new api, while also fixing the encoding issue (it had already been fixed in other tool - it is related to how we expect only rgb fields in the buffer)

You can use the following branch to calibrate https://github.com/tier4/CalibrationTools/pull/179

If you do not want to configure the launcher with the UI, you can also replace the relevant launcher with the following content:

<launch>

  <arg name="camera_optical_link_frame" default="zedxm_left_camera_optical_frame" description="E.g., camera0/camera_optical_link"/> <!-- this is needed for the calibrator interface - transformation algebra-->
  <arg name="lidar_frame" default="base_link" description="E.g., velodyne_top. this is used for the extrinsic_calibration_manager under the hood"/>
  <!-- <arg name="image_topic" default="/sensing/camera/camera0/image_rect_color/decompressed" description="Internal topic to decompress the image"/> -->
  <arg name="image_topic" default="/sensing/camera/zedxm/zed_node/rgb/image_rect_color" description="Internal topic to decompress the image"/>
  <!-- <arg name="camera_info_topic" default="/sensing/camera/camera0/camera_info"/> -->
  <arg name="camera_info_topic" default="/sensing/camera/zedxm/zed_node/rgb/camera_info"/>
  <!-- <arg name="pointcloud_topic" default="/sensing/lidar/top/pointcloud_raw"/> -->
  <arg name="pointcloud_topic" default="/sensing/lidar/concatenated/pointcloud"/>

  <arg name="use_rectified_image" default="true" description="image_rect vs. raw"/>
  <arg name="use_compressed_image" default="false" description=""/>
  <arg name="timer_period" default="1.0" description="Calibration timer period in seconds"/>
  <arg name="delay_tolerance" default="1.06" description="Maximum time difference allowed between sensors in seconds"/>

  <let name="rviz_profile" value=""/>
  <let name="rviz_profile" value="$(find-pkg-share interactive_camera_lidar_calibrator)/rviz/default_profile.rviz"/>

  <!-- interactive calibrator -->
  <node pkg="interactive_camera_lidar_calibrator" exec="interactive_calibrator" name="interactive_calibrator" output="screen">
    <remap from="pointcloud" to="$(var pointcloud_topic)"/>
    <remap from="image" to="$(var image_topic)"/>
    <remap from="camera_info" to="$(var camera_info_topic)"/>
    <remap from="extrinsic_calibration" to="calibrate_camera_lidar"/>

    <param name="use_rectified" value="$(var use_rectified_image)"/>
    <param name="use_compressed" value="$(var use_compressed_image)"/>
    <param name="timer_period" value="$(var timer_period)"/>
    <param name="delay_tolerance" value="$(var delay_tolerance)"/>

    <param name="use_calibration_api" value="true"/>
    <param name="can_publish_tf" value="false"/>
  </node>

  <node pkg="tf2_ros" exec="static_transform_publisher" name="dummy_broadcaster" output="screen" args="0 0 0 0 0 0 $(var lidar_frame) lidar_frame"/>

  <!-- remap the pointcloud topic to make the rviz profile generic -->
  <node pkg="rviz2" exec="rviz2" name="rviz2" output="screen" args="-d $(var rviz_profile)">
    <remap from="pointcloud_topic_placeholder" to="$(var pointcloud_topic)"/>
  </node>
</launch>

Since there were no tfs in the bag, I just used the default one:

ros2 run tf2_ros static_transform_publisher --frame-id base_link --child-frame-id zedxm_left_camera_optical_frame --x 0.0 --y 0.0 --z 0.0 --qx 0.5 --qy -0.5 --qz 0.5 --qw -0.5

Which gave me the following initial visualization:

Screenshot from 2024-07-19 22-48-44

Hope this helps and let me know how it goes !

knzo25 commented 1 week ago

@hsule If there are no updated in this, I will be closing this in about one week