thillRobot / seam_detection

ROS package for weld seam detection using pointcloud data
GNU General Public License v3.0
14 stars 3 forks source link

seam_detection

This is a ROS(1) package for weld seam detection from pointclouds using the point cloud library PCL.

seam_detection

Publications:

Automated Weld Path Generation Using Random Sample Consensus and Iterative Closest Point Workpiece Localization
Proceedings of the ASME 2022
International Design Engineering Technical Conferences and
Computers and Information in Engineering Conference
IDETC/CIE2022 August 14-17, 2022, St. Louis, MO

Installing seam_detection

Requirements:

Operating System:

Step 1 - Setup ROS workspace

Create and build a catkin workspace before proceeding. Choose a location and insert a name for the workpace. Typically this is somewhere in ~/.

mkdir -p ~/<workspace-name>/src
cd ~/<workspace-name>
catkin_make

Add the workspace path to /.bashrc so that ros can find your packages

echo "source ~/<workspace-name>/devel/setup.bash" >> ~/.bashrc

To use a catkin workspace that is already setup, skip Step 1 (the workspace can be compiled with catkin_make or catkin build).

Step 2 - Download seam_detection Package

Change to the source directory of the workapce and clone the package using git.

cd ~/<workspace-name>/src
git clone https://github.com/thillRobot/seam_detection.git

or using SSH (used by thillrobot)

git clone git@github.com:thillrobot/seam_detection.git

Step 3 - Compile seam_detection in catkin workspace

Change to top of workspace and compile.

cd ..
catkin_make

The workspace and package should compile without errors.

Using seam_detection

Primary Nodes

(Early work 2018-2021, needs testing)

Supporting Nodes

Development Nodes

Note: This project has been running for years, and it has seen a lot of recent changes. Some of the older methods may not run currently, but effort is being made to bring everthing up to date and improve documentation. Contact thillRobot if you have questions or run into problems.

Examples:

These examples require a pre-recorded pointcloud from a 3D Lidar and/or CAD. There are example scans here. This code is based on PCL - Sample Consensus and RANSAC (SEGMENTATION) Note: .pcd files are currently in the .gitignore so you have to generate them locally which is explained below.

Random Sample Consensus - RANSAC

Use RANSAC to fit a models to a pointcloud.

The library supports planes, cylinders, spheres and more.

roslaunch seam_detection ransac_plane.launch in_file:="lidar_cad_scenes/test_cloud8.pcd" thresh:=0.01
Use RANSAC to segment, or separate, pointclouds.
roslaunch seam_detection segment_plane.launch in_file:="lidar_cad_scenes/test_cloud8.pcd" thresh:=0.01
Use RANSAC for weld seam detection. Each plane is found with RANSAC, then the origin is calculated as the intersection of the three planes.
roslaunch seam_detection seam_detection_RANSAC.launch in_file:="lidar_cad_scenes/lidar_scene1.pcd" out_file:="scene1.txt" thresh1:=0.01 thresh2:=0.001

Iterative Closest Point - ICP

These demos require two points clouds to be saved as .pcd files. Use the default images or make you own with the following procedure.

Import a cloud from a CAD model: Solidworks(.stl)-->meshlab(.ply)-->cad2cloud(.pcd)-->ROS(pointcloud)
Step 1)

Make a part in your CAD program of choice. This part will become the 'reference cloud'. Save the file as a '.stl' file. If your CAD program can create a '.ply' or '.pcd' file you can skip steps 2 or 3 respectively. Use units of meters for the part and stl export.

Note: In Solidworks: Save As -> select .ply then click Option and set the output units to meters.

Step 2)

Convert the '.stl' to a '.ply' file using meshlab. Open the '.stl' using 'import mesh' and save it as a '.ply' file. Step2 can be done in solidworks. This could combine Step 1 and Step 2.

Step 3 - Option 1)

Convert a single '.ply' file to a '.pcd' file using cad_cloud.cpp. This is a I wrote based on sample code from PCL. The input arguments determine the resolution of the resulting files, and you must pass in the input and output file names. The parameters -n_samples and -leaf_size determine the resolution of the conversion.

cd seam_detection

rosrun seam_detection cad_cloud -n_samples 100000 -leaf_size 0.00025 -write_normals 1 ply_images/input.ply pcd_images/output.pcd

pcl_viewer -multiview 1 output.pcd
Step 3 - Option 2)

Alternatively, you can use cad_cloud_bulk.cpp to convert an entire directory of .ply files to .pcd files. This is based on the same sample code from PCL, but it iterates through the input directory with boost. The conversion parameter arguments are the same, but you must include the input and output directories instead of the file names.

rosrun seam_detection cad_cloud_bulk -n_samples 100000 -leaf_size .00025 -write_normals 1 -input_dir "ply_images/" -output_dir "pcd_images/"

Sometimes the extensions get changed from .ply to .PLY and I do not know why. This causes errors and confusion because there can be duplicate files in the same location. To fix this issue delete any duplicates before running the following command to change all extensions to lower case.

find . -name '*.*' -exec sh -c '
  a=$(echo "$0" | sed -r "s/([^.]*)\$/\L\1/");
  [ "$a" != "$0" ] && mv "$0" "$a" ' {} \;

This comes from stackoverflow

Step 4)

Use ICP to compare the CAD/reference image to the LIDAR/source image. The LIDAR '.pcd' file must also be in the image directory. There are four numbered scenes choose from. There appears to be one directory level hidden in the launch file. I am not sure if this is a good idea or not.

roslaunch seam_detection seam_detection_ICP.launch lidar_file:="lidar_cad_scenes/plate_cylinder.pcd" cad_file:="lidar_cad_scenes/cylinder.pcd"  thresh:=0.0001

Note: The code for seam_detection_icp.cpp was removed to reduce confusion. Use the updated seam_detection.cpp node instead for the same functionality .

RANSAC + ICP SEAM DETECTION

Use RANSAC + ICP for weld seam detection. First segmen t with RANSAC(or other) then use ICP to locate the origin of the part.

These examples have the round_tube or a square_tube and the plate. There can be variations in part1 one but you must choose round_tube or a square_tubefor the segmentation to work properly. These work well, but there is some discrepancy along the length of the cylinder. All other dimensions match very well. This seems to be related to the amount of data that is avaialable about this dimension.

---
scene_name: "table_8in10in_tee_longclamps_x4y24_45"
lidar_src_file: "pcd_images/table_tee/table_8in10in_tee_longclamps_x4y24_45.pcd"
part1_name: "8in10in_tee_01"
cad_ref_file: "pcd_images/table_tee/8in10in_tee_01_blndrB.pcd"
part1_type: "square_tube"
part2_name: "none"
part2_type: "none"

filter_box: [-0.05, 0.30, -1.0, -0.4, -0.02, 0.3] # bounding box limits
voxel_leaf_size: 0.0005                           # voxel leaf size

ransac_norm_dist_wt: 0.1 # RANSAC Normal Distance Weight
ransac_max_iter: 100     # RANSAC Maximum Iterations
ransac_dist_thrsh: 0.03  # RANSAC Distance Threshold
ransac_k_srch: 50        # RANSAC KD Tree Parmeter(?)
ransac_init_norm: [-1.0, 1.0, 0.0] # RANSAC init perpendiculr vector

icp_max_corr_dist: 0.5            # ICP Maximum Correspondence Distance
icp_max_iter: 1000000000          # ICP Maximum Iterations
icp_trns_epsl: 0.000000001        # ICP Transformation Epsilon
icp_ecld_fitn_epsl: 0.000000001   # ICP Euclidean Distance Fitness Epsilon          

expected_results: [0.1016, -0.6096, 0.0254,0.0,0.0,0.7854] # [4.0in, -24.0in, 1.0in]*(25.4e-3) #[0.0,0.0,45.0]*(pi/180)
calibration_offset: [-0.00893203,-0.000860624,0.00537355,-0.00493333,-0.000708936,0.019938]

seam1_length: 1.0                      # weld seam length
seam1_points_x: [10, 11, 12, 13]       # weld seam control points
seam1_points_y: [20, 55, 22, 23]
seam1_points_z: [30, 31, 54, 12]
Simulated Application - source and target clouds from CAD (simulated LiDAR)

plate_rect_block

roslaunch seam_detection seam_detection.launch config:="scenes/plate_rect_block_02"
roslaunch seam_detection seam_detection.launch config:="scenes/plate_rect_block_02_blndr"
roslaunch seam_detection seam_detection.launch config:="scenes/plate_rect_block_02_blndr"
roslaunch seam_detection seam_detection.launch config:="scenes/plate_rect_block_02_dx100_rz30_blndr"

table_tee

add these here, this scene was used in the 2022 pub (table_tee simulated application is missing or was never completed, look into this)

Experimental Application A - LiDAR scans from RPLiDAR A2 on Aubo i5

table_8in10in_tee

roslaunch seam_detection seam_detection.launch config:="scenes/table_8in10in_tee_x4y24_45"
roslaunch seam_detection seam_detection.launch config:="scenes/table_8in10in_tee_x0y24"

table_8in10in_tee_longclamps

roslaunch seam_detection seam_detection.launch config:="scenes/table_8in10in_tee_longclamps_x4y24_45"
Experimental Application B - LiDAR scans from RPLiDAR A2 on Aubo i10 - recorded 06/21/2023

add this

archived examples

These examples will not run because the config files need to be updated to the new format, do this soon

plate_round_tube_01 (not working)

roslaunch seam_detection seam_detection.launch scene:="plate_round_tube_01"

plate_square_tube_01 (not working)

roslaunch seam_detection seam_detection.launch scene:="plate_square_tube_01"

table_plate_tee_clamps (not working)

roslaunch seam_detection seam_detection.launch scene:="table_plate_tee_clamps_c1_blndr"
simulated test scenes
Testing TEASER
Testing Model Recognition from PCL
rosrun seam_detection correspondence_grouping pcd_images/plate_rect_block/rect_block_02.pcd pcd_images/plate_rect_block/rect_block_02.pcd -c -k

the correspondence grouping sample code compile and runs, but it only finds a model instance if I give it the same clouds...

$ rosrun seam_detection correspondence_grouping pcd_images/table_tee/offset_tee_01.pcd pcd_images/table_tee/offset_tee_c1.pcd -c -k
Failed to find match for field 'rgba'.
Failed to find match for field 'rgba'.
Model total points: 98060; Selected Keypoints: 1205
Scene total points: 98121; Selected Keypoints: 72
Correspondences found: 60
Model instances found: 0

$ rosrun seam_detection correspondence_grouping pcd_images/table_tee/offset_tee_c1.pcd pcd_images/table_tee/offset_tee_c1.pcd -c -k
Failed to find match for field 'rgba'.
Failed to find match for field 'rgba'.
Model total points: 98121; Selected Keypoints: 1217
Scene total points: 98121; Selected Keypoints: 72
Correspondences found: 70
Model instances found: 1

    Instance 1:
        Correspondences belonging to this instance: 56

            |  1.000 -0.000 -0.000 | 
        R = |  0.000  1.000  0.000 | 
            |  0.000  0.000  1.000 | 

        t = < 0.000, -0.000, -0.000 >
BEGINNING RANSAC SEGMENTATION
Plane coefficients: header:
seq: 0 stamp: 0 frame_id:
values[]
  values[0]:   9.70263e-06
  values[1]:   9.7027e-06
  values[2]:   1g
  values[3]:   -0.0250056

PointCloud representing the planar component: 2993 data points.
[pcl::SampleConsensusModel::getSamples] Can not select 0 unique points out of 0!
[pcl::RandomSampleConsensus::computeModel] No samples could be selected!
[pcl::SACSegmentationFromNormals::segment] Error segmenting the model! No solution found.
new test scenes - generated 06/21/2023 - rplidar a2 on aubo i10

two new steel objects: shape1 and shape2 (best names ever)

testing with register_clouds.cpp to compare ICP vs TEASER vs TEASER_FPFH (fast point feature histogram)

roslaunch seam_detection register_clouds.launch 

test mode 1: CAD model based target cloud (fixed) and a LiDAR based source cloud (transformed) - (what we previously have done)

example:

roslaunch seam_detection register_clouds.launch config:="scenes/shape2_60deg"

NEW! test mode 2: LiDAR based taget cloud and different LiDAR scan based source cloud - as suggested by SC

example:

roslaunch seam_detection register_clouds.launch config:="scenes/shape2_45deg_60deg"

filter_cloud

This routine is designed to automate the selection/identification of the source cloud to be used in registration

filtering process

the node filter_cloud.cpp containes bounding box, voxel, and cluster based filtering on a single pointcloud from pcd

roslaunch seam_detection filter_cloud.launch

adjust values in config/filter_cloud.yaml or use a different config file

roslaunch seam_detection filter_cloud.launch config:=filter_aubo_cloud

new test scenes from ds435i depth camera

pcd files in pcd_images/ds435i_table_parts/

roslaunch seam_detection filter_cloud.launch config:="filter_cloud_ds435i"

new developement node - class approach

filtering process - run the following launch to process a bag file and or directory of pcd files

roslaunch seam_detection filter_dataset.launch

The parameters can be set in config/filter_dataset.yaml, or a different config name can be passed to the launch command

roslaunch seam_detection filter_dataset.launch config:=<CONFIGNAME>

analyis and part identification - run the following to test the part identification process (This probably needs a new name for the script and the the rest... seam_detection is already used)

roslaunch seam_detection seam-detection.launch

The parameters can be set in config/seam-detection.yaml, or a different config name can be passed to the launch command

Config Files

All the file names and parameters for each primary node are defined in a config file .yaml saved in config/. Pass the name of config when using a node as shown below. The default config file sharing the node name will now be used if no config is specified.

Note: the way config files are has been improved to streamline the process and generalize across methods, see filter_cloud.yaml and register_clouds.yaml for updated examples. The launch arg has been renamed from scene to config, and the default config shares the node name. The older configs and docs are slowly being updated with the changes. Many of the old scene configs can be found in config/scenes.

running in Docker

Stand up the entire application in a single line using docker and docker compose. This is not required, but allows for portable testing.

Create a source directory and set the environment variable $ROS_WS (previously CATKIN_WS_PATH)

mkdir -p ~/catkin_ws/src
export ROS_WS=~/catkin_ws

Clone this repository into $ROS_WS/src

cd $ROS_WS/src
git clone git@github.com:thillrobot/seam_detection

Modify xauth access control to allow display

xhost local:root

Build the container and start the application

cd seam_detection/docker
docker compose up --build 

Run a simple test, this calls one of the launch files from above and uses the default config file.

cd seam_detection/docker
docker compose run seam-detection

Note: if you want to generate files in the container, for example when using cad_cloud to make PCDs, you must set the permissions of the workspace directory or sub directory on the host to give the docker container write access which would be an 'other' in this case.

chmod o+w seam_detection/<SUBDIR>

we might have to make a patch on the kinetic side to fix this.

new scenes and launch files from Aubo i10, Summer 2023 at RTT

launch files:

The process from the summer 2023 season needs documentation!

Changelog

Tagged Versions

Things To Do (priority top to bottom):