Skip to content
Open
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
44 changes: 44 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,8 @@ if(cv_bridge_VERSION VERSION_LESS "1.11.13")
add_definitions("-DCV_BRIDGE_CVT_COLOR_FOR_DISPLAY_OPTION_IS_NOT_SUPPORTED")
endif()

catkin_python_setup()

# generate the dynamic_reconfigure config file
generate_dynamic_reconfigure_options(
cfg/DiscreteFourierTransform.cfg
Expand Down Expand Up @@ -66,6 +68,8 @@ generate_dynamic_reconfigure_options(
cfg/HSVColorFilter.cfg
cfg/LabColorFilter.cfg
cfg/WatershedSegmentation.cfg
#
cfg/Tracking.cfg
)

## Generate messages in the 'msg' folder
Expand Down Expand Up @@ -107,6 +111,7 @@ add_message_files(
add_service_files(
FILES
FaceRecognitionTrain.srv
SetImages.srv
)

## Generate added messages and services with any dependencies listed here
Expand Down Expand Up @@ -327,6 +332,36 @@ opencv_apps_add_nodelet(segment_objects src/nodelet/segment_objects_nodelet.cpp)
# ./videostab.cpp
opencv_apps_add_nodelet(watershed_segmentation src/nodelet/watershed_segmentation_nodelet.cpp) # ./watershed.cpp

# contrib modules (https://docs.opencv.org/4.x/d3/d81/tutorial_contrib_root.html)
# alphamat. Information Flow Alpha Matting
# aruco. ArUco marker detection (aruco module)
# barcode. Tutorials for barcode module
# bgsegm. Tutorials for bgsegm module
# bioinspired. Discovering the human retina and its use for image processing
# ccalib. Multi-camera Calibration
# ccalib. Omnidirectional Camera Calibration
# cvv. Interactive Visual Debugging of Computer Vision applications
# dnn_objdetect. Object Detection using CNNs
# dnn_superres. Super Resolution using CNNs
# face. Tutorials for face module
# face. Tutorial on Facial Landmark Detector API
# fuzzy. Fuzzy image processing tutorials
# hdf. The Hierarchical Data Format (hdf) I/O
# julia. Introduction to Julia OpenCV Binding
# line_descriptor. Line Features Tutorial
# mcc. Color Correction Model
# mcc. ColorChecker Detection
# phase_unwrapping. Phase Unwrapping tutorial
# sfm. Structure From Motion
# stereo. Quasi Dense Stereo (stereo module)
# structured_light. Structured Light tutorials
# text. Text module
# tracking. Customizing the CN Tracker
if(OpenCV_VERSION VERSION_GREATER "4.0")
opencv_apps_add_nodelet(tracking src/nodelet/tracking_nodelet.cpp) # tracking. Introduction to OpenCV Tracker
endif()
# tracking. Using MultiTracker

# ros examples
opencv_apps_add_nodelet(simple_example src/nodelet/simple_example_nodelet.cpp)
opencv_apps_add_nodelet(simple_compressed_example src/nodelet/simple_compressed_example_nodelet.cpp)
Expand Down Expand Up @@ -379,6 +414,12 @@ install(DIRECTORY launch test scripts
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
USE_SOURCE_PERMISSIONS)

file(GLOB PROGRAM_FILES scripts/*.py)
catkin_install_python(PROGRAMS
"${PROGRAM_FILES}"
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

## test
if(CATKIN_ENABLE_TESTING)
find_package(rostest REQUIRED)
Expand All @@ -387,6 +428,9 @@ 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 OpenCV_VERSION VERSION_GREATER "4.0")
list(REMOVE_ITEM LAUNCH_FILES ${CMAKE_CURRENT_SOURCE_DIR}/launch/tracking.launch)
endif()
foreach(LAUNCH_FILE ${LAUNCH_FILES})
roslaunch_add_file_check(${LAUNCH_FILE})
endforeach()
Expand Down
23 changes: 23 additions & 0 deletions cfg/Tracking.cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
#! /usr/bin/env python

PACKAGE = "opencv_apps"

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.", False)

tracking_algorithm = gen.enum([gen.const("MIL", int_t, 0, "MIL (Multiple Instance Learning) tracker"),
gen.const("BOOSTING", int_t, 1, "On-line version of the AdaBoost tracker"),
gen.const("MEDIANFLOW", int_t, 2, "Median Flow tracker"),
gen.const("TLD", int_t, 3, "TLD (Tracking, learning and detection) tracker"),
gen.const("KCF", int_t, 4, "KCF (Kernelized Correlation Filter) tracker"),
gen.const("GOTURN", int_t, 5, "GOTURN (Generic Object Tracking Using Regression Networks) tracker"),
gen.const("MOSSE", int_t, 6, "MOSSE (Minimum Output Sum of Squared Error) tracker"),],
"An enum for Tracking Algorithms")

gen.add("tracking_algorithm", int_t, 0, "Tracking Algorithm", 4, 0, 6, edit_method=tracking_algorithm)

exit(gen.generate(PACKAGE, "tracking", "Tracking"))

20 changes: 20 additions & 0 deletions launch/tracking.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
<launch>
<arg name="node_name" default="tracking" />
<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="queue_size" default="3" doc="Specigy queue_size of input image subscribers" />

<arg name="tracking_algorithm" default="4" doc="Tracking algorithm 0: MIL, 1: Boosting, 2: Medianflow, 3: TLD, 4: KCF, 5: GOTURN, 6: MOSSE" />

<!-- threshold.cpp -->
<node name="$(arg node_name)" pkg="opencv_apps" type="tracking" output="screen">
<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="queue_size" value="$(arg queue_size)" />
<param name="tracking_algorithm" value="$(arg tracking_algorithm)" />
</node>

</launch>
4 changes: 4 additions & 0 deletions nodelet_plugins.xml
Original file line number Diff line number Diff line change
Expand Up @@ -127,6 +127,10 @@
<description>Nodelet for histogram equalization</description>
</class>

<class name="opencv_apps/tracking" type="opencv_apps::TrackingNodelet" base_class_type="nodelet::Nodelet">
<description>Nodelet for tracking</description>
</class>

<!--
for backward compatibility, can be removed in M-turtle
-->
Expand Down
32 changes: 21 additions & 11 deletions package.xml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<package>
<package format="3">
<name>opencv_apps</name>
<version>2.0.2</version>
<description>
Expand All @@ -18,6 +18,16 @@

<buildtool_depend>catkin</buildtool_depend>

<buildtool_depend condition="$ROS_PYTHON_VERSION == 2">python-setuptools</buildtool_depend>
<buildtool_depend condition="$ROS_PYTHON_VERSION == 3">python3-setuptools</buildtool_depend>

<build_export_depend>dynamic_reconfigure</build_export_depend>
<build_export_depend>nodelet</build_export_depend>
<build_export_depend>roscpp</build_export_depend>
<build_export_depend>sensor_msgs</build_export_depend>
<build_export_depend>std_msgs</build_export_depend>
<build_export_depend>std_srvs</build_export_depend>

<build_depend>cv_bridge</build_depend>
<build_depend>dynamic_reconfigure</build_depend>
<build_depend>g++-static</build_depend>
Expand All @@ -29,16 +39,16 @@
<build_depend>std_msgs</build_depend>
<build_depend>std_srvs</build_depend>

<run_depend>cv_bridge</run_depend>
<run_depend>dynamic_reconfigure</run_depend>
<run_depend>image_transport</run_depend>
<run_depend>image_view</run_depend>
<run_depend>message_runtime</run_depend>
<run_depend>nodelet</run_depend>
<run_depend>roscpp</run_depend>
<run_depend>sensor_msgs</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>std_srvs</run_depend>
<exec_depend>cv_bridge</exec_depend>
<exec_depend>dynamic_reconfigure</exec_depend>
<exec_depend>image_transport</exec_depend>
<exec_depend>image_view</exec_depend>
<exec_depend>message_runtime</exec_depend>
<exec_depend>nodelet</exec_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>sensor_msgs</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>std_srvs</exec_depend>

<test_depend>roslaunch</test_depend>
<test_depend>rostest</test_depend>
Expand Down
98 changes: 98 additions & 0 deletions scripts/set_image.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,98 @@
#! /usr/bin/env python
# Software License Agreement (BSD License)
#
# Copyright (c) 2022, Kei Okada
# 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.


from __future__ import print_function

try:
input = raw_input
except:
pass

import argparse
import cv2
import cv_bridge
import os
import sys
import time
import rospy

from opencv_apps.msg import Rect
from opencv_apps.srv import SetImages, SetImagesRequest


if __name__ == '__main__':
parser = argparse.ArgumentParser(description='Send ROI (and template image) to the tracker')
parser.add_argument('center_x', type=int, help='X coordinates of center of ROI')
parser.add_argument('center_y', type=int, help='Y coordinates of center of ROI')
parser.add_argument('width', type=int, help='Width of ROI')
parser.add_argument('height', type=int, help='Height of ROI')
parser.add_argument('image_file_name', nargs='?', help='File name of template image')
parser.add_argument('--debug-view', action='store_true', help='Display input_file with ROI')
args, unknown = parser.parse_known_args();

rospy.init_node("set_image")
rospy.wait_for_service('set_roi')
set_roi = rospy.ServiceProxy('set_roi', SetImages)

req = SetImagesRequest()

# set roi
rospy.loginfo("Set ROI({},{}, {}, {})".format(args.center_x, args.center_y, args.width, args.height))
rect = Rect(x=args.center_x, y=args.center_y, width=args.width, height=args.height)
req.rects=[rect]

# set images
if args.image_file_name:
fname = args.image_file_name
if os.path.exists(fname):
im = cv2.imread(fname)
im_msg = cv_bridge.CvBridge().cv2_to_imgmsg(im, "bgr8")
rospy.loginfo("Set Image{} from {}".format(im.shape, fname))
req.images = [im_msg]
if args.debug_view:
cv2.rectangle(im,
(int(rect.x - rect.width/2), int(rect.y - rect.height/2)),
(int(rect.x + rect.width/2), int(rect.y + rect.height/2)),
(0, 255, 0), 3)
cv2.imshow('template image', im)
cv2.waitKey(100)
else:
rospy.logerr("{} not found exitting".format(fname))
sys.exit(1)

ret = set_roi(images=req.images, rects=req.rects)
rospy.loginfo("'set_roi' returns\n {}".format(ret))
if args.debug_view:
time.sleep(2)
cv2.destroyAllWindows()
14 changes: 14 additions & 0 deletions setup.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
import catkin_pkg
from distutils.version import LooseVersion
if LooseVersion(catkin_pkg.__version__) <= LooseVersion('0.4.8'):
# on hydro we need to use distutils
from distutils.core import setup
else:
from setuptools import setup
from catkin_pkg.python_setup import generate_distutils_setup

d = generate_distutils_setup(
packages=['opencv_apps'],
package_dir={'': 'src'},
)
setup(**d)
Loading