Skip to content

Commit

Permalink
fix format by clang-format
Browse files Browse the repository at this point in the history
  • Loading branch information
k-okada committed Apr 21, 2019
1 parent 1557e0a commit a8ce75e
Show file tree
Hide file tree
Showing 29 changed files with 2,826 additions and 2,398 deletions.
492 changes: 229 additions & 263 deletions include/opencv_apps/nodelet.h

Large diffs are not rendered by default.

369 changes: 191 additions & 178 deletions src/nodelet/adding_images_nodelet.cpp

Large diffs are not rendered by default.

192 changes: 101 additions & 91 deletions src/nodelet/camshift_nodelet.cpp

Large diffs are not rendered by default.

218 changes: 125 additions & 93 deletions src/nodelet/color_filter_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,13 +46,15 @@
#include "opencv_apps/HLSColorFilterConfig.h"
#include "opencv_apps/HSVColorFilterConfig.h"

namespace color_filter {
namespace color_filter
{
class RGBColorFilterNodelet;
class HLSColorFilterNodelet;
class HSVColorFilterNodelet;
}

namespace opencv_apps {
namespace opencv_apps
{
class RGBColorFilter;
class HLSColorFilter;
class HSVColorFilter;
Expand Down Expand Up @@ -84,11 +86,11 @@ class ColorFilterNodelet : public opencv_apps::Nodelet

boost::mutex mutex_;

virtual void reconfigureCallback(Config &new_config, uint32_t level) = 0;
virtual void reconfigureCallback(Config& new_config, uint32_t level) = 0;

virtual void filter(const cv::Mat& input_image, cv::Mat& output_image) = 0;

const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
const std::string& frameWithDefault(const std::string& frame, const std::string& image_frame)
{
if (frame.empty())
return image_frame;
Expand All @@ -109,38 +111,42 @@ class ColorFilterNodelet : public opencv_apps::Nodelet
{
// Work on the image.
try
{
// Convert the image into something opencv can handle.
cv::Mat frame = cv_bridge::toCvShare(image_msg, sensor_msgs::image_encodings::BGR8)->image;
{
// Convert the image into something opencv can handle.
cv::Mat frame = cv_bridge::toCvShare(image_msg, sensor_msgs::image_encodings::BGR8)->image;

// Do the work
cv::Mat out_frame;
filter(frame, out_frame);
// Do the work
cv::Mat out_frame;
filter(frame, out_frame);

/// Create window
if( debug_view_) {
cv::namedWindow( window_name_, cv::WINDOW_AUTOSIZE );
}

std::string new_window_name;
/// Create window
if (debug_view_)
{
cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
}

if( debug_view_) {
if (window_name_ != new_window_name) {
cv::destroyWindow(window_name_);
window_name_ = new_window_name;
}
cv::imshow( window_name_, out_frame );
int c = cv::waitKey(1);
}
std::string new_window_name;

// Publish the image.
sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(image_msg->header, sensor_msgs::image_encodings::MONO8, out_frame).toImageMsg();
img_pub_.publish(out_img);
}
catch (cv::Exception &e)
if (debug_view_)
{
NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
if (window_name_ != new_window_name)
{
cv::destroyWindow(window_name_);
window_name_ = new_window_name;
}
cv::imshow(window_name_, out_frame);
int c = cv::waitKey(1);
}

// Publish the image.
sensor_msgs::Image::Ptr out_img =
cv_bridge::CvImage(image_msg->header, sensor_msgs::image_encodings::MONO8, out_frame).toImageMsg();
img_pub_.publish(out_img);
}
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);
}
}
void subscribe()
{
Expand All @@ -167,15 +173,16 @@ class ColorFilterNodelet : public opencv_apps::Nodelet
pnh_->param("queue_size", queue_size_, 3);
pnh_->param("debug_view", debug_view_, false);

if (debug_view_) {
if (debug_view_)
{
always_subscribe_ = true;
}

window_name_ = "ColorFilter Demo";

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

img_pub_ = advertiseImage(*pnh_, "image", 1);
Expand All @@ -184,8 +191,8 @@ class ColorFilterNodelet : public opencv_apps::Nodelet
}
};

class RGBColorFilterNodelet
: public ColorFilterNodelet<opencv_apps::RGBColorFilterConfig> {
class RGBColorFilterNodelet : public ColorFilterNodelet<opencv_apps::RGBColorFilterConfig>
{
protected:
int r_min_;
int r_max_;
Expand All @@ -194,8 +201,8 @@ class RGBColorFilterNodelet
int g_min_;
int g_max_;

virtual void reconfigureCallback(opencv_apps::RGBColorFilterConfig& config,
uint32_t level) {
virtual void reconfigureCallback(opencv_apps::RGBColorFilterConfig& config, uint32_t level)
{
boost::mutex::scoped_lock lock(mutex_);
config_ = config;
r_max_ = config.r_limit_max;
Expand All @@ -207,21 +214,26 @@ class RGBColorFilterNodelet
updateCondition();
}

virtual void updateCondition() {
if (r_max_ < r_min_) std::swap(r_max_, r_min_);
if (g_max_ < g_min_) std::swap(g_max_, g_min_);
if (b_max_ < b_min_) std::swap(b_max_, b_min_);
virtual void updateCondition()
{
if (r_max_ < r_min_)
std::swap(r_max_, r_min_);
if (g_max_ < g_min_)
std::swap(g_max_, g_min_);
if (b_max_ < b_min_)
std::swap(b_max_, b_min_);
lower_color_range_ = cv::Scalar(b_min_, g_min_, r_min_);
upper_color_range_ = cv::Scalar(b_max_, g_max_, r_max_);
}

virtual void filter(const cv::Mat& input_image, cv::Mat& output_image) {
cv::inRange(input_image, lower_color_range_, upper_color_range_,
output_image);
virtual void filter(const cv::Mat& input_image, cv::Mat& output_image)
{
cv::inRange(input_image, lower_color_range_, upper_color_range_, output_image);
}

protected:
virtual void onInit() {
virtual void onInit()
{
r_max_ = 255;
r_min_ = 0;
g_max_ = 255;
Expand All @@ -233,11 +245,11 @@ class RGBColorFilterNodelet
}
friend class color_filter::RGBColorFilterNodelet;
friend class color_filter::HLSColorFilterNodelet;
friend class color_filter::HSVColorFilterNodelet;
friend class color_filter::HSVColorFilterNodelet;
};

class HLSColorFilterNodelet
: public ColorFilterNodelet<opencv_apps::HLSColorFilterConfig> {
class HLSColorFilterNodelet : public ColorFilterNodelet<opencv_apps::HLSColorFilterConfig>
{
protected:
int h_min_;
int h_max_;
Expand All @@ -246,8 +258,8 @@ class HLSColorFilterNodelet
int l_min_;
int l_max_;

virtual void reconfigureCallback(opencv_apps::HLSColorFilterConfig& config,
uint32_t level) {
virtual void reconfigureCallback(opencv_apps::HLSColorFilterConfig& config, uint32_t level)
{
boost::mutex::scoped_lock lock(mutex_);
config_ = config;
h_max_ = config.h_limit_max;
Expand All @@ -259,24 +271,30 @@ class HLSColorFilterNodelet
updateCondition();
}

virtual void updateCondition() {
if (s_max_ < s_min_) std::swap(s_max_, s_min_);
if (l_max_ < l_min_) std::swap(l_max_, l_min_);
lower_color_range_ = cv::Scalar(h_min_/2, l_min_, s_min_, 0);
upper_color_range_ = cv::Scalar(h_max_/2, l_max_, s_max_, 0);
virtual void updateCondition()
{
if (s_max_ < s_min_)
std::swap(s_max_, s_min_);
if (l_max_ < l_min_)
std::swap(l_max_, l_min_);
lower_color_range_ = cv::Scalar(h_min_ / 2, l_min_, s_min_, 0);
upper_color_range_ = cv::Scalar(h_max_ / 2, l_max_, s_max_, 0);
}

virtual void filter(const cv::Mat& input_image, cv::Mat& output_image) {
virtual void filter(const cv::Mat& input_image, cv::Mat& output_image)
{
cv::Mat hls_image;
cv::cvtColor(input_image, hls_image, cv::COLOR_BGR2HLS);
if ( lower_color_range_[0] < upper_color_range_[0] ) {
cv::inRange(hls_image, lower_color_range_, upper_color_range_,
output_image);
}else {
cv::Scalar lower_color_range_0 = cv::Scalar( 0, l_min_, s_min_, 0);
cv::Scalar upper_color_range_0 = cv::Scalar(h_max_/2, l_max_, s_max_, 0);
cv::Scalar lower_color_range_360 = cv::Scalar(h_min_/2, l_min_, s_min_, 0);
cv::Scalar upper_color_range_360 = cv::Scalar( 360/2, l_max_, s_max_, 0);
if (lower_color_range_[0] < upper_color_range_[0])
{
cv::inRange(hls_image, lower_color_range_, upper_color_range_, output_image);
}
else
{
cv::Scalar lower_color_range_0 = cv::Scalar(0, l_min_, s_min_, 0);
cv::Scalar upper_color_range_0 = cv::Scalar(h_max_ / 2, l_max_, s_max_, 0);
cv::Scalar lower_color_range_360 = cv::Scalar(h_min_ / 2, l_min_, s_min_, 0);
cv::Scalar upper_color_range_360 = cv::Scalar(360 / 2, l_max_, s_max_, 0);
cv::Mat output_image_0, output_image_360;
cv::inRange(hls_image, lower_color_range_0, upper_color_range_0, output_image_0);
cv::inRange(hls_image, lower_color_range_360, upper_color_range_360, output_image_360);
Expand All @@ -285,7 +303,8 @@ class HLSColorFilterNodelet
}

public:
virtual void onInit() {
virtual void onInit()
{
h_max_ = 360;
h_min_ = 0;
s_max_ = 256;
Expand All @@ -297,8 +316,8 @@ class HLSColorFilterNodelet
}
};

class HSVColorFilterNodelet
: public ColorFilterNodelet<opencv_apps::HSVColorFilterConfig> {
class HSVColorFilterNodelet : public ColorFilterNodelet<opencv_apps::HSVColorFilterConfig>
{
protected:
int h_min_;
int h_max_;
Expand All @@ -307,8 +326,8 @@ class HSVColorFilterNodelet
int v_min_;
int v_max_;

virtual void reconfigureCallback(opencv_apps::HSVColorFilterConfig& config,
uint32_t level) {
virtual void reconfigureCallback(opencv_apps::HSVColorFilterConfig& config, uint32_t level)
{
boost::mutex::scoped_lock lock(mutex_);
config_ = config;
h_max_ = config.h_limit_max;
Expand All @@ -320,24 +339,30 @@ class HSVColorFilterNodelet
updateCondition();
}

virtual void updateCondition() {
if (s_max_ < s_min_) std::swap(s_max_, s_min_);
if (v_max_ < v_min_) std::swap(v_max_, v_min_);
lower_color_range_ = cv::Scalar(h_min_/2, s_min_, v_min_, 0);
upper_color_range_ = cv::Scalar(h_max_/2, s_max_, v_max_, 0);
virtual void updateCondition()
{
if (s_max_ < s_min_)
std::swap(s_max_, s_min_);
if (v_max_ < v_min_)
std::swap(v_max_, v_min_);
lower_color_range_ = cv::Scalar(h_min_ / 2, s_min_, v_min_, 0);
upper_color_range_ = cv::Scalar(h_max_ / 2, s_max_, v_max_, 0);
}

virtual void filter(const cv::Mat& input_image, cv::Mat& output_image) {
virtual void filter(const cv::Mat& input_image, cv::Mat& output_image)
{
cv::Mat hsv_image;
cv::cvtColor(input_image, hsv_image, cv::COLOR_BGR2HSV);
if ( lower_color_range_[0] < upper_color_range_[0] ) {
cv::inRange(hsv_image, lower_color_range_, upper_color_range_,
output_image);
}else {
cv::Scalar lower_color_range_0 = cv::Scalar( 0, s_min_, v_min_, 0);
cv::Scalar upper_color_range_0 = cv::Scalar(h_max_/2, s_max_, v_max_, 0);
cv::Scalar lower_color_range_360 = cv::Scalar(h_min_/2, s_min_, v_min_, 0);
cv::Scalar upper_color_range_360 = cv::Scalar( 360/2, s_max_, v_max_, 0);
if (lower_color_range_[0] < upper_color_range_[0])
{
cv::inRange(hsv_image, lower_color_range_, upper_color_range_, output_image);
}
else
{
cv::Scalar lower_color_range_0 = cv::Scalar(0, s_min_, v_min_, 0);
cv::Scalar upper_color_range_0 = cv::Scalar(h_max_ / 2, s_max_, v_max_, 0);
cv::Scalar lower_color_range_360 = cv::Scalar(h_min_ / 2, s_min_, v_min_, 0);
cv::Scalar upper_color_range_360 = cv::Scalar(360 / 2, s_max_, v_max_, 0);
cv::Mat output_image_0, output_image_360;
cv::inRange(hsv_image, lower_color_range_0, upper_color_range_0, output_image_0);
cv::inRange(hsv_image, lower_color_range_360, upper_color_range_360, output_image_360);
Expand All @@ -346,7 +371,8 @@ class HSVColorFilterNodelet
}

public:
virtual void onInit() {
virtual void onInit()
{
h_max_ = 360;
h_min_ = 0;
s_max_ = 256;
Expand All @@ -358,35 +384,41 @@ class HSVColorFilterNodelet
}
};

} // namespace opencv_apps
} // namespace opencv_apps

namespace color_filter {
class RGBColorFilterNodelet : public opencv_apps::RGBColorFilterNodelet {
namespace color_filter
{
class RGBColorFilterNodelet : public opencv_apps::RGBColorFilterNodelet
{
public:
virtual void onInit() {
virtual void onInit()
{
ROS_WARN("DeprecationWarning: Nodelet rgb_color_filter/rgb_color_filter is deprecated, "
"and renamed to opencv_apps/rgb_color_filter.");
opencv_apps::RGBColorFilterNodelet::onInit();
}
};
class HLSColorFilterNodelet : public opencv_apps::HLSColorFilterNodelet {
class HLSColorFilterNodelet : public opencv_apps::HLSColorFilterNodelet
{
public:
virtual void onInit() {
virtual void onInit()
{
ROS_WARN("DeprecationWarning: Nodelet hls_color_filter/hls_color_filter is deprecated, "
"and renamed to opencv_apps/hls_color_filter.");
opencv_apps::HLSColorFilterNodelet::onInit();
}
};
class HSVColorFilterNodelet : public opencv_apps::HSVColorFilterNodelet {
class HSVColorFilterNodelet : public opencv_apps::HSVColorFilterNodelet
{
public:
virtual void onInit() {
virtual void onInit()
{
ROS_WARN("DeprecationWarning: Nodelet hsv_color_filter/hsv_color_filter is deprecated, "
"and renamed to opencv_apps/hsv_color_filter.");
opencv_apps::HSVColorFilterNodelet::onInit();
}
};
} // namespace color_filter

} // namespace color_filter

#include <pluginlib/class_list_macros.h>
PLUGINLIB_EXPORT_CLASS(color_filter::RGBColorFilterNodelet, nodelet::Nodelet);
Expand Down
Loading

0 comments on commit a8ce75e

Please sign in to comment.