ITI-THM / ros2_surface_scanner

Apache License 2.0
3 stars 0 forks source link

A laser triangulation sensor with ROS2


Author: Tristan Elias Wolfram

This Repository introduces a sofware package for a laser triangulation sensor. The sensor is used to reconstruct surfaces of wood slices.

Here some example scans produced by the sensor:

scan0 scan1 scan2

📖 The scanner was developed as part of a Bachelor's thesis at the Institut für Technik und Informatik (ITI) at University of Applied Sciences Mittelhessen in Germany. You can find the thesis here.

The surface_scanner package

⚙️ Requirements

The Sytem is tested with two setups.

Installation

Go to your ROS workspace in the src-directory and clone the repository.

git clone https://github.com/TristanWolfram/ros2_surface_scanner.git

Use colcon to build the package:

cd ..
colcon build

To use the ROS2-nodes you have to source your current worspace from inside the workspace directory:

. install/setup.bash

Usage

Start the Scanner

To launch the whole surface scanner use the launch-file:

ros2 launch surface_scanner surface_scanner.launch.py

This will start three nodes, the surface_scanner_node, camera_node and rviz2.

# for raspberry setup
ros2 launch surface_scanner surface_scanner_rasp.launch.py

Nodes

surface_scanner_node

Responsible for all calculations. Stores all data.

Subscribed Topics

camera_node (camera_node_rasp)

The optical sensor of the triangolation sensor. Takes images for calibration and to reconstruct the surface. The pictures will be send to the surface_scanner_node via special topics.

Published Topics

rviz2

Used as point cloud subscriber

Subscribed Topics


Calibration

The following functions will start a client that calls a defined service.

Now you have to calibrate the scanner. The calibration consists of an intrinsic and an extrinsic calibration. For the intrinsic calibration, a chessboard must be recorded from 10 different positions. For the extrinsic one, the special calibration board with ChArUco markers must be placed under the sensor.

ros2 run surface_scanner intr_calib_imgs

This function is used to take the intrinsic calibration images.

However, the functionality for manually capturing 10 different images is not yet implemented.

Therefore you have to take the 10 images with your camera by yourself. You have to put these 10 images in the following Directory: surface_scanner/input/. Additionally the images must be named calibrationimg<0-9>.png.

If .png is the wrong file type for you, you have to change it manually in the code. You can find the code segment in the Camera_Node at function send_cam_calib_imgs.

The images shoud be look like this:

scan0 scan1 scan2

Used intrinsic calibration board:

  • 7x9
  • checker size = 0.025 m
ros2 run surface_scanner extr_calib_imgs

This function is used to take the extrinsic calibration images. You have to take an clear picture of the calibration board. The image pair shoud look like this:

scan0 scan1

Extrinsic calibration board:

  • primary (up):
    • aruco dictionary: DICT_4x4
    • X=7, Y=5
    • square length = 0.025m, marker length = 0.019m
  • secondary (down):
    • aruco dictionary: DICT_5x5
    • X=7, Y=5
    • square length = 0.025m, marker length = 0.019m

Note that the accuracy of the extrinsic calibration board is critical to the accuracy of the entire sensor.

You can use the pattern generator from calib.io to generate your own calibration board.

Now it is possible to calibrate the whole scanner by typing the following function into your terminal:

ros2 run surface_scanner calibrate

If the calibration succeded you will find the results in the out-directory. The Scanner_Node will also send a point cloud of the calculated laser plane to rviz2. The used topic for that is laser_plane.

For the intrinsic calibration an .npz-file should be created. You can use this file to import the camera data when you start the scanner another time. So you don't have to do an intrinsisc calibration again. Just use this calibration method:

ros2 run surface_scanner calibrate_with_import <path to camera parameters>

Camera Stream

You can turn on an camera stream. The camera node will now continuously publish images with the given topic (img_publisher). Rviz2 can subscribe to this topic an shows the images.

You can use this image stream to focus the camera or to put the calibration board or chessboard in the right position.

ros2 run surface_scanner start_img_stream

ros2 run surface_scanner stop_img_stream

Pointcloud generation

When the scanner is calibrated you can use it to reconstruct surfaces. A method that is always possible after calibration is to acquire one surface line with the following function. You will find the created pointcloud in the out-directory.

ros2 run surface_scanner surface_line

This function generates several surface_line pointclouds in a row.

ros2 run surface_scanner start_scan