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
3 changes: 3 additions & 0 deletions .github/workflows/code-coverage.yml
Original file line number Diff line number Diff line change
Expand Up @@ -8,5 +8,8 @@ on:
jobs:
code-coverage:
uses: vortexntnu/vortex-ci/.github/workflows/reusable-code-coverage.yml@main
with:
vcs-repo-file-url: './dependencies.repos'
before_install_target_dependencies: './scripts/ci_install_dependencies.sh'
secrets:
CODECOV_TOKEN: ${{ secrets.CODECOV_TOKEN }} # Set in the repository secrets
2 changes: 2 additions & 0 deletions .github/workflows/industrial-ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -13,4 +13,6 @@ jobs:
industrial-ci:
uses: vortexntnu/vortex-ci/.github/workflows/reusable-industrial-ci.yml@main
with:
upstream_workspace: './dependencies.repos'
before_install_upstream_dependencies: './scripts/ci_install_dependencies.sh'
ros_repo: '["testing", "main"]'
2 changes: 0 additions & 2 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,6 @@ dist/
downloads/
eggs/
.eggs/
lib/
lib64/
parts/
sdist/
Expand Down Expand Up @@ -210,7 +209,6 @@ devel/
logs/
build/
bin/
lib/
msg_gen/
srv_gen/
msg/*Action.msg
Expand Down
7 changes: 7 additions & 0 deletions dependencies.repos
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
repositories:
vortex-msgs:
type: git
url: https://github.com/vortexntnu/vortex-msgs.git
vortex-utils:
type: git
url: https://github.com/vortexntnu/vortex-utils.git
100 changes: 100 additions & 0 deletions line_detection_houghp/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,100 @@
cmake_minimum_required(VERSION 3.8)
project(line_detection_houghp)

if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 20)
endif()

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(OpenCV 4.5.4 REQUIRED)
find_package(vortex_utils REQUIRED)
find_package(vortex_utils_ros REQUIRED)
find_package(vortex_msgs REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(cv_bridge REQUIRED)
find_package(spdlog REQUIRED)
find_package(fmt REQUIRED)

include_directories(include)

set(CORE_LIB_NAME "${PROJECT_NAME}")

add_library(${CORE_LIB_NAME} SHARED
src/lib/houghp_line_detection.cpp
src/lib/utils.cpp
)

target_include_directories(${CORE_LIB_NAME}
PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>
${OpenCV_INCLUDE_DIRS}
)

ament_target_dependencies(${CORE_LIB_NAME}
vortex_utils
)

target_link_libraries(${CORE_LIB_NAME}
${OpenCV_LIBS})

set(COMPONENT_LIB_NAME "${PROJECT_NAME}_component")

add_library(${COMPONENT_LIB_NAME} SHARED
src/ros/${PROJECT_NAME}_ros.cpp
src/ros/${PROJECT_NAME}_ros_utils.cpp
)

ament_target_dependencies(${COMPONENT_LIB_NAME}
rclcpp
rclcpp_components
vortex_utils
vortex_utils_ros
vortex_msgs
cv_bridge
sensor_msgs
spdlog
fmt
)

target_link_libraries(${COMPONENT_LIB_NAME} ${PROJECT_NAME})

rclcpp_components_register_node(
${COMPONENT_LIB_NAME}
PLUGIN "LineDetectionHoughPNode"
EXECUTABLE ${PROJECT_NAME}_node
)

install(
TARGETS
${CORE_LIB_NAME}
${COMPONENT_LIB_NAME}
EXPORT export_${PROJECT_NAME}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)

install(
DIRECTORY include/
DESTINATION include
)

install(DIRECTORY
launch
config
DESTINATION share/${PROJECT_NAME}/
)

ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET)

ament_export_include_directories(include)
ament_export_libraries(${CORE_LIB_NAME})

ament_package()
108 changes: 108 additions & 0 deletions line_detection_houghp/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,108 @@
# Line Detection HoughP

## Overview

The `line_detection_houghp` package provides line detection functionality using the Probabilistic Hough Transform (HoughP) for images. It is designed to detect linear features such as pipelines, walls, and other structural elements in underwater environments.

## Architecture

The package follows the standard Vortex separation of concerns:

```
line_detection_houghp/
├── include/
│ └── line_detection_houghp/
│ ├── lib/ # Non-ROS library headers
│ │ └── houghp_line_detection.hpp
│ └── ros/ # ROS node headers
│ └── line_detection_ros.hpp
├── src/
│ ├── lib/ # Non-ROS library implementations
│ │ └── houghp_line_detection.cpp
│ └── ros/ # ROS node implementations
│ └── line_detection_ros.cpp
├── launch/
│ └── line_detection.launch.py
├── config/
│ └── line_detection_params.yaml
├── test/
│ └── test_houghp_line_detection.cpp
├── CMakeLists.txt
├── package.xml
└── README.md
```

**lib/** contains pure C++/OpenCV logic with no ROS dependencies. This makes it testable and reusable outside of ROS.

**ros/** contains the ROS 2 node that wraps the library, handling subscriptions, publishers, parameters, and message conversions.

## Topics

### Subscriptions

| Topic | Type | Description |
|-------|------|-------------|
| Input image | `sensor_msgs/msg/Image` | Input image for line detection (8-bit, single or multi-channel) |

### Publications

| Topic | Type | Modes | Description |
|-------|------|-------|-------------|
| Detected lines | `vortex_msgs/msg/LineSegment2DArray` | `standard` `visualize` `debug` | Detected line segments (Always published). |
| Color overlay | `sensor_msgs/msg/Image` (BGR, 8UC3) | `visualize` `debug` | Input color image with detected line segments drawn on top |
| Canny edge map | `sensor_msgs/msg/Image` (mono, 8UC1) | `debug` | Raw Canny edge map |
| Canny overlay | `sensor_msgs/msg/Image` (BGR, 8UC3) | `debug` | Edge map converted to BGR with detected line segments drawn on top |


## Parameters

### Canny Edge Detection

The Canny edge detector is used as a pre-processing step to extract edges before the Hough transform. It uses hysteresis thresholding with two thresholds to identify strong and weak edges.

| Parameter | Type | Description |
|-----------|------|-------------|
| `canny_low_threshold` | `int` | Low threshold for the hysteresis procedure. Edges with gradient magnitude below this are discarded. |
| `canny_high_threshold` | `int` | High threshold for the hysteresis procedure. Edges with gradient magnitude above this are always accepted. Edges between low and high are accepted only if connected to a strong edge. |
| `canny_aperture_size` | `int` | Aperture size for the Sobel operator used internally by Canny. Must be odd (3, 5, or 7). Larger values detect smoother edges. |
| `canny_L2_gradient` | `bool` | If `true`, uses the more accurate L2 norm (√(Gx² + Gy²)) for gradient magnitude instead of the default L1 norm (\|Gx\| + \|Gy\|). |

### Probabilistic Hough Transform

| Parameter | Type | Description |
|-----------|------|-------------|
| `hough_rho` | `double` | Distance resolution of the accumulator in pixels |
| `hough_theta` | `double` | Angle resolution of the accumulator in radians |
| `hough_threshold` | `int` | Accumulator threshold — minimum number of votes to accept a line |
| `min_line_length` | `double` | Minimum line length to accept (pixels). Lines shorter than this are rejected. |
| `max_line_gap` | `double` | Maximum allowed gap between points on the same line to link them into a single segment (pixels) |



> **Note:** Adjust parameters in the config YAML or via `ros2 param set` at runtime.

## Build

```bash
# Build this package and its dependencies
colcon build --packages-up-to line_detection_houghp --symlink-install
source install/setup.bash
```

## Run

```bash
# Launch the node with default parameters
ros2 launch line_detection_houghp line_detection.launch.py
```


## Theory

The [Probabilistic Hough Transform](https://docs.opencv.org/4.x/dd/d1a/group__imgproc__feature.html#ga8618180a5948286384e3b7ca02f6feeb) (`cv::HoughLinesP`) is a variant of the Standard Hough Transform that returns line segments rather than infinite lines. It works by:

1. Randomly sampling edge points from a binary image.
2. Accumulating votes in (ρ, θ) parameter space.
3. Extracting line segments that exceed the vote threshold and meet minimum length / maximum gap constraints.

Detected line segments are converted to polar (Hesse normal) form using `vortex::utils::types::LineSegment2D::polar_parametrization()` for downstream consumers.
23 changes: 23 additions & 0 deletions line_detection_houghp/config/line_detection_houghp.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
/**:
ros__parameters:
topic:
image_sub_topic: /fls_publisher/display_mono
line_segments_pub_topic: line_detection/line_segments
color_overlay_pub_topic: line_detection/visualization
canny_debug_pub_topic: line_detection/canny_image
canny_overlay_pub_topic: line_detection/canny_overlay

canny:
low_threshold: 100
high_threshold: 200
aperture_size: 3
L2_gradient: false

houghp:
rho: 1.0
theta: 0.01745329251 # pi / 180
threshold: 100
min_line_length: 20.0 # pixels
max_line_gap: 10.0 # pixels

mode: "debug" # {"standard", "visualize", "debug"}
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
#ifndef LINE_DETECTION_HOUGHP__LIB__LINE_DETECTION_HOUGHP_HPP_
#define LINE_DETECTION_HOUGHP__LIB__LINE_DETECTION_HOUGHP_HPP_

#include <opencv2/core.hpp>
#include <opencv2/imgproc.hpp>
#include <vector>
#include <vortex/utils/types.hpp>
#include "typedefs.hpp"

namespace vortex::line_detection {

class LineDetectorHoughP {
public:
explicit LineDetectorHoughP(const CannyConfig& edge_config,
const HoughPConfig& line_config);

Result detect(const cv::Mat& input_image,
DetectorMode mode = DetectorMode::standard) const;

private:
CannyConfig canny_config_;
HoughPConfig houghp_config_;

void detect_edges(const cv::Mat& input_image, cv::Mat& edge_image) const;

void detect_line_segments(const cv::Mat& edge_image,
std::vector<cv::Vec4i>& cv_lines) const;

static std::vector<vortex::utils::types::LineSegment2D> to_line_segments(
const std::vector<cv::Vec4i>& cv_lines);
};

} // namespace vortex::line_detection

#endif // LINE_DETECTION_HOUGHP__LIB__LINE_DETECTION_HOUGHP_HPP_
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
#ifndef LINE_DETECTION_HOUGHP__LIB__MODE_UTILS_HPP_
#define LINE_DETECTION_HOUGHP__LIB__MODE_UTILS_HPP_

#include <array>
#include <stdexcept>
#include <string>
#include <string_view>
#include <utility>
#include "line_detection_houghp/lib/typedefs.hpp"

namespace vortex::line_detection {

inline constexpr std::array<std::pair<std::string_view, DetectorMode>, 3>
kDetectorModeMap{{
{"standard", DetectorMode::standard},
{"visualize", DetectorMode::visualize},
{"debug", DetectorMode::debug},
}};

inline DetectorMode parse_mode(const std::string& s) {
for (const auto& [name, mode] : kDetectorModeMap) {
if (s == name)
return mode;
}
throw std::runtime_error("Invalid DetectorMode: " + s);
}

inline std::string_view to_string(DetectorMode mode) {
for (const auto& [name, m] : kDetectorModeMap) {
if (m == mode)
return name;
}
throw std::runtime_error("Unknown DetectorMode");
}

} // namespace vortex::line_detection

#endif // LINE_DETECTION_HOUGHP__LIB__MODE_UTILS_HPP_
Loading