Skip to content

Commit

Permalink
override is not supported gcc4.6 (12.04), remove this fix and add NOLINT
Browse files Browse the repository at this point in the history
  • Loading branch information
k-okada committed Apr 22, 2019
1 parent f1a8c68 commit 66980a2
Show file tree
Hide file tree
Showing 27 changed files with 115 additions and 115 deletions.
8 changes: 4 additions & 4 deletions src/nodelet/adding_images_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,7 @@ class AddingImagesNodelet : public opencv_apps::Nodelet
doWork(msg1, msg2, msg1->header.frame_id);
}

void subscribe() override
void subscribe() // NOLINT(modernize-use-override)
{
NODELET_DEBUG("Subscribing to image topic.");
sub_image1_.subscribe(*it_, "image1", 3);
Expand Down Expand Up @@ -148,7 +148,7 @@ class AddingImagesNodelet : public opencv_apps::Nodelet
}
}

void unsubscribe() override
void unsubscribe() // NOLINT(modernize-use-override)
{
NODELET_DEBUG("Unsubscribing from image topic.");
sub_image1_.unsubscribe();
Expand Down Expand Up @@ -241,7 +241,7 @@ class AddingImagesNodelet : public opencv_apps::Nodelet
}

public:
void onInit() override
virtual void onInit() // NOLINT(modernize-use-override)
{
Nodelet::onInit();
it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
Expand Down Expand Up @@ -275,7 +275,7 @@ namespace adding_images
class AddingImagesNodelet : public opencv_apps::AddingImagesNodelet
{
public:
void onInit() override
virtual void onInit() // NOLINT(modernize-use-override)
{
ROS_WARN("DeprecationWarning: Nodelet adding_images/adding_images is deprecated, "
"and renamed to opencv_apps/adding_images.");
Expand Down
8 changes: 4 additions & 4 deletions src/nodelet/camshift_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -338,7 +338,7 @@ class CamShiftNodelet : public opencv_apps::Nodelet
prev_stamp_ = msg->header.stamp;
}

void subscribe() override
void subscribe() // NOLINT(modernize-use-override)
{
NODELET_DEBUG("Subscribing to image topic.");
if (config_.use_camera_info)
Expand All @@ -347,15 +347,15 @@ class CamShiftNodelet : public opencv_apps::Nodelet
img_sub_ = it_->subscribe("image", queue_size_, &CamShiftNodelet::imageCallback, this);
}

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

public:
void onInit() override
virtual void onInit() // NOLINT(modernize-use-override)
{
Nodelet::onInit();
it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
Expand Down Expand Up @@ -444,7 +444,7 @@ namespace camshift
class CamShiftNodelet : public opencv_apps::CamShiftNodelet
{
public:
void onInit() override
virtual void onInit() // NOLINT(modernize-use-override)
{
ROS_WARN("DeprecationWarning: Nodelet camshift/camshift is deprecated, "
"and renamed to opencv_apps/camshift.");
Expand Down
30 changes: 15 additions & 15 deletions src/nodelet/color_filter_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -148,7 +148,7 @@ class ColorFilterNodelet : public opencv_apps::Nodelet
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() override
void subscribe() // NOLINT(modernize-use-override)
{
NODELET_DEBUG("Subscribing to image topic.");
if (config_.use_camera_info)
Expand All @@ -157,15 +157,15 @@ class ColorFilterNodelet : public opencv_apps::Nodelet
img_sub_ = it_->subscribe("image", queue_size_, &ColorFilterNodelet::imageCallback, this);
}

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

public:
void onInit() override
virtual void onInit() // NOLINT(modernize-use-override)
{
Nodelet::onInit();
it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
Expand Down Expand Up @@ -201,7 +201,7 @@ class RGBColorFilterNodelet : public ColorFilterNodelet<opencv_apps::RGBColorFil
int g_min_;
int g_max_;

void reconfigureCallback(opencv_apps::RGBColorFilterConfig& config, uint32_t level) override
void reconfigureCallback(opencv_apps::RGBColorFilterConfig& config, uint32_t level) // NOLINT(modernize-use-override)
{
boost::mutex::scoped_lock lock(mutex_);
config_ = config;
Expand All @@ -226,13 +226,13 @@ class RGBColorFilterNodelet : public ColorFilterNodelet<opencv_apps::RGBColorFil
upper_color_range_ = cv::Scalar(b_max_, g_max_, r_max_);
}

void filter(const cv::Mat& input_image, cv::Mat& output_image) override
void filter(const cv::Mat& input_image, cv::Mat& output_image) // NOLINT(modernize-use-override)
{
cv::inRange(input_image, lower_color_range_, upper_color_range_, output_image);
}

protected:
void onInit() override
virtual void onInit() // NOLINT(modernize-use-override)
{
r_max_ = 255;
r_min_ = 0;
Expand All @@ -258,7 +258,7 @@ class HLSColorFilterNodelet : public ColorFilterNodelet<opencv_apps::HLSColorFil
int l_min_;
int l_max_;

void reconfigureCallback(opencv_apps::HLSColorFilterConfig& config, uint32_t level) override
void reconfigureCallback(opencv_apps::HLSColorFilterConfig& config, uint32_t level) // NOLINT(modernize-use-override)
{
boost::mutex::scoped_lock lock(mutex_);
config_ = config;
Expand All @@ -281,7 +281,7 @@ class HLSColorFilterNodelet : public ColorFilterNodelet<opencv_apps::HLSColorFil
upper_color_range_ = cv::Scalar(h_max_ / 2, l_max_, s_max_, 0);
}

void filter(const cv::Mat& input_image, cv::Mat& output_image) override
void filter(const cv::Mat& input_image, cv::Mat& output_image) // NOLINT(modernize-use-override)
{
cv::Mat hls_image;
cv::cvtColor(input_image, hls_image, cv::COLOR_BGR2HLS);
Expand All @@ -303,7 +303,7 @@ class HLSColorFilterNodelet : public ColorFilterNodelet<opencv_apps::HLSColorFil
}

public:
void onInit() override
virtual void onInit() // NOLINT(modernize-use-override)
{
h_max_ = 360;
h_min_ = 0;
Expand All @@ -326,7 +326,7 @@ class HSVColorFilterNodelet : public ColorFilterNodelet<opencv_apps::HSVColorFil
int v_min_;
int v_max_;

void reconfigureCallback(opencv_apps::HSVColorFilterConfig& config, uint32_t level) override
void reconfigureCallback(opencv_apps::HSVColorFilterConfig& config, uint32_t level) // NOLINT(modernize-use-override)
{
boost::mutex::scoped_lock lock(mutex_);
config_ = config;
Expand All @@ -349,7 +349,7 @@ class HSVColorFilterNodelet : public ColorFilterNodelet<opencv_apps::HSVColorFil
upper_color_range_ = cv::Scalar(h_max_ / 2, s_max_, v_max_, 0);
}

void filter(const cv::Mat& input_image, cv::Mat& output_image) override
void filter(const cv::Mat& input_image, cv::Mat& output_image) // NOLINT(modernize-use-override)
{
cv::Mat hsv_image;
cv::cvtColor(input_image, hsv_image, cv::COLOR_BGR2HSV);
Expand All @@ -371,7 +371,7 @@ class HSVColorFilterNodelet : public ColorFilterNodelet<opencv_apps::HSVColorFil
}

public:
void onInit() override
virtual void onInit() // NOLINT(modernize-use-override)
{
h_max_ = 360;
h_min_ = 0;
Expand All @@ -391,7 +391,7 @@ namespace color_filter
class RGBColorFilterNodelet : public opencv_apps::RGBColorFilterNodelet
{
public:
void onInit() override
virtual void onInit() // NOLINT(modernize-use-override)
{
ROS_WARN("DeprecationWarning: Nodelet rgb_color_filter/rgb_color_filter is deprecated, "
"and renamed to opencv_apps/rgb_color_filter.");
Expand All @@ -401,7 +401,7 @@ class RGBColorFilterNodelet : public opencv_apps::RGBColorFilterNodelet
class HLSColorFilterNodelet : public opencv_apps::HLSColorFilterNodelet
{
public:
void onInit() override
virtual void onInit() // NOLINT(modernize-use-override)
{
ROS_WARN("DeprecationWarning: Nodelet hls_color_filter/hls_color_filter is deprecated, "
"and renamed to opencv_apps/hls_color_filter.");
Expand All @@ -411,7 +411,7 @@ class HLSColorFilterNodelet : public opencv_apps::HLSColorFilterNodelet
class HSVColorFilterNodelet : public opencv_apps::HSVColorFilterNodelet
{
public:
void onInit() override
virtual void onInit() // NOLINT(modernize-use-override)
{
ROS_WARN("DeprecationWarning: Nodelet hsv_color_filter/hsv_color_filter is deprecated, "
"and renamed to opencv_apps/hsv_color_filter.");
Expand Down
8 changes: 4 additions & 4 deletions src/nodelet/contour_moments_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -249,7 +249,7 @@ class ContourMomentsNodelet : public opencv_apps::Nodelet
prev_stamp_ = msg->header.stamp;
}

void subscribe() override
void subscribe() // NOLINT(modernize-use-override)
{
NODELET_DEBUG("Subscribing to image topic.");
if (config_.use_camera_info)
Expand All @@ -258,15 +258,15 @@ class ContourMomentsNodelet : public opencv_apps::Nodelet
img_sub_ = it_->subscribe("image", queue_size_, &ContourMomentsNodelet::imageCallback, this);
}

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

public:
void onInit() override
virtual void onInit() // NOLINT(modernize-use-override)
{
Nodelet::onInit();
it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
Expand Down Expand Up @@ -300,7 +300,7 @@ namespace contour_moments
class ContourMomentsNodelet : public opencv_apps::ContourMomentsNodelet
{
public:
void onInit() override
virtual void onInit() // NOLINT(modernize-use-override)
{
ROS_WARN("DeprecationWarning: Nodelet contour_moments/contour_moments is deprecated, "
"and renamed to opencv_apps/contour_moments.");
Expand Down
8 changes: 4 additions & 4 deletions src/nodelet/convex_hull_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -207,7 +207,7 @@ class ConvexHullNodelet : public opencv_apps::Nodelet
prev_stamp_ = msg->header.stamp;
}

void subscribe() override
void subscribe() // NOLINT(modernize-use-override)
{
NODELET_DEBUG("Subscribing to image topic.");
if (config_.use_camera_info)
Expand All @@ -216,15 +216,15 @@ class ConvexHullNodelet : public opencv_apps::Nodelet
img_sub_ = it_->subscribe("image", queue_size_, &ConvexHullNodelet::imageCallback, this);
}

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

public:
void onInit() override
virtual void onInit() // NOLINT(modernize-use-override)
{
Nodelet::onInit();
it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
Expand Down Expand Up @@ -258,7 +258,7 @@ namespace convex_hull
class ConvexHullNodelet : public opencv_apps::ConvexHullNodelet
{
public:
void onInit() override
virtual void onInit() // NOLINT(modernize-use-override)
{
ROS_WARN("DeprecationWarning: Nodelet convex_hull/convex_hull is deprecated, "
"and renamed to opencv_apps/convex_hull.");
Expand Down
8 changes: 4 additions & 4 deletions src/nodelet/corner_harris_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -182,7 +182,7 @@ class CornerHarrisNodelet : public opencv_apps::Nodelet
}
}

void subscribe() override
void subscribe() // NOLINT(modernize-use-override)
{
NODELET_DEBUG("Subscribing to image topic.");
if (config_.use_camera_info)
Expand All @@ -191,15 +191,15 @@ class CornerHarrisNodelet : public opencv_apps::Nodelet
img_sub_ = it_->subscribe("image", queue_size_, &CornerHarrisNodelet::imageCallback, this);
}

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

public:
void onInit() override
virtual void onInit() // NOLINT(modernize-use-override)
{
Nodelet::onInit();
it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
Expand Down Expand Up @@ -232,7 +232,7 @@ namespace corner_harris
class CornerHarrisNodelet : public opencv_apps::CornerHarrisNodelet
{
public:
void onInit() override
virtual void onInit() // NOLINT(modernize-use-override)
{
ROS_WARN("DeprecationWarning: Nodelet corner_harris/corner_harris is deprecated, "
"and renamed to opencv_apps/corner_harris.");
Expand Down
8 changes: 4 additions & 4 deletions src/nodelet/discrete_fourier_transform_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ class DiscreteFourierTransformNodelet : public opencv_apps::Nodelet
doWork(msg, msg->header.frame_id);
}

void subscribe() override
void subscribe() // NOLINT(modernize-use-override)
{
NODELET_DEBUG("Subscribing to image topic.");
if (config_.use_camera_info)
Expand All @@ -93,7 +93,7 @@ class DiscreteFourierTransformNodelet : public opencv_apps::Nodelet
img_sub_ = it_->subscribe("image", queue_size_, &DiscreteFourierTransformNodelet::imageCallback, this);
}

void unsubscribe() override
void unsubscribe() // NOLINT(modernize-use-override)
{
NODELET_DEBUG("Unsubscribing from image topic.");
img_sub_.shutdown();
Expand Down Expand Up @@ -185,7 +185,7 @@ class DiscreteFourierTransformNodelet : public opencv_apps::Nodelet
}

public:
void onInit() override
virtual void onInit() // NOLINT(modernize-use-override)
{
Nodelet::onInit();
it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
Expand Down Expand Up @@ -216,7 +216,7 @@ namespace discrete_fourier_transform
class DiscreteFourierTransformNodelet : public opencv_apps::DiscreteFourierTransformNodelet
{
public:
void onInit() override
virtual void onInit() // NOLINT(modernize-use-override)
{
ROS_WARN("DeprecationWarning: Nodelet discrete_fourier_transform/discrete_fourier_transform is deprecated, "
"and renamed to opencv_apps/discrete_fourier_transform.");
Expand Down
8 changes: 4 additions & 4 deletions src/nodelet/edge_detection_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -273,7 +273,7 @@ class EdgeDetectionNodelet : public opencv_apps::Nodelet
prev_stamp_ = msg->header.stamp;
}

void subscribe() override
void subscribe() // NOLINT(modernize-use-override)
{
NODELET_DEBUG("Subscribing to image topic.");
if (config_.use_camera_info)
Expand All @@ -282,15 +282,15 @@ class EdgeDetectionNodelet : public opencv_apps::Nodelet
img_sub_ = it_->subscribe("image", queue_size_, &EdgeDetectionNodelet::imageCallback, this);
}

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

public:
void onInit() override
virtual void onInit() // NOLINT(modernize-use-override)
{
Nodelet::onInit();
it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
Expand Down Expand Up @@ -327,7 +327,7 @@ namespace edge_detection
class EdgeDetectionNodelet : public opencv_apps::EdgeDetectionNodelet
{
public:
void onInit() override
virtual void onInit() // NOLINT(modernize-use-override)
{
ROS_WARN("DeprecationWarning: Nodelet edge_detection/edge_detection is deprecated, "
"and renamed to opencv_apps/edge_detection.");
Expand Down
Loading

0 comments on commit 66980a2

Please sign in to comment.