Skip to content

Commit 31df0c7

Browse files
committed
Add line segment detector(lsd)
1 parent 650aeb2 commit 31df0c7

File tree

7 files changed

+409
-5
lines changed

7 files changed

+409
-5
lines changed

CMakeLists.txt

Lines changed: 15 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,9 @@ message(STATUS "OpenCV Components: ${OpenCV_LIB_COMPONENTS}")
99
if(OpenCV_VERSION VERSION_LESS "3.0" OR TARGET opencv_optflow)
1010
set(OPENCV_HAVE_OPTFLOW TRUE)
1111
endif()
12+
if(TARGET opencv_line_descriptor)
13+
set(OPENCV_HAVE_LINE_DESCRIPTOR TRUE)
14+
endif()
1215
# Supporting CompressedImage in cv_bridge has been started from 1.11.9 (2015-11-29)
1316
# note : hydro 1.10.18, indigo : 1.11.13 ...
1417
# https://github.com/ros-perception/vision_opencv/pull/70
@@ -37,6 +40,7 @@ generate_dynamic_reconfigure_options(
3740
#
3841
cfg/CamShift.cfg
3942
cfg/FBackFlow.cfg
43+
cfg/LineSegmentDetector.cfg
4044
cfg/LKFlow.cfg
4145
cfg/PeopleDetect.cfg
4246
cfg/PhaseCorr.cfg
@@ -101,6 +105,9 @@ catkin_package(CATKIN_DEPENDS std_msgs
101105
include_directories(include ${catkin_INCLUDE_DIRS} ${OpenCV_INCLUDE_DIRS})
102106

103107
## Declare a cpp library
108+
if(OPENCV_HAVE_LINE_DESCRIPTOR)
109+
list(APPEND ${PROJECT_NAME}_EXTRA_FILES src/nodelet/line_segment_detector_nodelet.cpp)
110+
endif()
104111
if(OPENCV_HAVE_OPTFLOW)
105112
list(APPEND ${PROJECT_NAME}_EXTRA_FILES src/nodelet/simple_flow_nodelet.cpp)
106113
endif()
@@ -274,7 +281,9 @@ opencv_apps_add_nodelet(fback_flow fback_flow/fback_flow src/nodelet/fback_flow_
274281
# ./letter_recog.cpp
275282
opencv_apps_add_nodelet(lk_flow lk_flow/lk_flow src/nodelet/lk_flow_nodelet.cpp) # ./lkdemo.cpp
276283
# ./logistic_regression.cpp
277-
# ./lsd_lines.cpp
284+
if(OPENCV_HAVE_LINE_DESCRIPTOR)
285+
opencv_apps_add_nodelet(line_segment_detector line_segment_detector/line_segment_detector src/nodelet/line_segment_detector_nodelet.cpp) # ./lsd_lines.cpp
286+
endif()
278287
# ./mask_tmpl.cpp
279288
# ./matchmethod_orb_akaze_brisk.cpp
280289
# ./minarea.cpp
@@ -355,7 +364,11 @@ if(CATKIN_ENABLE_TESTING)
355364
else()
356365
file(GLOB LAUNCH_FILES launch/*.launch)
357366
foreach(LAUNCH_FILE ${LAUNCH_FILES})
358-
roslaunch_add_file_check(${LAUNCH_FILE})
367+
if(NOT OPENCV_HAVE_LINE_DESCRIPTOR AND "${LAUNCH_FILE}" MATCHES launch/line_segment_detector.launch)
368+
else()
369+
message(STATUS "${LAUNCH_FILE}")
370+
roslaunch_add_file_check(${LAUNCH_FILE})
371+
endif()
359372
endforeach()
360373
endif()
361374
add_subdirectory(test)

cfg/LineSegmentDetector.cfg

Lines changed: 55 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,55 @@
1+
#! /usr/bin/env python
2+
# Software License Agreement (BSD License)
3+
#
4+
# Copyright (c) 2016, JSK Lab.
5+
# All rights reserved.
6+
#
7+
# Redistribution and use in source and binary forms, with or without
8+
# modification, are permitted provided that the following conditions
9+
# are met:
10+
#
11+
# * Redistributions of source code must retain the above copyright
12+
# notice, this list of conditions and the following disclaimer.
13+
# * Redistributions in binary form must reproduce the above
14+
# copyright notice, this list of conditions and the following
15+
# disclaimer in the documentation and/or other materials provided
16+
# with the distribution.
17+
# * Neither the name of Kei Okada nor the names of its
18+
# contributors may be used to endorse or promote products derived
19+
# from this software without specific prior written permission.
20+
#
21+
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22+
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23+
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24+
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25+
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26+
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27+
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28+
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29+
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30+
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31+
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32+
# POSSIBILITY OF SUCH DAMAGE.
33+
34+
PACKAGE='line_segment_detector'
35+
36+
from dynamic_reconfigure.parameter_generator_catkin import *
37+
38+
gen = ParameterGenerator()
39+
gen.add("use_camera_info", bool_t, 0, "Indicates that the camera_info topic should be subscribed to to get the default input_frame_id. Otherwise the frame from the image message will be used.", True)
40+
41+
lsd_refine_type = gen.enum([ gen.const("REFINE_NONE", int_t, 0, "No refinement applied"),
42+
gen.const("REFINE_STD", int_t, 1, "Standard refinement is applied. E.g. breaking arches into smaller straighter line approximations."),
43+
gen.const("REFINE_ADV", int_t, 2, "Advanced refinement. Number of false alarms is calculated, lines are refined through increase of precision, decrement in size, etc."),
44+
], "An enum for Line Segment Detector Modes")
45+
gen.add("lsd_refine_type", int_t, 0, "Line Segment Detector Modes", 0, 0, 2, edit_method=lsd_refine_type)
46+
gen.add("lsd_scale", double_t, 0, "The scale of the image that will be used to find the lines. Range (0..1]", 0.8, 0.1, 1.0);
47+
gen.add("lsd_sigma_scale", double_t, 0, "Sigma for Gaussian filter. It is computed as sigma = _sigma_scale/_scale", 0.6, 0.1, 10.0);
48+
gen.add("lsd_quant", double_t, 0, "Bound to the quantization error on the gradient norm", 2.0, 0.0, 100.0);
49+
gen.add("lsd_angle_threshold", double_t, 0, "Gradient angle tolerance in degrees", 22.5, 0.1, 179.0);
50+
gen.add("lsd_log_eps", double_t, 0, "Detection threshold: -log10(NFA) > log_eps. Used only when advancent refinement is chosen", 0.0, 0.0, 360.0);
51+
gen.add("lsd_density_threshold", double_t, 0, "Minimal density of aligned region points in the enclosing rectangle", 0.7, 0.0, 0.9);
52+
gen.add("lsd_n_bins", int_t, 0, "Number of bins in pseudo-ordering of gradient modulus", 1024, 1, 10000)
53+
gen.add("lsd_line_length_threshold", double_t, 0, "Threshold of line length.", 100.0, 0.0, 1000.0)
54+
55+
exit(gen.generate(PACKAGE, "line_segment_detector", "LineSegmentDetector"))
Lines changed: 34 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,34 @@
1+
<launch>
2+
<arg name="node_name" default="line_segment_detector" />
3+
4+
<arg name="image" default="image" doc="The image topic. Should be remapped to the name of the real image topic." />
5+
6+
<arg name="use_camera_info" default="false" doc="Indicates that the camera_info topic should be subscribed to to get the default input_frame_id. Otherwise the frame from the image message will be used." />
7+
<arg name="debug_view" default="true" doc="Specify whether the node displays a window to show edge image" />
8+
9+
<arg name="lsd_refine_type" default="2" doc="Line Segment Detector Modes. 0: No refinement applied, 1: Standard refinement is applied, 2, Advanced refinement is applied."/>
10+
<arg name="lsd_scale" default="0.8" doc="The scale of the image that will be used to find the lines. Range (0..1]" />
11+
<arg name="lsd_sigma_scale" default="0.6" doc="Sigma for Gaussian filter. It is computed as sigma = _sigma_scale/_scale" />
12+
<arg name="lsd_quant" default="2.0" doc="Bound to the quantization error on the gradient norm" />
13+
<arg name="lsd_angle_threshold" default="22.5" doc="Gradient angle tolerance in degrees" />
14+
<arg name="lsd_log_eps" default="0" doc="Detection threshold: -log10(NFA) > log_eps. Used only when advancent refinement is chosen" />
15+
<arg name="lsd_density_threshold" default="0.3" doc="Minimal density of aligned region points in the enclosing rectangle" />
16+
<arg name="lsd_n_bins" default="1024" doc="Number of bins in pseudo-ordering of gradient modulus" />
17+
<arg name="lsd_line_length_threshold" default="0.0" doc="Threshold of line length" />
18+
19+
<!-- line_segment_detector.cpp -->
20+
<node name="$(arg node_name)" pkg="opencv_apps" type="line_segment_detector" >
21+
<remap from="image" to="$(arg image)" />
22+
<param name="use_camera_info" value="$(arg use_camera_info)" />
23+
<param name="debug_view" value="$(arg debug_view)" />
24+
<param name="lsd_refine_type" value="$(arg lsd_refine_type)" />
25+
<param name="lsd_scale" value="$(arg lsd_scale)" />
26+
<param name="lsd_sigma_scale" value="$(arg lsd_sigma_scale)" />
27+
<param name="lsd_quant" value="$(arg lsd_quant)" />
28+
<param name="lsd_angle_threshold" value="$(arg lsd_angle_threshold)" />
29+
<param name="lsd_log_eps" value="$(arg lsd_log_eps)" />
30+
<param name="lsd_density_threshold" value="$(arg lsd_density_threshold)" />
31+
<param name="lsd_n_bins" value="$(arg lsd_n_bins)" />
32+
<param name="lsd_line_length_threshold" value="$(arg lsd_line_length_threshold)" />
33+
</node>
34+
</launch>

nodelet_plugins.xml

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -59,6 +59,10 @@
5959
<description>Nodelet to demonstrates dense optical flow algorithm by Gunnar Farneback</description>
6060
</class>
6161

62+
<class name="line_segment_detector/line_segment_detector" type="line_segment_detector::LineSegmentDetectorNodelet" base_class_type="nodelet::Nodelet">
63+
<description>Nodelet to detector line segments</description>
64+
</class>
65+
6266
<class name="lk_flow/lk_flow" type="lk_flow::LKFlowNodelet" base_class_type="nodelet::Nodelet">
6367
<description>Nodelet to calculate Lukas-Kanade optical flow</description>
6468
</class>

0 commit comments

Comments
 (0)