Skip to content

wntdev99/v_shape_detector

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

1 Commit
 
 
 
 
 
 
 
 
 
 

Repository files navigation

v_shape_detector

A ROS 2 package that detects V-shaped targets from laser line segments and publishes the vertex pose with TF broadcasting.

Built on top of laser_line_extraction, which extracts line segments from sensor_msgs/LaserScan.


How It Works

LaserScan  →  laser_line_extraction  →  LineSegmentList  →  v_shape_detector  →  PoseStamped / TF

The detector iterates over all pairs of extracted line segments and checks whether they form a V-shape:

  1. Virtual intersection – the two lines are extended mathematically to find their crossing point (the vertex). This works even if the LiDAR misses the physical tip.
  2. Arm length filter – both arms must be within [min_arm_length, max_arm_length] and their length ratio must be below arm_length_ratio_max.
  3. Angle filter – the interior angle at the vertex must be within target_angle ± angle_tolerance.
  4. Distance filter – the vertex distance from the sensor must be within [min_vertex_distance, max_vertex_distance].
  5. Best candidate – if multiple V-shapes pass all filters, the one closest to target_angle is chosen.
  6. Pose output – the vertex position is published and a TF frame is broadcast. The x-axis of the frame points from the open end toward the vertex (approach direction).

Virtual Intersection vs. Midpoint

  ----seg_i----○
                \   ← line extended
                 ★  ← computed vertex (accurate even with a gap)
                /   ← line extended
  ----seg_j----○

Unlike a simple midpoint of the nearest endpoints, the virtual intersection correctly locates the vertex even when the LiDAR cannot scan the physical tip due to occlusion or limited resolution.


Requirements


Installation

mkdir -p ~/ros2_ws/src && cd ~/ros2_ws/src

# Install the required dependency first
git clone -b jazzy https://github.com/wntdev99/laser_line_extraction.git

# Then clone this package
git clone -b jazzy https://github.com/wntdev99/v_shape_detector.git

cd ~/ros2_ws
colcon build --packages-select laser_line_extraction v_shape_detector
source install/setup.bash

Usage

Launch with default parameters

ros2 launch v_shape_detector v_shape_detector.launch.py

Run with custom parameters

ros2 run v_shape_detector v_shape_detector_node \
  --ros-args \
  -p target_angle:=120.0 \
  -p angle_tolerance:=10.0 \
  -p max_intersection_ext:=0.3 \
  -p output_frame:=map

Topics

Subscribed

Topic Type Description
line_segments laser_line_extraction/msg/LineSegmentList Input line segments from laser_line_extraction

Published

Topic Type Description
v_shape/pose geometry_msgs/msg/PoseStamped Vertex pose in output_frame. x-axis points toward the open end.
v_shape/detected std_msgs/msg/Bool true while a V-shape is detected, false after timeout
v_shape/markers visualization_msgs/msg/MarkerArray RViz2 visualization (vertex sphere, arm lines, approach arrow)

TF Broadcast

Parent frame Child frame Description
output_frame (default: map) v_shape_vertex (configurable) Vertex pose transform

Parameters

Shape Detection

Parameter Default Description
target_angle 120.0 Target interior angle of the V (degrees)
angle_tolerance 10.0 Acceptable deviation from target_angle (degrees)
max_intersection_ext 0.3 How far to extend each segment when computing the virtual intersection, as a fraction of the segment length. 0.3 = up to 30% extension.

Arm Filters

Parameter Default Description
min_arm_length 0.15 Minimum length of each V arm (m)
max_arm_length 2.0 Maximum length of each V arm (m)
arm_length_ratio_max 3.0 Maximum ratio between the two arm lengths. Prevents very asymmetric pairs.

Vertex Distance Filters

Parameter Default Description
min_vertex_distance 0.1 Minimum distance from the sensor to the vertex (m)
max_vertex_distance 3.0 Maximum distance from the sensor to the vertex (m)

Output / TF

Parameter Default Description
output_frame "map" Frame to publish the pose and broadcast TF in. Falls back to sensor frame if TF is unavailable.
child_frame "v_shape_vertex" TF child frame name for the detected vertex
tf_timeout 0.1 TF lookup timeout (seconds)

Stability / Filtering

Parameter Default Description
detection_timeout 0.5 Seconds after the last detection before detected is set to false
position_filter_alpha 0.0 Exponential moving average coefficient for the vertex position. 0.0 = no filtering, 1.0 = instantaneous. Set to 0.30.7 for smoothing.
publish_markers true Whether to publish RViz2 visualization markers

Services

Service Type Description
~/enable std_srvs/srv/SetBool Enable or disable detection at runtime
# Disable detection
ros2 service call /v_shape_detector/enable std_srvs/srv/SetBool "{data: false}"

# Re-enable
ros2 service call /v_shape_detector/enable std_srvs/srv/SetBool "{data: true}"

Verification

# Check if the V-shape is detected
ros2 topic echo /v_shape/detected

# Watch the vertex pose
ros2 topic echo /v_shape/pose

# Check active parameters
ros2 param list /v_shape_detector
ros2 param get /v_shape_detector max_intersection_ext

RViz2 Visualization

Enable publish_markers:=true (default) and add a MarkerArray display for the /v_shape/markers topic.

Marker Color Description
Sphere (id 0) Red Detected vertex
Line strip (id 1, 2) Green V-shape arms
Arrow (id 3) Blue Approach direction (x-axis)

License

BSD

About

ROS 2 Jazzy package that detects V-shaped targets from laser line segments and broadcasts the vertex pose via TF

Resources

Stars

Watchers

Forks

Releases

No releases published

Packages

 
 
 

Contributors