Skip to content

qualcomm-qrb-ros/qrb_ros_calibrator

QRB ROS CALIBRATOR

ROS Packages for Sensor Extrinsic Parameters Calibration

πŸ‘‹ Overview

qrb_ros_calibrator provide the calibration tools as follow:

  • 2D-LiDAR and Odometry extrinsic parameter calibration tool
architecture
  • The qrb_laser_odom_calibr_lib is our algorithm package. It provide the data processing and extrinsic solving function to the Odometry LiDAR Calibrator APP

  • The qrb_ros_laser_odom_calibr is a ROS2 package, which provide data collection function by subscribing ros topic of sensor node and provide the UI which is created by QT for user.

  • 2D-LiDAR and Camera extrinsic parameter calibration tool

architecture
  • The qrb_laser_cam_calibrator_lib is our algorithm package. It provide the data processing and extrinsic solving function to the Camera LiDAR Calibrator APP
  • The qrb_ros_laser_camera_calibr is a ROS2 package, which provide data collection function by subscribing ros topic of sensor node and provide the UI which is created by QT for user.

βš“ APIs

πŸ”Ή qrb_laser_odom_calibr_lib APIs

Function Parameters Description
Calibrator(std::vector& laser_data_set_in, std::vector& odom_data_set_in)
  • laser_data_set_in: Laser data set used for calibration
  • odom_data_set_in: Odometry data set used for calibration
Get the Laser data and odometry data
void get_parameters_adjust(double& max_dist_seen_as_continuous, double& line_length_tolerance, double& ransac_fitline_dist_th)
  • max_dist_seen_as_continuous: Max distance seen as continuous
  • line_length_tolerance: Max length tolerance between detected line and target line
  • ransac_fitline_dist_th: The max distance threshold that taken as inner point when fitting 2d line
Get the value of the parameters that need to be adjusted
void update_parameters_detect(const int& id,const double& max_dist_seen_as_continuous, const double& line_length_tolerance, const double& ransac_fitline_dist_th)
  • id: Data frame index
  • max_dist_seen_as_continuous: Max distance seen as continuous
  • line_length_tolerance: Max length tolerance between detected line and target line
  • ransac_fitline_dist_th: The max distance threshold that taken as inner point when fitting 2d line
Update the parameters and detect the line features
bool calibrate() Empty Execute calibration and get the calibration result

πŸ”Ή qrb_laser_cam_calibrator_lib APIs

Function Parameters Description
initialize() Empty Initialize the calibrator
set_laser_plane(const LaserPlane & laser_plane)
  • laser_plane: Captured laser plane
Set the laser plane for initial rotation guess
set_laser_axis(const std::vector<std::string> & laser_axis)
  • laser_axis: The axises correspondence between laser axis and chessboard axis
Set the laser axis w.r.t chessboard coordinate frame for initial rotation guess
find_chessboard(const cv::Mat & image)
  • image: Input image
Check if there is a chessboard in the image
input_data(const std::vector<CameraData> & cam_data_set_in, const std::vector<LaserData> & laser_data_set_in)
  • cam_data_set_in: Input camera data set
  • laser_data_set_in: Input laser data set
Give the captured data to calibrator
update_parameters_detect(const int & index, const double & max_dist_seen_as_continuous, const double & ransac_fitline_dist_th)
  • index: The index of data set
  • max_dist_seen_as_continuous: Distance threshold for continuity
  • ransac_fitline_dist_th: RANSAC inner point distance threshold
Detect line in i-th laser data using specific parameters
get_parameters_adjust(double & max_dist_seen_as_continuous, double & ransac_fitline_dist_th)
  • max_dist_seen_as_continuous: Distance threshold for continuity
  • ransac_fitline_dist_th: RANSAC inner point distance threshold
Get the user input parameters
get_topic_name(std::string & laser_topic, std::string & image_topic)
  • laser_topic: Laser topic name
  • image_topic: Image topic name
Get the ROS topic name for data subscription
draw_projection_result(std::vector<cv::Mat> & project_result_img)
  • project_result_img: Input image set
Project laser points into image based on calibrated result
calibrate() Empty Execute calibration
save_result() Empty Save the calibration result in extrinsic.xml file

πŸ‘¨β€πŸ’» Build

Install the dependency

sudo apt-get update
sudo apt-get install libunwind-dev libpcl-dev libeigen3-dev ros-humble-nav2-* libceres-dev libopencv-dev qtbase5-dev libqt5svg5-dev

Build the tool

To build the 2D-LiDAR and Odometry extrinsic parameter calibration tool:

cd qrb_ros_calibrator/
cd qrb_laser_odom_calibr_lib
mkdir build
cd build
cmake ..
make
sudo make install
cd ../../
colcon build --packages-select qrb_ros_laser_odom_calibrator

To build the 2D-LiDAR and Camera extrinsic parameter calibration tool:

cd qrb_ros_calibrator/
cd qrb_laser_cam_calibrator_lib
mkdir build
cd build
cmake ..
make
sudo make install
cd ../../
colcon build --packages-select qrb_ros_laser_camera_calibrator

πŸš€ Usage

2D-LiDAR and Odometry Calibration

Preparation

Calibration target construction: User use two boards with different length to construct two edges of a triangle. See the picture below:

architecture

Put the Calibration target in front of the 2D LiDAR

Generate the input file:

cd qrb_ros_calibrator/
source install/setup.bash
ros2 run qrb_ros_laser_odom_calibrator qrb_ros_inputfile_template_generator

Then the parameters_input.yaml file will generated in current folder.

Edit the parameters_input.yaml, and give the laser_topic name and odom topic name for data capturing.

Edit the parameters_input.yaml, and give the long_edge_length and short_edge_length that the board you use.

Running the calibrator

ros2 run qrb_ros_laser_odom_calibrator qrb_ros_laser_odom_calibrator

Data Capture

The calibrator will capture data by subscribe ROS topic.

User can capture a frame of data by click the button of "Capture Data"

Then user control the AMR/Vehicle to move and rotate then stop and capture a frame of data(Keep the calibration target in the FOV of 2D LiDAR).

The user click the button of "Capture Data" to capture one frame of data each time the AMR stops, repeating multiple times.

We recommend that users collect data more than 10 times

Detect Features

After data capturing, user can click the button of "Detect Features" to detect the line features in the point cloud.

We draw the detected lines of the calibration target in "Line detection results" window using red corlor.

User can check the detection result, if the result is wrong, user can change the parameters by slide the sliders to get the new detected result.

Parameters Interpretation

Note: We use RANSAC to detect lines

  • max_dist_seen_as_continuous: Max distance seen as continuous in point cloud.

  • line_length_tolerance: Max length tolerance between detected line and target line(user input).

  • ransac_fitline_dist_th: The max distance threshold that taken as inner point when fitting 2d line.

Calibration

User can check every line detection results by click "Next Frame" or "Last Frame" button.

Then click the button of Calibrate to solve the extrinsic paramters.

The rotation matrix and translation vector between 2D LiDAR frame to Odometry frame will be saved in "extrinsic.yaml" file in current folder.

2D-LiDAR and Camera Calibration

Preparation

Calibration target: Checkerboard.

Put the Calibration target in front of the 2D LiDAR and Camera

Generate the input file:

cd qrb_ros_calibrator/
source install/setup.bash
ros2 run qrb_ros_laser_camera_calibrator qrb_ros_inputfile_template_generator

Then the parameters_input.yaml file will generated in current folder.

Parameters Interpretation

Note: We use RANSAC to detect lines

Note: When capture first frame of data, user should put the calibration board in front of 2d-lidar meanwhile keep the axis of calibration board coordinate system parallel to the axis of laser coordinate system as much as possible for initial extrinsic guess.

  • image_topic_name: The ros topic name of the camera image.

  • laser_topic_name: The ros topic name of the 2D LiDAR scan.

  • relative_dist_from_laser2chessboard_origin: The distance(m) from laser plane to the origin point of calibration board coordinate system when capture first frame of data.

  • chessboard_length_in_laser_frame: The length of the checkerboard is scanned into line.

  • laser_x_wrt_chessboard: The axis of the checkerboard corresponding to the x-axis of the 2D lidar. If the direction is reversed, add "-" after the character.

  • laser_y_wrt_chessboard: The axis of the checkerboard corresponding to the x-axis of the 2D lidar. If the direction is reversed, add "-" after the character.

  • laser_z_wrt_chessboard: The axis of the checkerboard corresponding to the x-axis of the 2D lidar. If the direction is reversed, add "-" after the character.

  • intrinsic: The camera intrinsic matrix

  • distortion: The camera distortion vector

  • chessborad_rows: The rows of the cornor points in the checkerboard.

  • chessborad_cols: The columns of the cornor points in the checkerboard.

  • chessboard_square_height: The heigth(mm) of the square in the checkerboard.

  • chessboard_square_width: The heigth(mm) of the square in the checkerboard.

  • left_margin_length: The length(mm) of margin to the left of the checker pattern of the checkerboard.

  • right_margin_length: The length(mm) of margin to the left of the checker pattern of the checkerboard.

  • up_margin_length: The length(mm) of margin above the checker pattern of the checkerboard.

  • down_margin_length: The length(mm) of margin below the checker pattern of the checkerboard.

  • max_dist_seen_as_continuous: Max distance seen as continuous in point cloud.

  • line_length_tolerance: Max length tolerance between detected line and target line(user input).

  • ransac_fitline_dist_th: The max distance threshold that taken as inner point when fitting 2d line.

User need to change the above parameters in parameters_input.yaml file according to the actual scenario.

Running the calibrator

ros2 run qrb_ros_laser_camera_calibrator qrb_ros_laser_camera_calibrator

Data Capture

The calibrator will capture data by subscribe ROS topic.

User can capture a frame of data by click the button of "Capture Data"

User put the calibration board in front of 2d-lidar meanwhile keep the axis of calibration board coordinate system parallel to the axis of laser coordinate system as much as possible.

Then user click the button of "Capture Data" to capture first frame of data.

Rotate and move the calibration board and capture data by pressing "Capture Data" button many times.

We recommend that users collect data more than 10 times

Detect Features

After data capturing, user can click the button of "Detect Features" to detect the line features in the point cloud.

We draw the detected lines of the calibration target in "Line detection results" window using red corlor.

User can check the detection result, if the result is wrong, user can change the parameters by slide the sliders to get the new detected result.

Calibration

User can check every line detection results by click "Next Frame" or "Last Frame" button.

Then click the button of Calibrate to solve the extrinsic paramters.

The rotation matrix and translation vector between 2D LiDAR frame to Camera frame will be saved in "extrinsic.yaml" file in current folder.

🀝 Contributing

We would love to have you as a part of the QRB ROS community. Whether you are helping us fix bugs, proposing new features, improving our documentation, or spreading the word, please refer to our contribution guidelines and code of conduct.

  • Bug report: If you see an error message or encounter failures, please create a bug report
  • Feature Request: If you have an idea or if there is a capability that is missing and would make development easier and more robust, please submit a feature request

❀️ Contributors

See also the list of contributors who participated in this project.

πŸ“œ License

Project is licensed under the BSD-3-clause License. See LICENSE for the full license text.

About

No description, website, or topics provided.

Resources

License

Code of conduct

Contributing

Stars

Watchers

Forks

Releases

No releases published

Packages

No packages published

Contributors 4

  •  
  •  
  •  
  •