Skip to content

Commit

Permalink
Add line segment detector(lsd)
Browse files Browse the repository at this point in the history
  • Loading branch information
iory committed Oct 8, 2016
1 parent 48f7688 commit b2ea66b
Show file tree
Hide file tree
Showing 7 changed files with 404 additions and 3 deletions.
12 changes: 11 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@ generate_dynamic_reconfigure_options(
#
cfg/CamShift.cfg
cfg/FBackFlow.cfg
cfg/LineSegmentDetector.cfg
cfg/LKFlow.cfg
cfg/PeopleDetect.cfg
cfg/PhaseCorr.cfg
Expand Down Expand Up @@ -88,6 +89,9 @@ catkin_package(CATKIN_DEPENDS std_msgs
include_directories(include ${catkin_INCLUDE_DIRS} ${OpenCV_INCLUDE_DIRS})

## Declare a cpp library
if(OpenCV_VERSION VERSION_GREATER "2.9.9")
list(APPEND ${PROJECT_NAME}_EXTRA_FILES src/nodelet/line_segment_detector_nodelet.cpp)
endif()
if(OPENCV_HAVE_OPTFLOW)
list(APPEND ${PROJECT_NAME}_EXTRA_FILES src/nodelet/simple_flow_nodelet.cpp)
endif()
Expand Down Expand Up @@ -259,7 +263,9 @@ opencv_apps_add_nodelet(fback_flow fback_flow/fback_flow src/nodelet/fback_flow_
# ./letter_recog.cpp
opencv_apps_add_nodelet(lk_flow lk_flow/lk_flow src/nodelet/lk_flow_nodelet.cpp) # ./lkdemo.cpp
# ./logistic_regression.cpp
# ./lsd_lines.cpp
if(OpenCV_VERSION VERSION_GREATER "2.9.9")
opencv_apps_add_nodelet(line_segment_detector line_segment_detector/line_segment_detector src/nodelet/line_segment_detector_nodelet.cpp) # ./lsd_lines.cpp
endif()
# ./mask_tmpl.cpp
# ./matchmethod_orb_akaze_brisk.cpp
# ./minarea.cpp
Expand Down Expand Up @@ -339,7 +345,11 @@ if(CATKIN_ENABLE_TESTING)
message(WARNING "roslaunch_add_file check fails with unsupported doc attributes ${roslaunch_VERSION}")
else()
file(GLOB LAUNCH_FILES launch/*.launch)
if(NOT (TARGET line_segment_detector_exe))
list(REMOVE_ITEM LAUNCH_FILES launch/line_segment_detector.launch)
endif()
foreach(LAUNCH_FILE ${LAUNCH_FILES})
message(STATUS "${LAUNCH_FILE}")
roslaunch_add_file_check(${LAUNCH_FILE})
endforeach()
endif()
Expand Down
55 changes: 55 additions & 0 deletions cfg/LineSegmentDetector.cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
#! /usr/bin/env python
# Software License Agreement (BSD License)
#
# Copyright (c) 2016, JSK Lab.
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * Redistributions in binary form must reproduce the above
# copyright notice, this list of conditions and the following
# disclaimer in the documentation and/or other materials provided
# with the distribution.
# * Neither the name of Kei Okada nor the names of its
# contributors may be used to endorse or promote products derived
# from this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.

PACKAGE='line_segment_detector'

from dynamic_reconfigure.parameter_generator_catkin import *

gen = ParameterGenerator()
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)

lsd_refine_type = gen.enum([ gen.const("REFINE_NONE", int_t, 0, "No refinement applied"),
gen.const("REFINE_STD", int_t, 1, "Standard refinement is applied. E.g. breaking arches into smaller straighter line approximations."),
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."),
], "An enum for Line Segment Detector Modes")
gen.add("lsd_refine_type", int_t, 0, "Line Segment Detector Modes", 0, 0, 2, edit_method=lsd_refine_type)
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);
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);
gen.add("lsd_quant", double_t, 0, "Bound to the quantization error on the gradient norm", 2.0, 0.0, 100.0);
gen.add("lsd_angle_threshold", double_t, 0, "Gradient angle tolerance in degrees", 22.5, 0.1, 179.0);
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);
gen.add("lsd_density_threshold", double_t, 0, "Minimal density of aligned region points in the enclosing rectangle", 0.7, 0.0, 0.9);
gen.add("lsd_n_bins", int_t, 0, "Number of bins in pseudo-ordering of gradient modulus", 1024, 1, 10000)
gen.add("lsd_line_length_threshold", double_t, 0, "Threshold of line length.", 100.0, 0.0, 1000.0)

exit(gen.generate(PACKAGE, "line_segment_detector", "LineSegmentDetector"))
34 changes: 34 additions & 0 deletions launch/line_segment_detector.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
<launch>
<arg name="node_name" default="line_segment_detector" />

<arg name="image" default="image" doc="The image topic. Should be remapped to the name of the real image topic." />

<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." />
<arg name="debug_view" default="true" doc="Specify whether the node displays a window to show edge image" />

<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."/>
<arg name="lsd_scale" default="0.8" doc="The scale of the image that will be used to find the lines. Range (0..1]" />
<arg name="lsd_sigma_scale" default="0.6" doc="Sigma for Gaussian filter. It is computed as sigma = _sigma_scale/_scale" />
<arg name="lsd_quant" default="2.0" doc="Bound to the quantization error on the gradient norm" />
<arg name="lsd_angle_threshold" default="22.5" doc="Gradient angle tolerance in degrees" />
<arg name="lsd_log_eps" default="0" doc="Detection threshold: -log10(NFA) > log_eps. Used only when advancent refinement is chosen" />
<arg name="lsd_density_threshold" default="0.3" doc="Minimal density of aligned region points in the enclosing rectangle" />
<arg name="lsd_n_bins" default="1024" doc="Number of bins in pseudo-ordering of gradient modulus" />
<arg name="lsd_line_length_threshold" default="0.0" doc="Threshold of line length" />

<!-- line_segment_detector.cpp -->
<node name="$(arg node_name)" pkg="opencv_apps" type="line_segment_detector" >
<remap from="image" to="$(arg image)" />
<param name="use_camera_info" value="$(arg use_camera_info)" />
<param name="debug_view" value="$(arg debug_view)" />
<param name="lsd_refine_type" value="$(arg lsd_refine_type)" />
<param name="lsd_scale" value="$(arg lsd_scale)" />
<param name="lsd_sigma_scale" value="$(arg lsd_sigma_scale)" />
<param name="lsd_quant" value="$(arg lsd_quant)" />
<param name="lsd_angle_threshold" value="$(arg lsd_angle_threshold)" />
<param name="lsd_log_eps" value="$(arg lsd_log_eps)" />
<param name="lsd_density_threshold" value="$(arg lsd_density_threshold)" />
<param name="lsd_n_bins" value="$(arg lsd_n_bins)" />
<param name="lsd_line_length_threshold" value="$(arg lsd_line_length_threshold)" />
</node>
</launch>
4 changes: 4 additions & 0 deletions nodelet_plugins.xml
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,10 @@
<description>Nodelet to demonstrates dense optical flow algorithm by Gunnar Farneback</description>
</class>

<class name="line_segment_detector/line_segment_detector" type="line_segment_detector::LineSegmentDetectorNodelet" base_class_type="nodelet::Nodelet">
<description>Nodelet to detector line segments</description>
</class>

<class name="lk_flow/lk_flow" type="lk_flow::LKFlowNodelet" base_class_type="nodelet::Nodelet">
<description>Nodelet to calculate Lukas-Kanade optical flow</description>
</class>
Expand Down
Loading

0 comments on commit b2ea66b

Please sign in to comment.