Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -71,3 +71,4 @@ To merge your changes/added files into the official match-ROS repository, we nee
| [250408](student_code/250408_Dynamic_Model_for_mobile_robots/README.md) | Entwicklung eines dynamischen Modells zur flexiblen Implementierung auf mobilen Robotersystemen | Dynamische Modellierung von mobilen Robotern, wobei das Modell flexibel auf verschiedenste Roboter übertragen werden kann |
| [250428](student_code/250428_Scan_to_map_localization_Mid360_Simulation/README.md) | Development and implementation of a concept for localization using 3D-LiDAR | Algorithm for scan-to-map based 3D real-time localization |
| [250429](student_code/250429_real_time_stabilization/README.md) | Real-Time Compensation of Ground Irregularities for Mobile Robot in Construction Additive Manufacturing | Algorithm to stabilize the nozzle for additive manufacturing purposes using IMU-based inclination data during movement on uneven terrain |
| [251127](student_code/251127_print_texture_localization/README.md) | Concept development for robot localization based on an object to be manufactured | Concept for texture-based localization approach for mobile manipulator based on the initial layers of the printed object, using image descriptors and ICP refinement|
51 changes: 51 additions & 0 deletions student_code/251127_print_texture_localization/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
# Wall Localization Demo

## Overview
This folder contains the code developed for wall-based scanner localization using geometric and appearance-based matching. The approach localizes a vertical profiler or scanner relative to a known wall geometry by combining 2D image-based matching (LBP or SIFT) with 3D ICP refinement.

**Author:** Linh Thach Dang
**E-Mail:** linh.thach.dang@stud.uni-hannover.de


## Installation
Copy this folder into the `src` directory of a catkin workspace and build it using `catkin_tools`.

```bash
cd ~/catkin_ws/src
cp -r wall_localization_demo .
cd ~/catkin_ws
catkin build
source devel/setup.bash
```

## Package
### wall_localization_demo

This package contains all nodes, scripts, and launch files required for:
- offline wall map generation,
- live localization,
- evaluation against ground truth.


## Scripts

All core scripts are located in `src/wall_localization_demo/`.

### main.py
Runs the live localization pipeline.
Subscribes to a LaserScan topic, transforms scan points into the wall frame, builds a local patch image, performs 2D localization (SIFT or LBP), refines the pose using ICP, and publishes the estimated scanner pose as the TF frame `scanner_icp_refined`.

### localization_core.py
Implements the core localization algorithms used by `main.py`, including patch generation, descriptor extraction, database matching, ICP refinement, and pose estimation.

### compare_poses.py
Logs ground truth and estimated poses during localization.
Samples TF and writes two CSV files:
- `groundtruth_poses.csv` (wall → vertical_profiler_link)
- `estimated_poses.csv` (wall → scanner_icp_refined)

### move_along_wall.py
Moves the robot along the wall at a fixed offset to generate continuous scan data during experiments.

### pcl2texture.py
Utility script to convert point cloud data into image or texture representations of the wall.
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
rosbag
.vscode
.git

*.csv
*.png
*.jpg
*.obj
*.dae
*.npy
*.npz
*.pkl
Original file line number Diff line number Diff line change
@@ -0,0 +1,84 @@
cmake_minimum_required(VERSION 3.0.2)
project(wall_localization_demo)

## Python3 required
set(CMAKE_CXX_STANDARD 14)
set(PYTHON_EXECUTABLE /usr/bin/python3)

find_package(catkin REQUIRED COMPONENTS
rospy
std_msgs
geometry_msgs
sensor_msgs
nav_msgs
tf2_ros
tf_conversions
pcl_ros
pcl_msgs
gazebo_ros
)

## OpenCV (used inside localization_2d.py and main.py)
find_package(OpenCV REQUIRED)

catkin_python_setup()

## Open3D is a Python dependency, not C++.
## sklearn/skimage/numpy also Python dependencies.

catkin_package(
CATKIN_DEPENDS
rospy
std_msgs
sensor_msgs
geometry_msgs
nav_msgs
tf2_ros
tf_conversions
pcl_ros
pcl_msgs
gazebo_ros
)

#############
## INSTALL ##
#############

## Install Python scripts so rosrun/roslaunch can find them
catkin_install_python(
PROGRAMS
src/wall_localization_demo/main.py
src/wall_localization_demo/move_along_wall.py
src/wall_localization_demo/compare_poses.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

## Install launch files
install(DIRECTORY launch/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch
)

## Install config files
install(DIRECTORY config/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config
)

## Install models (for Gazebo)
install(DIRECTORY models/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/models
)

## Install worlds
install(DIRECTORY worlds/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/worlds
)

## Install URDF files
install(DIRECTORY urdf/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/urdf
)

## Install any data (optional)
install(DIRECTORY data/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/data
)
Original file line number Diff line number Diff line change
@@ -0,0 +1,118 @@
# wall_localization_demo

## Overview
This package implements a wall-based localization approach for a vertical profiler using LaserScan data in ROS Noetic.
The scanner pose is estimated relative to a known wall geometry by combining 2D image-based feature matching (LBP or SIFT) with 3D ICP refinement.
The package supports offline wall map generation, live localization in Gazebo simulation, and quantitative evaluation against ground truth data.

**Author:** Linh Thach Dang
**E-Mail:** linh.thach.dang@stud.uni-hannover.de

## Usage
To run the live localization experiment in Gazebo, launch:
```bash
roslaunch wall_localization_demo run_localization.launch
```
This starts the simulation, initializes the localization pipeline, publishes required static transforms, and records ground truth and estimated poses.


## Config files

- ```offline_map.yaml```
Contains file paths to the offline wall map, point cloud, and descriptor databases used during localization.

- ```estimator_params.yaml```
Defines parameters for the live localization pipeline, including frame definitions, filtering limits, and ICP settings.

- ```localization_params.yaml```
Contains parameters for the 2D feature matching stage, such as descriptor configuration and matching thresholds.


## Launch files

- ```run_localization.launch```
Runs the complete live localization pipeline in simulation.

Argument list:
method (type: string, default: sift): Feature matching method used for localization (sift or lbp).
pointcloud_topic (type: string, default: /scan_cloud): LaserScan input topic.

- ```build_offline_map.launch```
Builds the offline wall map and descriptor databases from recorded scan data.

- ```run_mapping_recording.launch```
Records wall scan data while the robot moves along the wall.

- ```spawn_world_and_robot.launch```
Spawns the Gazebo world, wall model, and robot equipped with the vertical profiler sensor.


## Nodes

```scanner_pose_estimator```

This node performs the live wall-based localization. It processes incoming LaserScan data, builds local wall patches, performs 2D image-based matching, refines the pose using ICP, and publishes the estimated scanner pose as a TF transform.


## Subscribed Topics

```scan_cloud``` (sensor_msgs/LaserScan)
Laser scan data acquired by the vertical profiler sensor.

```odom``` (nav_msgs/Odometry)
Odometry data of the mobile robot.

## Parameters
```wall_frame``` (type: string, default: wall): Reference frame attached to the wall geometry.

```scanner_frame``` (type: string, default: vertical_profiler_link): Frame of the vertical profiler sensor.

```base_frame``` (type: string, default: base_link): Robot base frame used for odometry and TF lookups.

```odom_topic``` (type: string, default: /odom): Odometry topic used for motion tracking.

```s_min_live``` (type: float, default: -0.6): Minimum along-wall coordinate for live scan filtering.

```s_max_live``` (type: float, default: 0.6): Maximum along-wall coordinate for live scan filtering.

```z_min_live``` (type: float, default: 0.0): Minimum height for live scan filtering.

```z_max_live``` (type: float, default: 2.0): Maximum height for live scan filtering.

```live_img_w``` (type: int, default: 6): Width of the live patch image.

```live_img_h``` (type: int, default: 11): Height of the live patch image.

```icp_max_iter``` (type: int, default: 50): Maximum number of ICP iterations.

```icp_max_dist``` (type: float, default: 0.0035): Maximum correspondence distance used during ICP refinement.

```method``` (type: string, default: sift): Feature matching method used for 2D localization.

```stride``` (type: int, default: 16): Step size used when sliding the query window over the offline wall map during 2D localization.

```max_query_kps``` (type: int, default: 60): Maximum number of keypoints extracted from the live patch and used for feature matching.

```patch_h``` (type: int, default: 100): Height of the image patch used for 2D feature extraction and matching.

```patch_w``` (type: int, default: 100): Width of the image patch used for 2D feature extraction and matching.

```lbp_radius``` (type: int, default: 2): Radius of the circular neighborhood used for LBP feature computation.

```lbp_points``` (type: int, default: 16): Number of sampling points on the LBP circular neighborhood.

```lbphf_keep``` (type: int, default: 24): Number of most significant LBP-HF histogram bins retained for matching.

```coarse_topk``` (type: int, default: 10): Number of top candidate matches retained during coarse 2D localization.

```sift_ratio``` (type: float, default: 0.7): Lowe’s ratio threshold used to filter ambiguous SIFT feature matches.

```sift_pca_dim``` (type: int, default: 4): Dimensionality of SIFT descriptors after PCA compression.

```scale_bins``` (type: int, default: 3): Number of scale bins used for multi-scale SIFT feature extraction.

```flann_trees``` (type: int, default: 4): Number of KD-trees used by the FLANN-based SIFT matcher.

```flann_checks``` (type: int, default: 60): Number of search checks performed by the FLANN matcher during feature matching.


Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
wall_frame: "wall"
scanner_frame: "vertical_profiler_link"
base_frame: "base_link"

s_min_live: -1.0
s_max_live: 1.0
z_min_live: 0.0
z_max_live: 5.0

live_patch_s_length: 0.20

method: "lbp"

icp_max_dist: 0.05
icp_max_iter: 50

live_img_h: 11 # matches PATCH_H
live_img_w: 6 # matches PATCH_W
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
# ============================================================
# LOCALIZATION_2D PARAMETERS (OVERWRITES DEFAULT CONSTANTS)
# ============================================================

loc2d:

# -------- General --------
stride: 16
max_query_kps: 60
patch_h: 100
patch_w: 100

# -------- LBP-HF --------
lbp_radius: 2
lbp_points: 16
lbphf_keep: 24
coarse_topk: 10

# -------- SIFT --------
sift_ratio: 0.7
sift_pca_dim: 4
scale_bins: 3

# -------- FLANN (SIFT matcher) --------
flann_trees: 4
flann_checks: 60

Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
cloud: "$(find wall_localization_demo)/data/demo_points.csv"
out_map: "offline_map.npy"
out_points: "offline_points.npy"
delta_s: 0.005
delta_z: 0.005
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
<launch>

<!-- Build mapping dictionary (u,v)->(gray, point_indices) -->
<node pkg="wall_localization_demo" type="pcl2texture.py"
name="build_texture_map" output="screen">
<param name="cloud"
value="$(find wall_localization_demo)/data/mapping_run/wall_points_gazebo.csv"/>
<param name="out-map"
value="$(find wall_localization_demo)/data/mapping_run/offline_map_gazebo.npy"/>
<param name="out-points"
value="$(find wall_localization_demo)/data/mapping_run/offline_points_gazebo.npy"/>
<param name="delta-s" value="0.005"/>
<param name="delta-z" value="0.005"/>
</node>

</launch>
Loading