Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
18 commits
Select commit Hold shift + click to select a range
c9d0564
[objectness] initial commit. succeeded in executing, error in https:/…
mqcmd196 Apr 5, 2022
3ec63d6
[objectness] change the way to load the training_path, remove BING pa…
mqcmd196 Apr 9, 2022
7d707f2
[objectness] rename var, add max objectness number, change init cv bi…
mqcmd196 Apr 9, 2022
2414af6
[objectness] fix coding style based on clang-format
mqcmd196 Apr 11, 2022
97801f9
[objectness] add test
mqcmd196 Apr 11, 2022
e287bc9
[objectness] don't build on OpenCV < 3.2 env
mqcmd196 Apr 11, 2022
c8bafe4
[objectness] change default objectness num, topic name
mqcmd196 Apr 12, 2022
ba92d8d
[objectness] publish debug image
mqcmd196 Apr 12, 2022
bfca234
[objectness] add default training_path arg to pass the test and add F…
mqcmd196 Apr 12, 2022
bf29e5c
[objectness] fix coding style based on clang-tidy
mqcmd196 Apr 12, 2022
42284e0
check objectness/rects, rosbag play with -r 0.5
k-okada Apr 12, 2022
9db07a1
objectness_nodelet.cpp: add img_pub_ to publish draw image, enable al…
k-okada Apr 12, 2022
6e33c63
use NOT OpenCV_VERSION VERSION_LESS 3.2 instead of OPENCV_HAVE_SALIENCY
k-okada Apr 12, 2022
4aa1388
fix for clang-tidy
k-okada Apr 12, 2022
7e250e6
use ARGS for roslaunch_add_file_check(objectness.launch)
k-okada Apr 12, 2022
c5feadd
skip roslaunch_add_file_check(objectness.launch) if OpenCV < 3.2
k-okada Apr 12, 2022
0cbd924
chown -R root $CI_SOURCE_PATH
k-okada Apr 13, 2022
6020231
Merge pull request #2 from k-okada/PR/feature/objectness-fix
mqcmd196 Apr 13, 2022
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
2 changes: 2 additions & 0 deletions .travis.sh
Original file line number Diff line number Diff line change
Expand Up @@ -163,6 +163,8 @@ elif [ "$TEST" == "clang-tidy" ]; then
run-clang-tidy -fix -p $(dirname $file)
done
travis_time_end

sudo chown -R $(whoami) $CI_SOURCE_PATH # to fix fatal: unsafe repository ('/home/runner/work/opencv_apps/opencv_apps' is owned by someone else)
git -C $CI_SOURCE_PATH --no-pager diff
git -C $CI_SOURCE_PATH diff-index --quiet HEAD -- .

Expand Down
13 changes: 12 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,7 @@ generate_dynamic_reconfigure_options(
cfg/HSVColorFilter.cfg
cfg/LabColorFilter.cfg
cfg/WatershedSegmentation.cfg
cfg/Objectness.cfg
)

## Generate messages in the 'msg' folder
Expand Down Expand Up @@ -348,6 +349,9 @@ opencv_apps_add_nodelet(simple_compressed_example src/nodelet/simple_compressed_
if(OPENCV_HAVE_OPTFLOW)
opencv_apps_add_nodelet(simple_flow src/nodelet/simple_flow_nodelet.cpp)
endif()
if(OpenCV_VERSION VERSION_GREATER "3.1") # cv::saliency::ObjectnessBING is supported since 3.2
opencv_apps_add_nodelet(objectness src/nodelet/objectness_nodelet.cpp)
endif()
# https://github.com/opencv/opencv/blob/2.4/samples/cpp/bgfg_gmg.cpp
# https://github.com/opencv/opencv/blob/2.4/samples/cpp/hybridtrackingsample.cpp
# https://github.com/opencv/opencv/blob/2.4/samples/cpp/linemod.cpp
Expand Down Expand Up @@ -387,8 +391,15 @@ 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(OpenCV_VERSION VERSION_LESS "3.2")
list(REMOVE_ITEM LAUNCH_FILES ${PROJECT_SOURCE_DIR}/launch/objectness.launch)
endif()
foreach(LAUNCH_FILE ${LAUNCH_FILES})
roslaunch_add_file_check(${LAUNCH_FILE})
set(ARGS "")
if("${LAUNCH_FILE}" STREQUAL "${CMAKE_CURRENT_SOURCE_DIR}/launch/objectness.launch")
set(ARGS "training_path:=${CMAKE_CURRENT_SOURCE_DIR}/test")
endif()
roslaunch_add_file_check(${LAUNCH_FILE} ${ARGS})
endforeach()
endif()
add_subdirectory(test)
Expand Down
44 changes: 44 additions & 0 deletions cfg/Objectness.cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
#! /usr/bin/env python
# Software License Agreement (BSD License)
#
# Copyright (c) 2022, Yoshiki Obinata.
# 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 = "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)
gen.add("nss", int_t, 0, "Size for non-maximal suppress", 2, 1, 255)
gen.add("max_objectness", int_t, 0, "Maximum number of objectness to be detected", 255, 1, 3)

exit(gen.generate(PACKAGE, "objectness", "Objectness"))
27 changes: 27 additions & 0 deletions launch/objectness.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
<?xml version="1.0" encoding="utf-8"?>
<launch>
<arg name="node_name" default="objectness" />

<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 image" />
<arg name="queue_size" default="3" doc="Specigy queue_size of input image subscribers" />

<arg name="training_path" default="" doc="The path of trained model.
Please download
https://github.com/opencv/opencv_contrib/tree/3.4/modules/saliency/samples/ObjectnessTrainedModel" />
<arg name="nss" default="2" doc="Size for non-maximal suppress" />
<arg name="max_objectness" default="10" doc="Maximum number of objectness to be detected" />

<!-- equalize_histogram.cpp -->
<node name="$(arg node_name)" pkg="opencv_apps" type="objectness" 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="training_path" value="$(arg training_path)" />
<param name="nss" value="$(arg nss)" />
<param name="max_objectness" value="$(arg max_objectness)" />
</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/objectness" type="opencv_apps::ObjectnessNodelet" base_class_type="nodelet::Nodelet">
<description>Nodelet for detecting objectness</description>
</class>

<!--
for backward compatibility, can be removed in M-turtle
-->
Expand Down
226 changes: 226 additions & 0 deletions src/nodelet/objectness_nodelet.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,226 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2022, Yoshiki Obinata.
* 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 the 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.
*********************************************************************/

#include <ros/ros.h>
#include "opencv_apps/nodelet.h"
#include <image_transport/image_transport.h>
#include <cv_bridge/cv_bridge.h>
#include <sensor_msgs/image_encodings.h>

#include <opencv2/saliency.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/imgproc/imgproc.hpp>

#include <dynamic_reconfigure/server.h>
#include "opencv_apps/ObjectnessConfig.h"
#include "opencv_apps/RectArrayStamped.h"

namespace opencv_apps
{
class ObjectnessNodelet : public opencv_apps::Nodelet
{
std::string window_name_;

image_transport::Publisher img_pub_;
image_transport::Subscriber img_sub_;
image_transport::CameraSubscriber cam_sub_;
ros::Publisher msg_pub_;

std::shared_ptr<image_transport::ImageTransport> it_;

typedef opencv_apps::ObjectnessConfig Config;
typedef dynamic_reconfigure::Server<Config> ReconfigureServer;

Config config_;
std::shared_ptr<ReconfigureServer> reconfigure_server_;

int queue_size_;
bool debug_view_;

boost::mutex mutex_;

cv::Ptr<cv::saliency::Saliency> objectnessAlgorithm;

int nss_;
std::string training_path_;
int max_objectness_;

void reconfigureCallback(Config& new_config, uint32_t level)
{
config_ = new_config;
nss_ = config_.nss;
max_objectness_ = config_.max_objectness;
}

void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
{
doWork(msg, cam_info->header.frame_id);
}

void imageCallback(const sensor_msgs::ImageConstPtr& msg)
{
doWork(msg, msg->header.frame_id);
}

void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg)
{
try
{
// declaration
std::vector<cv::Vec4i> objectness_boxes;
cv::Mat frame, debug_frame;
opencv_apps::RectArrayStamped rects;

// convert the image msg to cv object
if (msg->encoding == sensor_msgs::image_encodings::BGR8)
{
frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
}
else if (msg->encoding == sensor_msgs::image_encodings::RGB8)
{
frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::RGB8)->image;
cv::cvtColor(frame, frame, CV_RGB2BGR);
}
else if (msg->encoding == sensor_msgs::image_encodings::MONO8)
{
frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::MONO8)->image;
}
else
{
NODELET_ERROR_STREAM("Not supported image encoding: " << msg->encoding);
}

if (debug_view_)
{
cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
}
debug_frame = frame.clone();

// reconfigure
objectnessAlgorithm.dynamicCast<cv::saliency::ObjectnessBING>()->setNSS(nss_);

// detect
if (objectnessAlgorithm->computeSaliency(frame, objectness_boxes))
{
rects.header.frame_id = input_frame_from_msg; // set header
// for(const cv::Vec4i& b : objectnessBoxes_){
for (int i = 0; i < std::min((int)objectness_boxes.size(), max_objectness_); i++)
{
// array b has (minX, minY, maxX, maxY)
cv::Vec4i& b = objectness_boxes.at(i);
opencv_apps::Rect rect;
rect.x = float(b[0] + b[2]) / 2.0;
rect.y = float(b[1] + b[3]) / 2.0;
rect.width = b[2] - b[0];
rect.height = b[3] - b[1];
rects.rects.push_back(rect);
// draw rect in debug view
cv::rectangle(debug_frame, cv::Vec2i(b[0], b[1]), cv::Vec2i(b[2], b[3]), cv::Vec3i(0, 0, 255), 3);
}
// Publish the image.
sensor_msgs::Image::Ptr out_img =
cv_bridge::CvImage(msg->header, sensor_msgs::image_encodings::BGR8, debug_frame).toImageMsg();
img_pub_.publish(out_img);

// publish
msg_pub_.publish(rects);
}

// draw debug window
if (debug_view_)
{
cv::imshow(window_name_, debug_frame);
int c = cv::waitKey(1);
}
}
catch (cv::Exception& e)
{
NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
NODELET_ERROR("Please check whether you set the training path correctly at the same time");
}
}

void subscribe() // NOLINT(modernize-use-override)
{
NODELET_DEBUG("Subscribing to image topic.");
if (config_.use_camera_info)
cam_sub_ = it_->subscribeCamera("image", queue_size_, &ObjectnessNodelet::imageCallbackWithInfo, this);
else
img_sub_ = it_->subscribe("image", queue_size_, &ObjectnessNodelet::imageCallback, this);
}

void unsubscribe() // NOLINT(modernize-use-override)
{
NODELET_DEBUG("Unsubscribing from image topic.");
img_sub_.shutdown();
cam_sub_.shutdown();
}

virtual void onInit() // NOLINT(modernize-use-override)
{
Nodelet::onInit();
it_ = std::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
pnh_->param("queue_size", queue_size_, 3);
pnh_->param("debug_view", debug_view_, false);
if (debug_view_)
{
always_subscribe_ = true;
}
pnh_->getParam("training_path", training_path_);

if (training_path_.empty())
NODELET_FATAL("Please set the path to directory of training data");

window_name_ = "Objectness View";

objectnessAlgorithm = cv::saliency::ObjectnessBING::create(); // support BING

NODELET_INFO_STREAM("BING Training path: " << training_path_);
objectnessAlgorithm.dynamicCast<cv::saliency::ObjectnessBING>()->setTrainingPath(training_path_);

reconfigure_server_ = std::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
typename dynamic_reconfigure::Server<Config>::CallbackType f =
std::bind(&ObjectnessNodelet::reconfigureCallback, this, std::placeholders::_1, std::placeholders::_2);
reconfigure_server_->setCallback(f);

img_pub_ = advertiseImage(*pnh_, "image", 1);
msg_pub_ = advertise<opencv_apps::RectArrayStamped>(*pnh_, "rects", 1);

onInitPostProcess();
}
};
} // namespace opencv_apps

#include <pluginlib/class_list_macros.h>
PLUGINLIB_EXPORT_CLASS(opencv_apps::ObjectnessNodelet, nodelet::Nodelet);
Loading