diff --git a/include/opencv_apps/nodelet.h b/include/opencv_apps/nodelet.h index f731eb14..d23e09f9 100644 --- a/include/opencv_apps/nodelet.h +++ b/include/opencv_apps/nodelet.h @@ -40,6 +40,11 @@ #include #include +// https://stackoverflow.com/questions/10496824/how-to-define-nullptr-for-supporting-both-c03-and-c11 +#if !defined(nullptr) +#define nullptr NULL +#endif + namespace opencv_apps { /** @brief diff --git a/src/nodelet/adding_images_nodelet.cpp b/src/nodelet/adding_images_nodelet.cpp index f4d5cd0e..18d2e600 100644 --- a/src/nodelet/adding_images_nodelet.cpp +++ b/src/nodelet/adding_images_nodelet.cpp @@ -101,15 +101,15 @@ class AddingImagesNodelet : public opencv_apps::Nodelet void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg1, const sensor_msgs::ImageConstPtr& msg2, const sensor_msgs::CameraInfoConstPtr& cam_info) { - do_work(msg1, msg2, cam_info->header.frame_id); + doWork(msg1, msg2, cam_info->header.frame_id); } void imageCallback(const sensor_msgs::ImageConstPtr& msg1, const sensor_msgs::ImageConstPtr& msg2) { - do_work(msg1, msg2, msg1->header.frame_id); + doWork(msg1, msg2, msg1->header.frame_id); } - void subscribe() + void subscribe() override { NODELET_DEBUG("Subscribing to image topic."); sub_image1_.subscribe(*it_, "image1", 3); @@ -148,7 +148,7 @@ class AddingImagesNodelet : public opencv_apps::Nodelet } } - void unsubscribe() + void unsubscribe() override { NODELET_DEBUG("Unsubscribing from image topic."); sub_image1_.unsubscribe(); @@ -173,8 +173,8 @@ class AddingImagesNodelet : public opencv_apps::Nodelet gamma_ = config.gamma; } - void do_work(const sensor_msgs::Image::ConstPtr& image_msg1, const sensor_msgs::Image::ConstPtr& image_msg2, - const std::string input_frame_from_msg) + void doWork(const sensor_msgs::Image::ConstPtr& image_msg1, const sensor_msgs::Image::ConstPtr& image_msg2, + const std::string& input_frame_from_msg) { boost::mutex::scoped_lock lock(mutex_); // Work on the image. @@ -195,14 +195,14 @@ class AddingImagesNodelet : public opencv_apps::Nodelet int new_rows = std::max(image1.rows, image2.rows); int new_cols = std::max(image1.cols, image2.cols); // if ( new_rows != image1.rows || new_cols != image1.cols ) { - cv::Mat image1_ = cv::Mat(new_rows, new_cols, image1.type()); - image1.copyTo(image1_(cv::Rect(0, 0, image1.cols, image1.rows))); - image1 = image1_.clone(); // need clone becuase toCvShare?? + cv::Mat image1 = cv::Mat(new_rows, new_cols, image1.type()); + image1.copyTo(image1(cv::Rect(0, 0, image1.cols, image1.rows))); + image1 = image1.clone(); // need clone becuase toCvShare?? // if ( new_rows != image2.rows || new_cols != image2.cols ) { - cv::Mat image2_ = cv::Mat(new_rows, new_cols, image2.type()); - image2.copyTo(image2_(cv::Rect(0, 0, image2.cols, image2.rows))); - image2 = image2_.clone(); + cv::Mat image2 = cv::Mat(new_rows, new_cols, image2.type()); + image2.copyTo(image2(cv::Rect(0, 0, image2.cols, image2.rows))); + image2 = image2.clone(); } cv::addWeighted(image1, alpha_, image2, beta_, gamma_, result_image); //-- Show what you got @@ -241,7 +241,7 @@ class AddingImagesNodelet : public opencv_apps::Nodelet } public: - virtual void onInit() + void onInit() override { Nodelet::onInit(); it_ = boost::shared_ptr(new image_transport::ImageTransport(*nh_)); @@ -275,7 +275,7 @@ namespace adding_images class AddingImagesNodelet : public opencv_apps::AddingImagesNodelet { public: - virtual void onInit() + void onInit() override { ROS_WARN("DeprecationWarning: Nodelet adding_images/adding_images is deprecated, " "and renamed to opencv_apps/adding_images."); diff --git a/src/nodelet/camshift_nodelet.cpp b/src/nodelet/camshift_nodelet.cpp index 512fef50..e3210c31 100644 --- a/src/nodelet/camshift_nodelet.cpp +++ b/src/nodelet/camshift_nodelet.cpp @@ -99,7 +99,7 @@ class CamShiftNodelet : public opencv_apps::Nodelet cv::Mat hist, histimg; // cv::Mat hsv; - static void onMouse(int event, int x, int y, int, void*) + static void onMouse(int event, int x, int y, int /*unused*/, void* /*unused*/) { on_mouse_update_ = true; on_mouse_event_ = event; @@ -124,20 +124,20 @@ class CamShiftNodelet : public opencv_apps::Nodelet void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info) { - do_work(msg, cam_info->header.frame_id); + doWork(msg, cam_info->header.frame_id); } void imageCallback(const sensor_msgs::ImageConstPtr& msg) { - do_work(msg, msg->header.frame_id); + doWork(msg, msg->header.frame_id); } - static void trackbarCallback(int, void*) + static void trackbarCallback(int /*unused*/, void* /*unused*/) { need_config_update_ = true; } - void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg) + void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg) { // Work on the image. try @@ -158,7 +158,7 @@ class CamShiftNodelet : public opencv_apps::Nodelet cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE); - cv::setMouseCallback(window_name_, onMouse, 0); + cv::setMouseCallback(window_name_, onMouse, nullptr); cv::createTrackbar("Vmin", window_name_, &vmin_, 256, trackbarCallback); cv::createTrackbar("Vmax", window_name_, &vmax_, 256, trackbarCallback); cv::createTrackbar("Smin", window_name_, &smin_, 256, trackbarCallback); @@ -212,9 +212,9 @@ class CamShiftNodelet : public opencv_apps::Nodelet if (trackObject) { - int _vmin = vmin_, _vmax = vmax_; + int vmin = vmin_, vmax = vmax_; - cv::inRange(hsv, cv::Scalar(0, smin_, MIN(_vmin, _vmax)), cv::Scalar(180, 256, MAX(_vmin, _vmax)), mask); + cv::inRange(hsv, cv::Scalar(0, smin_, MIN(vmin, vmax)), cv::Scalar(180, 256, MAX(vmin, vmax)), mask); int ch[] = { 0, 0 }; hue.create(hsv.size(), hsv.depth()); cv::mixChannels(&hsv, 1, &hue, 1, ch, 1); @@ -222,7 +222,7 @@ class CamShiftNodelet : public opencv_apps::Nodelet if (trackObject < 0) { cv::Mat roi(hue, selection), maskroi(mask, selection); - cv::calcHist(&roi, 1, 0, maskroi, hist, 1, &hsize, &phranges); + cv::calcHist(&roi, 1, nullptr, maskroi, hist, 1, &hsize, &phranges); cv::normalize(hist, hist, 0, 255, cv::NORM_MINMAX); std::vector hist_value; hist_value.resize(hsize); @@ -236,7 +236,7 @@ class CamShiftNodelet : public opencv_apps::Nodelet trackObject = 1; histimg = cv::Scalar::all(0); - int binW = histimg.cols / hsize; + int bin_w = histimg.cols / hsize; cv::Mat buf(1, hsize, CV_8UC3); for (int i = 0; i < hsize; i++) buf.at(i) = cv::Vec3b(cv::saturate_cast(i * 180. / hsize), 255, 255); @@ -245,14 +245,14 @@ class CamShiftNodelet : public opencv_apps::Nodelet for (int i = 0; i < hsize; i++) { int val = cv::saturate_cast(hist.at(i) * histimg.rows / 255); - cv::rectangle(histimg, cv::Point(i * binW, histimg.rows), cv::Point((i + 1) * binW, histimg.rows - val), + cv::rectangle(histimg, cv::Point(i * bin_w, histimg.rows), cv::Point((i + 1) * bin_w, histimg.rows - val), cv::Scalar(buf.at(i)), -1, 8); } } - cv::calcBackProject(&hue, 1, 0, hist, backproj, &phranges); + cv::calcBackProject(&hue, 1, nullptr, hist, backproj, &phranges); backproj &= mask; - cv::RotatedRect trackBox = cv::CamShift( + cv::RotatedRect track_box = cv::CamShift( backproj, trackWindow, cv::TermCriteria(cv::TermCriteria::EPS + cv::TermCriteria::MAX_ITER, 10, 1)); if (trackWindow.area() <= 1) { @@ -265,18 +265,18 @@ class CamShiftNodelet : public opencv_apps::Nodelet if (backprojMode) cv::cvtColor(backproj, frame, cv::COLOR_GRAY2BGR); #ifndef CV_VERSION_EPOCH - cv::ellipse(frame, trackBox, cv::Scalar(0, 0, 255), 3, cv::LINE_AA); + cv::ellipse(frame, track_box, cv::Scalar(0, 0, 255), 3, cv::LINE_AA); #else - cv::ellipse(frame, trackBox, cv::Scalar(0, 0, 255), 3, CV_AA); + cv::ellipse(frame, track_box, cv::Scalar(0, 0, 255), 3, CV_AA); #endif - rect_msg.rect.angle = trackBox.angle; + rect_msg.rect.angle = track_box.angle; opencv_apps::Point2D point_msg; opencv_apps::Size size_msg; - point_msg.x = trackBox.center.x; - point_msg.y = trackBox.center.y; - size_msg.width = trackBox.size.width; - size_msg.height = trackBox.size.height; + point_msg.x = track_box.center.x; + point_msg.y = track_box.center.y; + size_msg.width = track_box.size.width; + size_msg.height = track_box.size.height; rect_msg.rect.center = point_msg; rect_msg.rect.size = size_msg; } @@ -338,7 +338,7 @@ class CamShiftNodelet : public opencv_apps::Nodelet prev_stamp_ = msg->header.stamp; } - void subscribe() + void subscribe() override { NODELET_DEBUG("Subscribing to image topic."); if (config_.use_camera_info) @@ -347,7 +347,7 @@ class CamShiftNodelet : public opencv_apps::Nodelet img_sub_ = it_->subscribe("image", queue_size_, &CamShiftNodelet::imageCallback, this); } - void unsubscribe() + void unsubscribe() override { NODELET_DEBUG("Unsubscribing from image topic."); img_sub_.shutdown(); @@ -355,7 +355,7 @@ class CamShiftNodelet : public opencv_apps::Nodelet } public: - virtual void onInit() + void onInit() override { Nodelet::onInit(); it_ = boost::shared_ptr(new image_transport::ImageTransport(*nh_)); @@ -416,7 +416,7 @@ class CamShiftNodelet : public opencv_apps::Nodelet trackWindow = cv::Rect(0, 0, 640, 480); // histimg = cv::Scalar::all(0); - int binW = histimg.cols / hsize; + int bin_w = histimg.cols / hsize; cv::Mat buf(1, hsize, CV_8UC3); for (int i = 0; i < hsize; i++) buf.at(i) = cv::Vec3b(cv::saturate_cast(i * 180. / hsize), 255, 255); @@ -425,7 +425,7 @@ class CamShiftNodelet : public opencv_apps::Nodelet for (int i = 0; i < hsize; i++) { int val = cv::saturate_cast(hist.at(i) * histimg.rows / 255); - cv::rectangle(histimg, cv::Point(i * binW, histimg.rows), cv::Point((i + 1) * binW, histimg.rows - val), + cv::rectangle(histimg, cv::Point(i * bin_w, histimg.rows), cv::Point((i + 1) * bin_w, histimg.rows - val), cv::Scalar(buf.at(i)), -1, 8); } } @@ -444,7 +444,7 @@ namespace camshift class CamShiftNodelet : public opencv_apps::CamShiftNodelet { public: - virtual void onInit() + void onInit() override { ROS_WARN("DeprecationWarning: Nodelet camshift/camshift is deprecated, " "and renamed to opencv_apps/camshift."); diff --git a/src/nodelet/color_filter_nodelet.cpp b/src/nodelet/color_filter_nodelet.cpp index 1f796ac0..2939b4d4 100644 --- a/src/nodelet/color_filter_nodelet.cpp +++ b/src/nodelet/color_filter_nodelet.cpp @@ -99,15 +99,15 @@ class ColorFilterNodelet : public opencv_apps::Nodelet void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info) { - do_work(msg, cam_info->header.frame_id); + doWork(msg, cam_info->header.frame_id); } void imageCallback(const sensor_msgs::ImageConstPtr& msg) { - do_work(msg, msg->header.frame_id); + doWork(msg, msg->header.frame_id); } - void do_work(const sensor_msgs::ImageConstPtr& image_msg, const std::string input_frame_from_msg) + void doWork(const sensor_msgs::ImageConstPtr& image_msg, const std::string& input_frame_from_msg) { // Work on the image. try @@ -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() + void subscribe() override { NODELET_DEBUG("Subscribing to image topic."); if (config_.use_camera_info) @@ -157,7 +157,7 @@ class ColorFilterNodelet : public opencv_apps::Nodelet img_sub_ = it_->subscribe("image", queue_size_, &ColorFilterNodelet::imageCallback, this); } - void unsubscribe() + void unsubscribe() override { NODELET_DEBUG("Unsubscribing from image topic."); img_sub_.shutdown(); @@ -165,7 +165,7 @@ class ColorFilterNodelet : public opencv_apps::Nodelet } public: - virtual void onInit() + void onInit() override { Nodelet::onInit(); it_ = boost::shared_ptr(new image_transport::ImageTransport(*nh_)); @@ -201,7 +201,7 @@ class RGBColorFilterNodelet : public ColorFilterNodelet contour1, std::vector contour2) +bool compareContourAreas(const std::vector& contour1, const std::vector& contour2) { double i = fabs(contourArea(cv::Mat(contour1))); double j = fabs(contourArea(cv::Mat(contour2))); @@ -103,20 +103,20 @@ class ContourMomentsNodelet : public opencv_apps::Nodelet void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info) { - do_work(msg, cam_info->header.frame_id); + doWork(msg, cam_info->header.frame_id); } void imageCallback(const sensor_msgs::ImageConstPtr& msg) { - do_work(msg, msg->header.frame_id); + doWork(msg, msg->header.frame_id); } - static void trackbarCallback(int, void*) + static void trackbarCallback(int /*unused*/, void* /*unused*/) { need_config_update_ = true; } - void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg) + void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg) { // Work on the image. try @@ -249,7 +249,7 @@ class ContourMomentsNodelet : public opencv_apps::Nodelet prev_stamp_ = msg->header.stamp; } - void subscribe() + void subscribe() override { NODELET_DEBUG("Subscribing to image topic."); if (config_.use_camera_info) @@ -258,7 +258,7 @@ class ContourMomentsNodelet : public opencv_apps::Nodelet img_sub_ = it_->subscribe("image", queue_size_, &ContourMomentsNodelet::imageCallback, this); } - void unsubscribe() + void unsubscribe() override { NODELET_DEBUG("Unsubscribing from image topic."); img_sub_.shutdown(); @@ -266,7 +266,7 @@ class ContourMomentsNodelet : public opencv_apps::Nodelet } public: - virtual void onInit() + void onInit() override { Nodelet::onInit(); it_ = boost::shared_ptr(new image_transport::ImageTransport(*nh_)); @@ -300,7 +300,7 @@ namespace contour_moments class ContourMomentsNodelet : public opencv_apps::ContourMomentsNodelet { public: - virtual void onInit() + void onInit() override { ROS_WARN("DeprecationWarning: Nodelet contour_moments/contour_moments is deprecated, " "and renamed to opencv_apps/contour_moments."); diff --git a/src/nodelet/convex_hull_nodelet.cpp b/src/nodelet/convex_hull_nodelet.cpp index 4e8dd659..e2fb95d4 100644 --- a/src/nodelet/convex_hull_nodelet.cpp +++ b/src/nodelet/convex_hull_nodelet.cpp @@ -95,20 +95,20 @@ class ConvexHullNodelet : public opencv_apps::Nodelet void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info) { - do_work(msg, cam_info->header.frame_id); + doWork(msg, cam_info->header.frame_id); } void imageCallback(const sensor_msgs::ImageConstPtr& msg) { - do_work(msg, msg->header.frame_id); + doWork(msg, msg->header.frame_id); } - static void trackbarCallback(int, void*) + static void trackbarCallback(int /*unused*/, void* /*unused*/) { need_config_update_ = true; } - void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg) + void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg) { // Work on the image. try @@ -168,11 +168,11 @@ class ConvexHullNodelet : public opencv_apps::Nodelet cv::drawContours(drawing, hull, (int)i, color, 4, 8, std::vector(), 0, cv::Point()); opencv_apps::Contour contour_msg; - for (size_t j = 0; j < hull[i].size(); j++) + for (const cv::Point& j : hull[i]) { opencv_apps::Point2D point_msg; - point_msg.x = hull[i][j].x; - point_msg.y = hull[i][j].y; + point_msg.x = j.x; + point_msg.y = j.y; contour_msg.points.push_back(point_msg); } contours_msg.contours.push_back(contour_msg); @@ -207,7 +207,7 @@ class ConvexHullNodelet : public opencv_apps::Nodelet prev_stamp_ = msg->header.stamp; } - void subscribe() + void subscribe() override { NODELET_DEBUG("Subscribing to image topic."); if (config_.use_camera_info) @@ -216,7 +216,7 @@ class ConvexHullNodelet : public opencv_apps::Nodelet img_sub_ = it_->subscribe("image", queue_size_, &ConvexHullNodelet::imageCallback, this); } - void unsubscribe() + void unsubscribe() override { NODELET_DEBUG("Unsubscribing from image topic."); img_sub_.shutdown(); @@ -224,7 +224,7 @@ class ConvexHullNodelet : public opencv_apps::Nodelet } public: - virtual void onInit() + void onInit() override { Nodelet::onInit(); it_ = boost::shared_ptr(new image_transport::ImageTransport(*nh_)); @@ -258,7 +258,7 @@ namespace convex_hull class ConvexHullNodelet : public opencv_apps::ConvexHullNodelet { public: - virtual void onInit() + void onInit() override { ROS_WARN("DeprecationWarning: Nodelet convex_hull/convex_hull is deprecated, " "and renamed to opencv_apps/convex_hull."); diff --git a/src/nodelet/corner_harris_nodelet.cpp b/src/nodelet/corner_harris_nodelet.cpp index eec4b3be..5b9bbde7 100644 --- a/src/nodelet/corner_harris_nodelet.cpp +++ b/src/nodelet/corner_harris_nodelet.cpp @@ -90,20 +90,20 @@ class CornerHarrisNodelet : public opencv_apps::Nodelet void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info) { - do_work(msg, cam_info->header.frame_id); + doWork(msg, cam_info->header.frame_id); } void imageCallback(const sensor_msgs::ImageConstPtr& msg) { - do_work(msg, msg->header.frame_id); + doWork(msg, msg->header.frame_id); } - static void trackbarCallback(int, void*) + static void trackbarCallback(int /*unused*/, void* /*unused*/) { need_config_update_ = true; } - void do_work(const sensor_msgs::ImageConstPtr& image_msg, const std::string input_frame_from_msg) + void doWork(const sensor_msgs::ImageConstPtr& image_msg, const std::string& input_frame_from_msg) { // Work on the image. try @@ -128,12 +128,12 @@ class CornerHarrisNodelet : public opencv_apps::Nodelet } /// Detector parameters - int blockSize = 2; - int apertureSize = 3; + int block_size = 2; + int aperture_size = 3; double k = 0.04; /// Detecting corners - cv::cornerHarris(src_gray, dst, blockSize, apertureSize, k, cv::BORDER_DEFAULT); + cv::cornerHarris(src_gray, dst, block_size, aperture_size, k, cv::BORDER_DEFAULT); /// Normalizing cv::normalize(dst, dst_norm, 0, 255, cv::NORM_MINMAX, CV_32FC1, cv::Mat()); @@ -182,7 +182,7 @@ class CornerHarrisNodelet : public opencv_apps::Nodelet } } - void subscribe() + void subscribe() override { NODELET_DEBUG("Subscribing to image topic."); if (config_.use_camera_info) @@ -191,7 +191,7 @@ class CornerHarrisNodelet : public opencv_apps::Nodelet img_sub_ = it_->subscribe("image", queue_size_, &CornerHarrisNodelet::imageCallback, this); } - void unsubscribe() + void unsubscribe() override { NODELET_DEBUG("Unsubscribing from image topic."); img_sub_.shutdown(); @@ -199,7 +199,7 @@ class CornerHarrisNodelet : public opencv_apps::Nodelet } public: - virtual void onInit() + void onInit() override { Nodelet::onInit(); it_ = boost::shared_ptr(new image_transport::ImageTransport(*nh_)); @@ -232,7 +232,7 @@ namespace corner_harris class CornerHarrisNodelet : public opencv_apps::CornerHarrisNodelet { public: - virtual void onInit() + void onInit() override { ROS_WARN("DeprecationWarning: Nodelet corner_harris/corner_harris is deprecated, " "and renamed to opencv_apps/corner_harris."); diff --git a/src/nodelet/discrete_fourier_transform_nodelet.cpp b/src/nodelet/discrete_fourier_transform_nodelet.cpp index 0ca2ad07..da46d04e 100644 --- a/src/nodelet/discrete_fourier_transform_nodelet.cpp +++ b/src/nodelet/discrete_fourier_transform_nodelet.cpp @@ -75,15 +75,15 @@ class DiscreteFourierTransformNodelet : public opencv_apps::Nodelet void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info) { - do_work(msg, cam_info->header.frame_id); + doWork(msg, cam_info->header.frame_id); } void imageCallback(const sensor_msgs::ImageConstPtr& msg) { - do_work(msg, msg->header.frame_id); + doWork(msg, msg->header.frame_id); } - void subscribe() + void subscribe() override { NODELET_DEBUG("Subscribing to image topic."); if (config_.use_camera_info) @@ -93,7 +93,7 @@ class DiscreteFourierTransformNodelet : public opencv_apps::Nodelet img_sub_ = it_->subscribe("image", queue_size_, &DiscreteFourierTransformNodelet::imageCallback, this); } - void unsubscribe() + void unsubscribe() override { NODELET_DEBUG("Unsubscribing from image topic."); img_sub_.shutdown(); @@ -106,7 +106,7 @@ class DiscreteFourierTransformNodelet : public opencv_apps::Nodelet config_ = config; } - void do_work(const sensor_msgs::Image::ConstPtr& image_msg, const std::string input_frame_from_msg) + void doWork(const sensor_msgs::Image::ConstPtr& image_msg, const std::string& input_frame_from_msg) { // Work on the image. try @@ -185,7 +185,7 @@ class DiscreteFourierTransformNodelet : public opencv_apps::Nodelet } public: - virtual void onInit() + void onInit() override { Nodelet::onInit(); it_ = boost::shared_ptr(new image_transport::ImageTransport(*nh_)); @@ -216,7 +216,7 @@ namespace discrete_fourier_transform class DiscreteFourierTransformNodelet : public opencv_apps::DiscreteFourierTransformNodelet { public: - virtual void onInit() + void onInit() override { ROS_WARN("DeprecationWarning: Nodelet discrete_fourier_transform/discrete_fourier_transform is deprecated, " "and renamed to opencv_apps/discrete_fourier_transform."); diff --git a/src/nodelet/edge_detection_nodelet.cpp b/src/nodelet/edge_detection_nodelet.cpp index abdc348e..82d5bf30 100644 --- a/src/nodelet/edge_detection_nodelet.cpp +++ b/src/nodelet/edge_detection_nodelet.cpp @@ -117,20 +117,20 @@ class EdgeDetectionNodelet : public opencv_apps::Nodelet void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info) { - do_work(msg, cam_info->header.frame_id); + doWork(msg, cam_info->header.frame_id); } void imageCallback(const sensor_msgs::ImageConstPtr& msg) { - do_work(msg, msg->header.frame_id); + doWork(msg, msg->header.frame_id); } - static void trackbarCallback(int, void*) + static void trackbarCallback(int /*unused*/, void* /*unused*/) { need_config_update_ = true; } - void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg) + void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg) { // Work on the image. try @@ -205,7 +205,7 @@ class EdgeDetectionNodelet : public opencv_apps::Nodelet } case opencv_apps::EdgeDetection_Canny: { - int edgeThresh = 1; + int edge_thresh = 1; int kernel_size = 3; int const max_canny_threshold1 = 500; int const max_canny_threshold2 = 500; @@ -273,7 +273,7 @@ class EdgeDetectionNodelet : public opencv_apps::Nodelet prev_stamp_ = msg->header.stamp; } - void subscribe() + void subscribe() override { NODELET_DEBUG("Subscribing to image topic."); if (config_.use_camera_info) @@ -282,7 +282,7 @@ class EdgeDetectionNodelet : public opencv_apps::Nodelet img_sub_ = it_->subscribe("image", queue_size_, &EdgeDetectionNodelet::imageCallback, this); } - void unsubscribe() + void unsubscribe() override { NODELET_DEBUG("Unsubscribing from image topic."); img_sub_.shutdown(); @@ -290,7 +290,7 @@ class EdgeDetectionNodelet : public opencv_apps::Nodelet } public: - virtual void onInit() + void onInit() override { Nodelet::onInit(); it_ = boost::shared_ptr(new image_transport::ImageTransport(*nh_)); @@ -327,7 +327,7 @@ namespace edge_detection class EdgeDetectionNodelet : public opencv_apps::EdgeDetectionNodelet { public: - virtual void onInit() + void onInit() override { ROS_WARN("DeprecationWarning: Nodelet edge_detection/edge_detection is deprecated, " "and renamed to opencv_apps/edge_detection."); diff --git a/src/nodelet/face_detection_nodelet.cpp b/src/nodelet/face_detection_nodelet.cpp index 5d0f9d84..d3c5376c 100644 --- a/src/nodelet/face_detection_nodelet.cpp +++ b/src/nodelet/face_detection_nodelet.cpp @@ -94,15 +94,15 @@ class FaceDetectionNodelet : public opencv_apps::Nodelet void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info) { - do_work(msg, cam_info->header.frame_id); + doWork(msg, cam_info->header.frame_id); } void imageCallback(const sensor_msgs::ImageConstPtr& msg) { - do_work(msg, msg->header.frame_id); + doWork(msg, msg->header.frame_id); } - void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg) + void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg) { // Work on the image. try @@ -135,51 +135,51 @@ class FaceDetectionNodelet : public opencv_apps::Nodelet #endif cv::Mat face_image; - if (faces.size() > 0) + if (!faces.empty()) { cv::Rect max_area = faces[0]; - for (size_t i = 0; i < faces.size(); i++) + for (const cv::Rect& face : faces) { - if (max_area.width * max_area.height > faces[i].width * faces[i].height) + if (max_area.width * max_area.height > face.width * face.height) { - max_area = faces[i]; + max_area = face; } } face_image = frame(max_area).clone(); } - for (size_t i = 0; i < faces.size(); i++) + for (const cv::Rect& face : faces) { - cv::Point center(faces[i].x + faces[i].width / 2, faces[i].y + faces[i].height / 2); - cv::ellipse(frame, center, cv::Size(faces[i].width / 2, faces[i].height / 2), 0, 0, 360, - cv::Scalar(255, 0, 255), 2, 8, 0); + cv::Point center(face.x + face.width / 2, face.y + face.height / 2); + cv::ellipse(frame, center, cv::Size(face.width / 2, face.height / 2), 0, 0, 360, cv::Scalar(255, 0, 255), 2, 8, + 0); opencv_apps::Face face_msg; face_msg.face.x = center.x; face_msg.face.y = center.y; - face_msg.face.width = faces[i].width; - face_msg.face.height = faces[i].height; + face_msg.face.width = face.width; + face_msg.face.height = face.height; - cv::Mat faceROI = frame_gray(faces[i]); + cv::Mat face_roi = frame_gray(face); std::vector eyes; //-- In each face, detect eyes #ifndef CV_VERSION_EPOCH - eyes_cascade_.detectMultiScale(faceROI, eyes, 1.1, 2, 0, cv::Size(30, 30)); + eyes_cascade_.detectMultiScale(face_roi, eyes, 1.1, 2, 0, cv::Size(30, 30)); #else - eyes_cascade_.detectMultiScale(faceROI, eyes, 1.1, 2, 0 | CV_HAAR_SCALE_IMAGE, cv::Size(30, 30)); + eyes_cascade_.detectMultiScale(face_roi, eyes, 1.1, 2, 0 | CV_HAAR_SCALE_IMAGE, cv::Size(30, 30)); #endif - for (size_t j = 0; j < eyes.size(); j++) + for (const cv::Rect& eye : eyes) { - cv::Point eye_center(faces[i].x + eyes[j].x + eyes[j].width / 2, faces[i].y + eyes[j].y + eyes[j].height / 2); - int radius = cvRound((eyes[j].width + eyes[j].height) * 0.25); + cv::Point eye_center(face.x + eye.x + eye.width / 2, face.y + eye.y + eye.height / 2); + int radius = cvRound((eye.width + eye.height) * 0.25); cv::circle(frame, eye_center, radius, cv::Scalar(255, 0, 0), 3, 8, 0); opencv_apps::Rect eye_msg; eye_msg.x = eye_center.x; eye_msg.y = eye_center.y; - eye_msg.width = eyes[j].width; - eye_msg.height = eyes[j].height; + eye_msg.width = eye.width; + eye_msg.height = eye.height; face_msg.eyes.push_back(eye_msg); } @@ -197,7 +197,7 @@ class FaceDetectionNodelet : public opencv_apps::Nodelet cv_bridge::CvImage(msg->header, sensor_msgs::image_encodings::BGR8, frame).toImageMsg(); img_pub_.publish(out_img); msg_pub_.publish(faces_msg); - if (faces.size() > 0) + if (!faces.empty()) { sensor_msgs::Image::Ptr out_face_img = cv_bridge::CvImage(msg->header, sensor_msgs::image_encodings::BGR8, face_image).toImageMsg(); @@ -212,7 +212,7 @@ class FaceDetectionNodelet : public opencv_apps::Nodelet prev_stamp_ = msg->header.stamp; } - void subscribe() + void subscribe() override { NODELET_DEBUG("Subscribing to image topic."); if (config_.use_camera_info) @@ -221,7 +221,7 @@ class FaceDetectionNodelet : public opencv_apps::Nodelet img_sub_ = it_->subscribe("image", queue_size_, &FaceDetectionNodelet::imageCallback, this); } - void unsubscribe() + void unsubscribe() override { NODELET_DEBUG("Unsubscribing from image topic."); img_sub_.shutdown(); @@ -229,7 +229,7 @@ class FaceDetectionNodelet : public opencv_apps::Nodelet } public: - virtual void onInit() + void onInit() override { Nodelet::onInit(); it_ = boost::shared_ptr(new image_transport::ImageTransport(*nh_)); @@ -276,7 +276,7 @@ namespace face_detection class FaceDetectionNodelet : public opencv_apps::FaceDetectionNodelet { public: - virtual void onInit() + void onInit() override { ROS_WARN("DeprecationWarning: Nodelet face_detection/face_detection is deprecated, " "and renamed to opencv_apps/face_detection."); diff --git a/src/nodelet/face_recognition_nodelet.cpp b/src/nodelet/face_recognition_nodelet.cpp index 9ed51994..244dacd3 100644 --- a/src/nodelet/face_recognition_nodelet.cpp +++ b/src/nodelet/face_recognition_nodelet.cpp @@ -103,7 +103,7 @@ path user_expanded_path(const path& p) if (user_dir.length() == 1) { homedir = getenv("HOME"); - if (homedir == NULL) + if (homedir == nullptr) { homedir = getpwuid(getuid())->pw_dir; } @@ -112,15 +112,15 @@ path user_expanded_path(const path& p) { std::string uname = user_dir.substr(1, user_dir.length()); passwd* pw = getpwnam(uname.c_str()); - if (pw == NULL) + if (pw == nullptr) return p; homedir = pw->pw_dir; } ret = path(std::string(homedir)); return ret.append(++it, p.end(), path::codecvt()); } -} -} // end of utility for resolving paths +} // namespace filesystem +} // namespace boost namespace opencv_apps { @@ -137,11 +137,11 @@ class LabelMapper if (id < it->second) id = it->second + 1; } - for (size_t i = 0; i < l.size(); ++i) + for (const std::string& i : l) { - if (m_.find(l[i]) == m_.end()) + if (m_.find(i) == m_.end()) { - m_[l[i]] = id; + m_[i] = id; id++; } } @@ -372,7 +372,7 @@ class FaceRecognitionNodelet : public opencv_apps::Nodelet storage_->load(images, labels); } - if (images.size() == 0) + if (images.empty()) return; std::vector resized_images(images.size()); @@ -461,7 +461,7 @@ class FaceRecognitionNodelet : public opencv_apps::Nodelet try { std::vector images(req.images.size()); - bool use_roi = req.rects.size() == 0 ? false : true; + bool use_roi = !req.rects.empty(); if (use_roi && req.images.size() != req.rects.size()) { @@ -617,7 +617,7 @@ class FaceRecognitionNodelet : public opencv_apps::Nodelet config_ = config; } - void subscribe() + void subscribe() override { NODELET_DEBUG("subscribe"); img_sub_.subscribe(*it_, "image", 1); @@ -636,7 +636,7 @@ class FaceRecognitionNodelet : public opencv_apps::Nodelet } } - void unsubscribe() + void unsubscribe() override { NODELET_DEBUG("unsubscribe"); img_sub_.unsubscribe(); @@ -644,7 +644,7 @@ class FaceRecognitionNodelet : public opencv_apps::Nodelet } public: - virtual void onInit() + void onInit() override { Nodelet::onInit(); @@ -676,7 +676,7 @@ namespace face_recognition class FaceRecognitionNodelet : public opencv_apps::FaceRecognitionNodelet { public: - virtual void onInit() + void onInit() override { ROS_WARN("DeprecationWarning: Nodelet face_recognition/face_recognition is deprecated, " "and renamed to opencv_apps/face_recognition."); diff --git a/src/nodelet/fback_flow_nodelet.cpp b/src/nodelet/fback_flow_nodelet.cpp index 604e1b32..724e9868 100644 --- a/src/nodelet/fback_flow_nodelet.cpp +++ b/src/nodelet/fback_flow_nodelet.cpp @@ -91,20 +91,20 @@ class FBackFlowNodelet : public opencv_apps::Nodelet void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info) { - do_work(msg, cam_info->header.frame_id); + doWork(msg, cam_info->header.frame_id); } void imageCallback(const sensor_msgs::ImageConstPtr& msg) { - do_work(msg, msg->header.frame_id); + doWork(msg, msg->header.frame_id); } - static void trackbarCallback(int, void*) + static void trackbarCallback(int /*unused*/, void* /*unused*/) { need_config_update_ = true; } - void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg) + void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg) { // Work on the image. try @@ -191,7 +191,7 @@ class FBackFlowNodelet : public opencv_apps::Nodelet prev_stamp_ = msg->header.stamp; } - void subscribe() + void subscribe() override { NODELET_DEBUG("Subscribing to image topic."); if (config_.use_camera_info) @@ -200,7 +200,7 @@ class FBackFlowNodelet : public opencv_apps::Nodelet img_sub_ = it_->subscribe("image", queue_size_, &FBackFlowNodelet::imageCallback, this); } - void unsubscribe() + void unsubscribe() override { NODELET_DEBUG("Unsubscribing from image topic."); img_sub_.shutdown(); @@ -208,7 +208,7 @@ class FBackFlowNodelet : public opencv_apps::Nodelet } public: - virtual void onInit() + void onInit() override { Nodelet::onInit(); it_ = boost::shared_ptr(new image_transport::ImageTransport(*nh_)); @@ -242,7 +242,7 @@ namespace fback_flow class FBackFlowNodelet : public opencv_apps::FBackFlowNodelet { public: - virtual void onInit() + void onInit() override { ROS_WARN("DeprecationWarning: Nodelet fback_flow/fback_flow is deprecated, " "and renamed to opencv_apps/fback_flow."); diff --git a/src/nodelet/find_contours_nodelet.cpp b/src/nodelet/find_contours_nodelet.cpp index 732c6f33..0e05b1bc 100644 --- a/src/nodelet/find_contours_nodelet.cpp +++ b/src/nodelet/find_contours_nodelet.cpp @@ -95,20 +95,20 @@ class FindContoursNodelet : public opencv_apps::Nodelet void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info) { - do_work(msg, cam_info->header.frame_id); + doWork(msg, cam_info->header.frame_id); } void imageCallback(const sensor_msgs::ImageConstPtr& msg) { - do_work(msg, msg->header.frame_id); + doWork(msg, msg->header.frame_id); } - static void trackbarCallback(int, void*) + static void trackbarCallback(int /*unused*/, void* /*unused*/) { need_config_update_ = true; } - void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg) + void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg) { // Work on the image. try @@ -163,11 +163,11 @@ class FindContoursNodelet : public opencv_apps::Nodelet cv::drawContours(drawing, contours, (int)i, color, 2, 8, hierarchy, 0, cv::Point()); opencv_apps::Contour contour_msg; - for (size_t j = 0; j < contours[i].size(); j++) + for (const cv::Point& j : contours[i]) { opencv_apps::Point2D point_msg; - point_msg.x = contours[i][j].x; - point_msg.y = contours[i][j].y; + point_msg.x = j.x; + point_msg.y = j.y; contour_msg.points.push_back(point_msg); } contours_msg.contours.push_back(contour_msg); @@ -202,7 +202,7 @@ class FindContoursNodelet : public opencv_apps::Nodelet prev_stamp_ = msg->header.stamp; } - void subscribe() + void subscribe() override { NODELET_DEBUG("Subscribing to image topic."); if (config_.use_camera_info) @@ -211,7 +211,7 @@ class FindContoursNodelet : public opencv_apps::Nodelet img_sub_ = it_->subscribe("image", queue_size_, &FindContoursNodelet::imageCallback, this); } - void unsubscribe() + void unsubscribe() override { NODELET_DEBUG("Unsubscribing from image topic."); img_sub_.shutdown(); @@ -219,7 +219,7 @@ class FindContoursNodelet : public opencv_apps::Nodelet } public: - virtual void onInit() + void onInit() override { Nodelet::onInit(); it_ = boost::shared_ptr(new image_transport::ImageTransport(*nh_)); @@ -254,7 +254,7 @@ namespace find_contours class FindContoursNodelet : public opencv_apps::FindContoursNodelet { public: - virtual void onInit() + void onInit() override { ROS_WARN("DeprecationWarning: Nodelet find_contours/find_contours is deprecated, " "and renamed to opencv_apps/find_contours."); diff --git a/src/nodelet/general_contours_nodelet.cpp b/src/nodelet/general_contours_nodelet.cpp index aaf18a6b..dc886720 100644 --- a/src/nodelet/general_contours_nodelet.cpp +++ b/src/nodelet/general_contours_nodelet.cpp @@ -95,20 +95,20 @@ class GeneralContoursNodelet : public opencv_apps::Nodelet void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info) { - do_work(msg, cam_info->header.frame_id); + doWork(msg, cam_info->header.frame_id); } void imageCallback(const sensor_msgs::ImageConstPtr& msg) { - do_work(msg, msg->header.frame_id); + doWork(msg, msg->header.frame_id); } - static void trackbarCallback(int, void*) + static void trackbarCallback(int /*unused*/, void* /*unused*/) { need_config_update_ = true; } - void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg) + void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg) { // Work on the image. try @@ -154,15 +154,15 @@ class GeneralContoursNodelet : public opencv_apps::Nodelet cv::findContours(threshold_output, contours, hierarchy, CV_RETR_TREE, CV_CHAIN_APPROX_SIMPLE, cv::Point(0, 0)); /// Find the rotated rectangles and ellipses for each contour - std::vector minRect(contours.size()); - std::vector minEllipse(contours.size()); + std::vector min_rect(contours.size()); + std::vector min_ellipse(contours.size()); for (size_t i = 0; i < contours.size(); i++) { - minRect[i] = cv::minAreaRect(cv::Mat(contours[i])); + min_rect[i] = cv::minAreaRect(cv::Mat(contours[i])); if (contours[i].size() > 5) { - minEllipse[i] = cv::fitEllipse(cv::Mat(contours[i])); + min_ellipse[i] = cv::fitEllipse(cv::Mat(contours[i])); } } @@ -174,33 +174,33 @@ class GeneralContoursNodelet : public opencv_apps::Nodelet // contour cv::drawContours(drawing, contours, (int)i, color, 1, 8, std::vector(), 0, cv::Point()); // ellipse - cv::ellipse(drawing, minEllipse[i], color, 2, 8); + cv::ellipse(drawing, min_ellipse[i], color, 2, 8); // rotated rectangle cv::Point2f rect_points[4]; - minRect[i].points(rect_points); + min_rect[i].points(rect_points); for (int j = 0; j < 4; j++) cv::line(drawing, rect_points[j], rect_points[(j + 1) % 4], color, 1, 8); opencv_apps::RotatedRect rect_msg; opencv_apps::Point2D rect_center; opencv_apps::Size rect_size; - rect_center.x = minRect[i].center.x; - rect_center.y = minRect[i].center.y; - rect_size.width = minRect[i].size.width; - rect_size.height = minRect[i].size.height; + rect_center.x = min_rect[i].center.x; + rect_center.y = min_rect[i].center.y; + rect_size.width = min_rect[i].size.width; + rect_size.height = min_rect[i].size.height; rect_msg.center = rect_center; rect_msg.size = rect_size; - rect_msg.angle = minRect[i].angle; + rect_msg.angle = min_rect[i].angle; opencv_apps::RotatedRect ellipse_msg; opencv_apps::Point2D ellipse_center; opencv_apps::Size ellipse_size; - ellipse_center.x = minEllipse[i].center.x; - ellipse_center.y = minEllipse[i].center.y; - ellipse_size.width = minEllipse[i].size.width; - ellipse_size.height = minEllipse[i].size.height; + ellipse_center.x = min_ellipse[i].center.x; + ellipse_center.y = min_ellipse[i].center.y; + ellipse_size.width = min_ellipse[i].size.width; + ellipse_size.height = min_ellipse[i].size.height; ellipse_msg.center = ellipse_center; ellipse_msg.size = ellipse_size; - ellipse_msg.angle = minEllipse[i].angle; + ellipse_msg.angle = min_ellipse[i].angle; rects_msg.rects.push_back(rect_msg); ellipses_msg.rects.push_back(ellipse_msg); @@ -236,7 +236,7 @@ class GeneralContoursNodelet : public opencv_apps::Nodelet prev_stamp_ = msg->header.stamp; } - void subscribe() + void subscribe() override { NODELET_DEBUG("Subscribing to image topic."); if (config_.use_camera_info) @@ -245,7 +245,7 @@ class GeneralContoursNodelet : public opencv_apps::Nodelet img_sub_ = it_->subscribe("image", queue_size_, &GeneralContoursNodelet::imageCallback, this); } - void unsubscribe() + void unsubscribe() override { NODELET_DEBUG("Unsubscribing from image topic."); img_sub_.shutdown(); @@ -253,7 +253,7 @@ class GeneralContoursNodelet : public opencv_apps::Nodelet } public: - virtual void onInit() + void onInit() override { Nodelet::onInit(); it_ = boost::shared_ptr(new image_transport::ImageTransport(*nh_)); @@ -289,7 +289,7 @@ namespace general_contours class GeneralContoursNodelet : public opencv_apps::GeneralContoursNodelet { public: - virtual void onInit() + void onInit() override { ROS_WARN("DeprecationWarning: Nodelet general_contours/general_contours is deprecated, " "and renamed to opencv_apps/general_contours."); diff --git a/src/nodelet/goodfeature_track_nodelet.cpp b/src/nodelet/goodfeature_track_nodelet.cpp index 406f9532..5c63924f 100644 --- a/src/nodelet/goodfeature_track_nodelet.cpp +++ b/src/nodelet/goodfeature_track_nodelet.cpp @@ -93,20 +93,20 @@ class GoodfeatureTrackNodelet : public opencv_apps::Nodelet void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info) { - do_work(msg, cam_info->header.frame_id); + doWork(msg, cam_info->header.frame_id); } void imageCallback(const sensor_msgs::ImageConstPtr& msg) { - do_work(msg, msg->header.frame_id); + doWork(msg, msg->header.frame_id); } - static void trackbarCallback(int, void*) + static void trackbarCallback(int /*unused*/, void* /*unused*/) { need_config_update_ = true; } - void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg) + void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg) { // Work on the image. try @@ -120,7 +120,7 @@ class GoodfeatureTrackNodelet : public opencv_apps::Nodelet // Do the work cv::Mat src_gray; - int maxTrackbar = 100; + int max_trackbar = 100; if (frame.channels() > 1) { @@ -136,7 +136,7 @@ class GoodfeatureTrackNodelet : public opencv_apps::Nodelet { /// Create Trackbars for Thresholds cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE); - cv::createTrackbar("Max corners", window_name_, &max_corners_, maxTrackbar, trackbarCallback); + cv::createTrackbar("Max corners", window_name_, &max_corners_, max_trackbar, trackbarCallback); if (need_config_update_) { config_.max_corners = max_corners_; @@ -153,25 +153,25 @@ class GoodfeatureTrackNodelet : public opencv_apps::Nodelet /// Parameters for Shi-Tomasi algorithm std::vector corners; - double qualityLevel = 0.01; - double minDistance = 10; - int blockSize = 3; - bool useHarrisDetector = false; + double quality_level = 0.01; + double min_distance = 10; + int block_size = 3; + bool use_harris_detector = false; double k = 0.04; cv::RNG rng(12345); /// Apply corner detection - cv::goodFeaturesToTrack(src_gray, corners, max_corners_, qualityLevel, minDistance, cv::Mat(), blockSize, - useHarrisDetector, k); + cv::goodFeaturesToTrack(src_gray, corners, max_corners_, quality_level, min_distance, cv::Mat(), block_size, + use_harris_detector, k); /// Draw corners detected NODELET_INFO_STREAM("** Number of corners detected: " << corners.size()); int r = 4; - for (size_t i = 0; i < corners.size(); i++) + for (const cv::Point2f& corner : corners) { - cv::circle(frame, corners[i], r, cv::Scalar(rng.uniform(0, 255), rng.uniform(0, 255), rng.uniform(0, 255)), -1, - 8, 0); + cv::circle(frame, corner, r, cv::Scalar(rng.uniform(0, 255), rng.uniform(0, 255), rng.uniform(0, 255)), -1, 8, + 0); } //-- Show what you got @@ -182,11 +182,11 @@ class GoodfeatureTrackNodelet : public opencv_apps::Nodelet } // Create msgs - for (size_t i = 0; i < corners.size(); i++) + for (const cv::Point2f& i : corners) { opencv_apps::Point2D corner; - corner.x = corners[i].x; - corner.y = corners[i].y; + corner.x = i.x; + corner.y = i.y; corners_msg.points.push_back(corner); } // Publish the image. @@ -202,7 +202,7 @@ class GoodfeatureTrackNodelet : public opencv_apps::Nodelet prev_stamp_ = msg->header.stamp; } - void subscribe() + void subscribe() override { NODELET_DEBUG("Subscribing to image topic."); if (config_.use_camera_info) @@ -211,7 +211,7 @@ class GoodfeatureTrackNodelet : public opencv_apps::Nodelet img_sub_ = it_->subscribe("image", queue_size_, &GoodfeatureTrackNodelet::imageCallback, this); } - void unsubscribe() + void unsubscribe() override { NODELET_DEBUG("Unsubscribing from image topic."); img_sub_.shutdown(); @@ -219,7 +219,7 @@ class GoodfeatureTrackNodelet : public opencv_apps::Nodelet } public: - virtual void onInit() + void onInit() override { Nodelet::onInit(); it_ = boost::shared_ptr(new image_transport::ImageTransport(*nh_)); @@ -254,7 +254,7 @@ namespace goodfeature_track class GoodfeatureTrackNodelet : public opencv_apps::GoodfeatureTrackNodelet { public: - virtual void onInit() + void onInit() override { ROS_WARN("DeprecationWarning: Nodelet goodfeature_track/goodfeature_track is deprecated, " "and renamed to opencv_apps/goodfeature_track."); diff --git a/src/nodelet/hough_circles_nodelet.cpp b/src/nodelet/hough_circles_nodelet.cpp index 687f606b..681c191a 100644 --- a/src/nodelet/hough_circles_nodelet.cpp +++ b/src/nodelet/hough_circles_nodelet.cpp @@ -134,12 +134,12 @@ class HoughCirclesNodelet : public opencv_apps::Nodelet void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info) { - do_work(msg, cam_info->header.frame_id); + doWork(msg, cam_info->header.frame_id); } void imageCallback(const sensor_msgs::ImageConstPtr& msg) { - do_work(msg, msg->header.frame_id); + doWork(msg, msg->header.frame_id); } static void trackbarCallback(int value, void* userdata) @@ -147,7 +147,7 @@ class HoughCirclesNodelet : public opencv_apps::Nodelet need_config_update_ = true; } - void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg) + void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg) { // Work on the image. try @@ -250,10 +250,10 @@ class HoughCirclesNodelet : public opencv_apps::Nodelet } // clone the colour, input image for displaying purposes - for (size_t i = 0; i < circles.size(); i++) + for (const cv::Vec3f& i : circles) { - cv::Point center(cvRound(circles[i][0]), cvRound(circles[i][1])); - int radius = cvRound(circles[i][2]); + cv::Point center(cvRound(i[0]), cvRound(i[1])); + int radius = cvRound(i[2]); // circle center circle(out_image, center, 3, cv::Scalar(0, 255, 0), -1, 8, 0); // circle outline @@ -314,7 +314,7 @@ class HoughCirclesNodelet : public opencv_apps::Nodelet prev_stamp_ = msg->header.stamp; } - void subscribe() + void subscribe() override { NODELET_DEBUG("Subscribing to image topic."); if (config_.use_camera_info) @@ -323,7 +323,7 @@ class HoughCirclesNodelet : public opencv_apps::Nodelet img_sub_ = it_->subscribe("image", queue_size_, &HoughCirclesNodelet::imageCallback, this); } - void unsubscribe() + void unsubscribe() override { NODELET_DEBUG("Unsubscribing from image topic."); img_sub_.shutdown(); @@ -331,7 +331,7 @@ class HoughCirclesNodelet : public opencv_apps::Nodelet } public: - virtual void onInit() + void onInit() override { Nodelet::onInit(); it_ = boost::shared_ptr(new image_transport::ImageTransport(*nh_)); @@ -378,7 +378,7 @@ namespace hough_circles class HoughCirclesNodelet : public opencv_apps::HoughCirclesNodelet { public: - virtual void onInit() + void onInit() override { ROS_WARN("DeprecationWarning: Nodelet hough_circles/hough_circles is deprecated, " "and renamed to opencv_apps/hough_circles."); diff --git a/src/nodelet/hough_lines_nodelet.cpp b/src/nodelet/hough_lines_nodelet.cpp index e50ae958..98fec48a 100644 --- a/src/nodelet/hough_lines_nodelet.cpp +++ b/src/nodelet/hough_lines_nodelet.cpp @@ -105,20 +105,20 @@ class HoughLinesNodelet : public opencv_apps::Nodelet void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info) { - do_work(msg, cam_info->header.frame_id); + doWork(msg, cam_info->header.frame_id); } void imageCallback(const sensor_msgs::ImageConstPtr& msg) { - do_work(msg, msg->header.frame_id); + doWork(msg, msg->header.frame_id); } - static void trackbarCallback(int, void*) + static void trackbarCallback(int /*unused*/, void* /*unused*/) { need_config_update_ = true; } - void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg) + void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg) { // Work on the image. try @@ -195,9 +195,9 @@ class HoughLinesNodelet : public opencv_apps::Nodelet cv::HoughLines(in_image, s_lines, rho_, theta_ * CV_PI / 180, threshold_, minLineLength_, maxLineGap_); /// Show the result - for (size_t i = 0; i < s_lines.size(); i++) + for (const cv::Vec2f& s_line : s_lines) { - float r = s_lines[i][0], t = s_lines[i][1]; + float r = s_line[0], t = s_line[1]; double cos_t = cos(t), sin_t = sin(t); double x0 = r * cos_t, y0 = r * sin_t; double alpha = 1000; @@ -228,9 +228,8 @@ class HoughLinesNodelet : public opencv_apps::Nodelet cv::HoughLinesP(in_image, p_lines, rho_, theta_ * CV_PI / 180, threshold_, minLineLength_, maxLineGap_); /// Show the result - for (size_t i = 0; i < p_lines.size(); i++) + for (const cv::Vec4i& l : p_lines) { - cv::Vec4i l = p_lines[i]; #ifndef CV_VERSION_EPOCH cv::line(out_image, cv::Point(l[0], l[1]), cv::Point(l[2], l[3]), cv::Scalar(255, 0, 0), 3, cv::LINE_AA); #else @@ -268,7 +267,7 @@ class HoughLinesNodelet : public opencv_apps::Nodelet prev_stamp_ = msg->header.stamp; } - void subscribe() + void subscribe() override { NODELET_DEBUG("Subscribing to image topic."); if (config_.use_camera_info) @@ -277,7 +276,7 @@ class HoughLinesNodelet : public opencv_apps::Nodelet img_sub_ = it_->subscribe("image", queue_size_, &HoughLinesNodelet::imageCallback, this); } - void unsubscribe() + void unsubscribe() override { NODELET_DEBUG("Unsubscribing from image topic."); img_sub_.shutdown(); @@ -285,7 +284,7 @@ class HoughLinesNodelet : public opencv_apps::Nodelet } public: - virtual void onInit() + void onInit() override { Nodelet::onInit(); it_ = boost::shared_ptr(new image_transport::ImageTransport(*nh_)); @@ -322,7 +321,7 @@ namespace hough_lines class HoughLinesNodelet : public opencv_apps::HoughLinesNodelet { public: - virtual void onInit() + void onInit() override { ROS_WARN("DeprecationWarning: Nodelet hough_lines/hough_lines is deprecated, " "and renamed to opencv_apps/hough_lines."); diff --git a/src/nodelet/lk_flow_nodelet.cpp b/src/nodelet/lk_flow_nodelet.cpp index f08b3f53..0d17bb8c 100644 --- a/src/nodelet/lk_flow_nodelet.cpp +++ b/src/nodelet/lk_flow_nodelet.cpp @@ -110,12 +110,12 @@ class LKFlowNodelet : public opencv_apps::Nodelet void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info) { - do_work(msg, cam_info->header.frame_id); + doWork(msg, cam_info->header.frame_id); } void imageCallback(const sensor_msgs::ImageConstPtr& msg) { - do_work(msg, msg->header.frame_id); + doWork(msg, msg->header.frame_id); } #if 0 static void onMouse( int event, int x, int y, int /*flags*/, void* /*param*/ ) @@ -127,12 +127,12 @@ class LKFlowNodelet : public opencv_apps::Nodelet } } #endif - static void trackbarCallback(int, void*) + static void trackbarCallback(int /*unused*/, void* /*unused*/) { need_config_update_ = true; } - void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg) + void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg) { // Work on the image. try @@ -166,7 +166,7 @@ class LKFlowNodelet : public opencv_apps::Nodelet // Do the work cv::TermCriteria termcrit(cv::TermCriteria::MAX_ITER + cv::TermCriteria::EPS, 20, 0.03); - cv::Size subPixWinSize(10, 10), winSize(31, 31); + cv::Size sub_pix_win_size(10, 10), win_size(31, 31); if (image.channels() > 1) { @@ -185,7 +185,7 @@ class LKFlowNodelet : public opencv_apps::Nodelet // automatic initialization cv::goodFeaturesToTrack(gray, points[1], MAX_COUNT, quality_level_, min_distance_, cv::Mat(), block_size_, false, harris_k_); - cv::cornerSubPix(gray, points[1], subPixWinSize, cv::Size(-1, -1), termcrit); + cv::cornerSubPix(gray, points[1], sub_pix_win_size, cv::Size(-1, -1), termcrit); addRemovePt = false; } else if (!points[0].empty()) @@ -194,7 +194,7 @@ class LKFlowNodelet : public opencv_apps::Nodelet std::vector err; if (prevGray.empty()) gray.copyTo(prevGray); - cv::calcOpticalFlowPyrLK(prevGray, gray, points[0], points[1], status, err, winSize, 3, termcrit, 0, 0.001); + cv::calcOpticalFlowPyrLK(prevGray, gray, points[0], points[1], status, err, win_size, 3, termcrit, 0, 0.001); size_t i, k; for (i = k = 0; i < points[1].size(); i++) { @@ -232,7 +232,7 @@ class LKFlowNodelet : public opencv_apps::Nodelet { std::vector tmp; tmp.push_back(point); - cv::cornerSubPix(gray, tmp, winSize, cv::Size(-1, -1), termcrit); + cv::cornerSubPix(gray, tmp, win_size, cv::Size(-1, -1), termcrit); points[1].push_back(tmp[0]); addRemovePt = false; } @@ -275,26 +275,26 @@ class LKFlowNodelet : public opencv_apps::Nodelet prev_stamp_ = msg->header.stamp; } - bool initialize_points_cb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response) + bool initializePointsCb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response) { needToInit = true; return true; } - bool delete_points_cb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response) + bool deletePointsCb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response) { points[0].clear(); points[1].clear(); return true; } - bool toggle_night_mode_cb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response) + bool toggleNightModeCb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response) { nightMode = !nightMode; return true; } - void subscribe() + void subscribe() override { NODELET_DEBUG("Subscribing to image topic."); if (config_.use_camera_info) @@ -303,7 +303,7 @@ class LKFlowNodelet : public opencv_apps::Nodelet img_sub_ = it_->subscribe("image", queue_size_, &LKFlowNodelet::imageCallback, this); } - void unsubscribe() + void unsubscribe() override { NODELET_DEBUG("Unsubscribing from image topic."); img_sub_.shutdown(); @@ -311,7 +311,7 @@ class LKFlowNodelet : public opencv_apps::Nodelet } public: - virtual void onInit() + void onInit() override { Nodelet::onInit(); it_ = boost::shared_ptr(new image_transport::ImageTransport(*nh_)); @@ -337,11 +337,9 @@ class LKFlowNodelet : public opencv_apps::Nodelet img_pub_ = advertiseImage(*pnh_, "image", 1); msg_pub_ = advertise(*pnh_, "flows", 1); - initialize_points_service_ = - pnh_->advertiseService("initialize_points", &LKFlowNodelet::initialize_points_cb, this); - delete_points_service_ = pnh_->advertiseService("delete_points", &LKFlowNodelet::delete_points_cb, this); - toggle_night_mode_service_ = - pnh_->advertiseService("toggle_night_mode", &LKFlowNodelet::toggle_night_mode_cb, this); + initialize_points_service_ = pnh_->advertiseService("initialize_points", &LKFlowNodelet::initializePointsCb, this); + delete_points_service_ = pnh_->advertiseService("delete_points", &LKFlowNodelet::deletePointsCb, this); + toggle_night_mode_service_ = pnh_->advertiseService("toggle_night_mode", &LKFlowNodelet::toggleNightModeCb, this); NODELET_INFO("Hot keys: "); NODELET_INFO("\tESC - quit the program"); @@ -361,7 +359,7 @@ namespace lk_flow class LKFlowNodelet : public opencv_apps::LKFlowNodelet { public: - virtual void onInit() + void onInit() override { ROS_WARN("DeprecationWarning: Nodelet lk_flow/lk_flow is deprecated, " "and renamed to opencv_apps/lk_flow."); diff --git a/src/nodelet/nodelet.cpp b/src/nodelet/nodelet.cpp index af5b30a6..b4175e99 100644 --- a/src/nodelet/nodelet.cpp +++ b/src/nodelet/nodelet.cpp @@ -79,9 +79,8 @@ void Nodelet::connectionCallback(const ros::SingleSubscriberPublisher& pub) if (!always_subscribe_) { boost::mutex::scoped_lock lock(connection_mutex_); - for (size_t i = 0; i < publishers_.size(); i++) + for (const ros::Publisher& pub : publishers_) { - ros::Publisher pub = publishers_[i]; if (pub.getNumSubscribers() > 0) { if (!ever_subscribed_) @@ -121,9 +120,8 @@ void Nodelet::imageConnectionCallback(const image_transport::SingleSubscriberPub if (!always_subscribe_) { boost::mutex::scoped_lock lock(connection_mutex_); - for (size_t i = 0; i < image_publishers_.size(); i++) + for (const image_transport::Publisher& pub : image_publishers_) { - image_transport::Publisher pub = image_publishers_[i]; if (pub.getNumSubscribers() > 0) { if (!ever_subscribed_) @@ -173,9 +171,8 @@ void Nodelet::cameraConnectionBaseCallback() if (!always_subscribe_) { boost::mutex::scoped_lock lock(connection_mutex_); - for (size_t i = 0; i < camera_publishers_.size(); i++) + for (const image_transport::CameraPublisher& pub : camera_publishers_) { - image_transport::CameraPublisher pub = camera_publishers_[i]; if (pub.getNumSubscribers() > 0) { if (!ever_subscribed_) @@ -205,4 +202,4 @@ void Nodelet::cameraConnectionBaseCallback() } } } -} +} // namespace opencv_apps diff --git a/src/nodelet/people_detect_nodelet.cpp b/src/nodelet/people_detect_nodelet.cpp index 8ac6e42e..45171780 100644 --- a/src/nodelet/people_detect_nodelet.cpp +++ b/src/nodelet/people_detect_nodelet.cpp @@ -103,20 +103,20 @@ class PeopleDetectNodelet : public opencv_apps::Nodelet void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info) { - do_work(msg, cam_info->header.frame_id); + doWork(msg, cam_info->header.frame_id); } void imageCallback(const sensor_msgs::ImageConstPtr& msg) { - do_work(msg, msg->header.frame_id); + doWork(msg, msg->header.frame_id); } - static void trackbarCallback(int, void*) + static void trackbarCallback(int /*unused*/, void* /*unused*/) { need_config_update_ = true; } - void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg) + void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg) { // Work on the image. try @@ -192,7 +192,7 @@ class PeopleDetectNodelet : public opencv_apps::Nodelet prev_stamp_ = msg->header.stamp; } - void subscribe() + void subscribe() override { NODELET_DEBUG("Subscribing to image topic."); if (config_.use_camera_info) @@ -201,7 +201,7 @@ class PeopleDetectNodelet : public opencv_apps::Nodelet img_sub_ = it_->subscribe("image", queue_size_, &PeopleDetectNodelet::imageCallback, this); } - void unsubscribe() + void unsubscribe() override { NODELET_DEBUG("Unsubscribing from image topic."); img_sub_.shutdown(); @@ -209,7 +209,7 @@ class PeopleDetectNodelet : public opencv_apps::Nodelet } public: - virtual void onInit() + void onInit() override { Nodelet::onInit(); it_ = boost::shared_ptr(new image_transport::ImageTransport(*nh_)); @@ -245,7 +245,7 @@ namespace people_detect class PeopleDetectNodelet : public opencv_apps::PeopleDetectNodelet { public: - virtual void onInit() + void onInit() override { ROS_WARN("DeprecationWarning: Nodelet people_detect/people_detect is deprecated, " "and renamed to opencv_apps/people_detect."); diff --git a/src/nodelet/phase_corr_nodelet.cpp b/src/nodelet/phase_corr_nodelet.cpp index 8455f108..f6e17c39 100644 --- a/src/nodelet/phase_corr_nodelet.cpp +++ b/src/nodelet/phase_corr_nodelet.cpp @@ -86,20 +86,20 @@ class PhaseCorrNodelet : public opencv_apps::Nodelet void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info) { - do_work(msg, cam_info->header.frame_id); + doWork(msg, cam_info->header.frame_id); } void imageCallback(const sensor_msgs::ImageConstPtr& msg) { - do_work(msg, msg->header.frame_id); + doWork(msg, msg->header.frame_id); } - static void trackbarCallback(int, void*) + static void trackbarCallback(int /*unused*/, void* /*unused*/) { need_config_update_ = true; } - void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg) + void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg) { // Work on the image. try @@ -184,7 +184,7 @@ class PhaseCorrNodelet : public opencv_apps::Nodelet prev_stamp_ = msg->header.stamp; } - void subscribe() + void subscribe() override { NODELET_DEBUG("Subscribing to image topic."); if (config_.use_camera_info) @@ -193,7 +193,7 @@ class PhaseCorrNodelet : public opencv_apps::Nodelet img_sub_ = it_->subscribe("image", queue_size_, &PhaseCorrNodelet::imageCallback, this); } - void unsubscribe() + void unsubscribe() override { NODELET_DEBUG("Unsubscribing from image topic."); img_sub_.shutdown(); @@ -201,7 +201,7 @@ class PhaseCorrNodelet : public opencv_apps::Nodelet } public: - virtual void onInit() + void onInit() override { Nodelet::onInit(); it_ = boost::shared_ptr(new image_transport::ImageTransport(*nh_)); @@ -235,7 +235,7 @@ namespace phase_corr class PhaseCorrNodelet : public opencv_apps::PhaseCorrNodelet { public: - virtual void onInit() + void onInit() override { ROS_WARN("DeprecationWarning: Nodelet phase_corr/phase_corr is deprecated, " "and renamed to opencv_apps/phase_corr."); diff --git a/src/nodelet/pyramids_nodelet.cpp b/src/nodelet/pyramids_nodelet.cpp index b72c29b4..8eeba0d4 100644 --- a/src/nodelet/pyramids_nodelet.cpp +++ b/src/nodelet/pyramids_nodelet.cpp @@ -91,15 +91,15 @@ class PyramidsNodelet : public opencv_apps::Nodelet void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info) { - do_work(msg, cam_info->header.frame_id); + doWork(msg, cam_info->header.frame_id); } void imageCallback(const sensor_msgs::ImageConstPtr& msg) { - do_work(msg, msg->header.frame_id); + doWork(msg, msg->header.frame_id); } - void do_work(const sensor_msgs::ImageConstPtr& image_msg, const std::string input_frame_from_msg) + void doWork(const sensor_msgs::ImageConstPtr& image_msg, const std::string& input_frame_from_msg) { // Work on the image. try @@ -148,7 +148,7 @@ class PyramidsNodelet : public opencv_apps::Nodelet } } - void subscribe() + void subscribe() override { NODELET_DEBUG("Subscribing to image topic."); if (config_.use_camera_info) @@ -157,7 +157,7 @@ class PyramidsNodelet : public opencv_apps::Nodelet img_sub_ = it_->subscribe("image", queue_size_, &PyramidsNodelet::imageCallback, this); } - void unsubscribe() + void unsubscribe() override { NODELET_DEBUG("Unsubscribing from image topic."); img_sub_.shutdown(); @@ -165,7 +165,7 @@ class PyramidsNodelet : public opencv_apps::Nodelet } public: - virtual void onInit() + void onInit() override { Nodelet::onInit(); it_ = boost::shared_ptr(new image_transport::ImageTransport(*nh_)); @@ -197,7 +197,7 @@ namespace pyramids class PyramidsNodelet : public opencv_apps::PyramidsNodelet { public: - virtual void onInit() + void onInit() override { ROS_WARN("DeprecationWarning: Nodelet pyramids/pyramids is deprecated, " "and renamed to opencv_apps/pyramids."); diff --git a/src/nodelet/segment_objects_nodelet.cpp b/src/nodelet/segment_objects_nodelet.cpp index 359361d5..58e89d78 100644 --- a/src/nodelet/segment_objects_nodelet.cpp +++ b/src/nodelet/segment_objects_nodelet.cpp @@ -100,20 +100,20 @@ class SegmentObjectsNodelet : public opencv_apps::Nodelet void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info) { - do_work(msg, cam_info->header.frame_id); + doWork(msg, cam_info->header.frame_id); } void imageCallback(const sensor_msgs::ImageConstPtr& msg) { - do_work(msg, msg->header.frame_id); + doWork(msg, msg->header.frame_id); } - static void trackbarCallback(int, void*) + static void trackbarCallback(int /*unused*/, void* /*unused*/) { need_config_update_ = true; } - void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg) + void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg) { // Work on the image. try @@ -160,37 +160,37 @@ class SegmentObjectsNodelet : public opencv_apps::Nodelet out_frame = cv::Mat::zeros(frame.size(), CV_8UC3); - if (contours.size() == 0) + if (contours.empty()) return; // iterate through all the top-level contours, // draw each connected component with its own random color - int idx = 0, largestComp = 0; - double maxArea = 0; + int idx = 0, largest_comp = 0; + double max_area = 0; for (; idx >= 0; idx = hierarchy[idx][0]) { const std::vector& c = contours[idx]; double area = fabs(cv::contourArea(cv::Mat(c))); - if (area > maxArea) + if (area > max_area) { - maxArea = area; - largestComp = idx; + max_area = area; + largest_comp = idx; } } cv::Scalar color(0, 0, 255); - cv::drawContours(out_frame, contours, largestComp, color, CV_FILLED, 8, hierarchy); + cv::drawContours(out_frame, contours, largest_comp, color, CV_FILLED, 8, hierarchy); std_msgs::Float64 area_msg; - area_msg.data = maxArea; - for (size_t i = 0; i < contours.size(); i++) + area_msg.data = max_area; + for (const std::vector& contour : contours) { opencv_apps::Contour contour_msg; - for (size_t j = 0; j < contours[i].size(); j++) + for (const cv::Point& j : contour) { opencv_apps::Point2D point_msg; - point_msg.x = contours[i][j].x; - point_msg.y = contours[i][j].y; + point_msg.x = j.x; + point_msg.y = j.y; contour_msg.points.push_back(point_msg); } contours_msg.contours.push_back(contour_msg); @@ -225,14 +225,14 @@ class SegmentObjectsNodelet : public opencv_apps::Nodelet prev_stamp_ = msg->header.stamp; } - bool update_bg_model_cb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response) + bool updateBgModelCb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response) { update_bg_model = !update_bg_model; NODELET_INFO("Learn background is in state = %d", update_bg_model); return true; } - void subscribe() + void subscribe() override { NODELET_DEBUG("Subscribing to image topic."); if (config_.use_camera_info) @@ -241,7 +241,7 @@ class SegmentObjectsNodelet : public opencv_apps::Nodelet img_sub_ = it_->subscribe("image", queue_size_, &SegmentObjectsNodelet::imageCallback, this); } - void unsubscribe() + void unsubscribe() override { NODELET_DEBUG("Unsubscribing from image topic."); img_sub_.shutdown(); @@ -249,7 +249,7 @@ class SegmentObjectsNodelet : public opencv_apps::Nodelet } public: - virtual void onInit() + void onInit() override { Nodelet::onInit(); it_ = boost::shared_ptr(new image_transport::ImageTransport(*nh_)); @@ -279,8 +279,7 @@ class SegmentObjectsNodelet : public opencv_apps::Nodelet img_pub_ = advertiseImage(*pnh_, "image", 1); msg_pub_ = advertise(*pnh_, "contours", 1); area_pub_ = advertise(*pnh_, "area", 1); - update_bg_model_service_ = - pnh_->advertiseService("update_bg_model", &SegmentObjectsNodelet::update_bg_model_cb, this); + update_bg_model_service_ = pnh_->advertiseService("update_bg_model", &SegmentObjectsNodelet::updateBgModelCb, this); onInitPostProcess(); } @@ -293,7 +292,7 @@ namespace segment_objects class SegmentObjectsNodelet : public opencv_apps::SegmentObjectsNodelet { public: - virtual void onInit() + void onInit() override { ROS_WARN("DeprecationWarning: Nodelet segment_objects/segment_objects is deprecated, " "and renamed to opencv_apps/segment_objects."); diff --git a/src/nodelet/simple_compressed_example_nodelet.cpp b/src/nodelet/simple_compressed_example_nodelet.cpp index 0a940884..610af320 100644 --- a/src/nodelet/simple_compressed_example_nodelet.cpp +++ b/src/nodelet/simple_compressed_example_nodelet.cpp @@ -71,9 +71,9 @@ class ImageConverter image_sub_ = nh_.subscribe("image/compressed", queue_size_, &ImageConverter::imageCb, this); image_pub_ = nh_.advertise("/image_converter/output_video/compressed", 1); - ros::NodeHandle pnh_("~"); - pnh_.param("queue_size", queue_size_, 3); - pnh_.param("debug_view", debug_view_, false); + ros::NodeHandle pnh("~"); + pnh.param("queue_size", queue_size_, 3); + pnh.param("debug_view", debug_view_, false); if (debug_view_) { cv::namedWindow(OPENCV_WINDOW); @@ -226,7 +226,7 @@ note : hydro 1.10.18, indigo : 1.11.13 ... class SimpleCompressedExampleNodelet : public nodelet::Nodelet { public: - virtual void onInit() + void onInit() override { simple_compressed_example::ImageConverter ic; ros::spin(); @@ -240,7 +240,7 @@ namespace simple_compressed_example class SimpleCompressedExampleNodelet : public opencv_apps::SimpleCompressedExampleNodelet { public: - virtual void onInit() + void onInit() override { ROS_WARN("DeprecationWarning: Nodelet simple_compressed_example/simple_compressed_example is deprecated, " "and renamed to opencv_apps/simple_compressed_example."); diff --git a/src/nodelet/simple_example_nodelet.cpp b/src/nodelet/simple_example_nodelet.cpp index 7389bfe6..c34a2c22 100644 --- a/src/nodelet/simple_example_nodelet.cpp +++ b/src/nodelet/simple_example_nodelet.cpp @@ -69,9 +69,9 @@ class ImageConverter image_sub_ = it_.subscribe("image", queue_size_, &ImageConverter::imageCb, this); image_pub_ = it_.advertise("/image_converter/output_video/raw", 1); - ros::NodeHandle pnh_("~"); - pnh_.param("queue_size", queue_size_, 1); - pnh_.param("debug_view", debug_view_, false); + ros::NodeHandle pnh("~"); + pnh.param("queue_size", queue_size_, 1); + pnh.param("debug_view", debug_view_, false); if (debug_view_) { cv::namedWindow(OPENCV_WINDOW); @@ -115,12 +115,12 @@ class ImageConverter } }; -} // namesapce simple_example +} // namespace simple_example class SimpleExampleNodelet : public nodelet::Nodelet { public: - virtual void onInit() + void onInit() override { simple_example::ImageConverter ic; ros::spin(); @@ -134,7 +134,7 @@ namespace simple_example class SimpleExampleNodelet : public opencv_apps::SimpleExampleNodelet { public: - virtual void onInit() + void onInit() override { ROS_WARN("DeprecationWarning: Nodelet simple_example/simple_example is deprecated, " "and renamed to opencv_apps/simple_example."); diff --git a/src/nodelet/simple_flow_nodelet.cpp b/src/nodelet/simple_flow_nodelet.cpp index 2512dd30..a8b27743 100644 --- a/src/nodelet/simple_flow_nodelet.cpp +++ b/src/nodelet/simple_flow_nodelet.cpp @@ -96,20 +96,20 @@ class SimpleFlowNodelet : public opencv_apps::Nodelet void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info) { - do_work(msg, cam_info->header.frame_id); + doWork(msg, cam_info->header.frame_id); } void imageCallback(const sensor_msgs::ImageConstPtr& msg) { - do_work(msg, msg->header.frame_id); + doWork(msg, msg->header.frame_id); } - static void trackbarCallback(int, void*) + static void trackbarCallback(int /*unused*/, void* /*unused*/) { need_config_update_ = true; } - void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg) + void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg) { // Work on the image. try @@ -224,7 +224,7 @@ class SimpleFlowNodelet : public opencv_apps::Nodelet prev_stamp_ = msg->header.stamp; } - void subscribe() + void subscribe() override { NODELET_DEBUG("Subscribing to image topic."); if (config_.use_camera_info) @@ -233,7 +233,7 @@ class SimpleFlowNodelet : public opencv_apps::Nodelet img_sub_ = it_->subscribe("image", queue_size_, &SimpleFlowNodelet::imageCallback, this); } - void unsubscribe() + void unsubscribe() override { NODELET_DEBUG("Unsubscribing from image topic."); img_sub_.shutdown(); @@ -241,7 +241,7 @@ class SimpleFlowNodelet : public opencv_apps::Nodelet } public: - virtual void onInit() + void onInit() override { Nodelet::onInit(); it_ = boost::shared_ptr(new image_transport::ImageTransport(*nh_)); @@ -276,7 +276,7 @@ namespace simple_flow class SimpleFlowNodelet : public opencv_apps::SimpleFlowNodelet { public: - virtual void onInit() + void onInit() override { ROS_WARN("DeprecationWarning: Nodelet simple_flow/simple_flow is deprecated, " "and renamed to opencv_apps/simple_flow."); diff --git a/src/nodelet/smoothing_nodelet.cpp b/src/nodelet/smoothing_nodelet.cpp index aab5e115..c1d582a9 100644 --- a/src/nodelet/smoothing_nodelet.cpp +++ b/src/nodelet/smoothing_nodelet.cpp @@ -99,20 +99,20 @@ class SmoothingNodelet : public opencv_apps::Nodelet void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info) { - do_work(msg, cam_info->header.frame_id); + doWork(msg, cam_info->header.frame_id); } void imageCallback(const sensor_msgs::ImageConstPtr& msg) { - do_work(msg, msg->header.frame_id); + doWork(msg, msg->header.frame_id); } - static void trackbarCallback(int, void*) + static void trackbarCallback(int /*unused*/, void* /*unused*/) { need_config_update_ = true; } - void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg) + void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg) { // Work on the image. try @@ -189,7 +189,7 @@ class SmoothingNodelet : public opencv_apps::Nodelet prev_stamp_ = msg->header.stamp; } - void subscribe() + void subscribe() override { NODELET_DEBUG("Subscribing to image topic."); if (config_.use_camera_info) @@ -198,7 +198,7 @@ class SmoothingNodelet : public opencv_apps::Nodelet img_sub_ = it_->subscribe("image", queue_size_, &SmoothingNodelet::imageCallback, this); } - void unsubscribe() + void unsubscribe() override { NODELET_DEBUG("Unsubscribing from image topic."); img_sub_.shutdown(); @@ -206,7 +206,7 @@ class SmoothingNodelet : public opencv_apps::Nodelet } public: - virtual void onInit() + void onInit() override { Nodelet::onInit(); it_ = boost::shared_ptr(new image_transport::ImageTransport(*nh_)); @@ -240,7 +240,7 @@ namespace smoothing class SmoothingNodelet : public opencv_apps::SmoothingNodelet { public: - virtual void onInit() + void onInit() override { ROS_WARN("DeprecationWarning: Nodelet smoothing/smoothing is deprecated, " "and renamed to opencv_apps/smoothing."); diff --git a/src/nodelet/threshold_nodelet.cpp b/src/nodelet/threshold_nodelet.cpp index 32416145..35e59985 100644 --- a/src/nodelet/threshold_nodelet.cpp +++ b/src/nodelet/threshold_nodelet.cpp @@ -82,15 +82,15 @@ class ThresholdNodelet : public opencv_apps::Nodelet void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info) { - do_work(msg, cam_info->header.frame_id); + doWork(msg, cam_info->header.frame_id); } void imageCallback(const sensor_msgs::ImageConstPtr& msg) { - do_work(msg, msg->header.frame_id); + doWork(msg, msg->header.frame_id); } - void subscribe() + void subscribe() override { NODELET_DEBUG("Subscribing to image topic."); if (config_.use_camera_info) @@ -99,7 +99,7 @@ class ThresholdNodelet : public opencv_apps::Nodelet img_sub_ = it_->subscribe("image", queue_size_, &ThresholdNodelet::imageCallback, this); } - void unsubscribe() + void unsubscribe() override { NODELET_DEBUG("Unsubscribing from image topic."); img_sub_.shutdown(); @@ -116,7 +116,7 @@ class ThresholdNodelet : public opencv_apps::Nodelet apply_otsu_ = config.apply_otsu; } - void do_work(const sensor_msgs::Image::ConstPtr& image_msg, const std::string input_frame_from_msg) + void doWork(const sensor_msgs::Image::ConstPtr& image_msg, const std::string& input_frame_from_msg) { try { @@ -147,7 +147,7 @@ class ThresholdNodelet : public opencv_apps::Nodelet } public: - virtual void onInit() + void onInit() override { Nodelet::onInit(); it_ = boost::shared_ptr(new image_transport::ImageTransport(*nh_)); @@ -177,7 +177,7 @@ namespace threshold class ThresholdNodelet : public opencv_apps::ThresholdNodelet { public: - virtual void onInit() + void onInit() override { ROS_WARN("DeprecationWarning: Nodelet threshold/threshold is deprecated, " "and renamed to opencv_apps/threshold."); diff --git a/src/nodelet/watershed_segmentation_nodelet.cpp b/src/nodelet/watershed_segmentation_nodelet.cpp index c16a8a71..97fada5f 100644 --- a/src/nodelet/watershed_segmentation_nodelet.cpp +++ b/src/nodelet/watershed_segmentation_nodelet.cpp @@ -85,7 +85,7 @@ class WatershedSegmentationNodelet : public opencv_apps::Nodelet cv::Mat markerMask; cv::Point prevPt; - static void onMouse(int event, int x, int y, int flags, void*) + static void onMouse(int event, int x, int y, int flags, void* /*unused*/) { on_mouse_update_ = true; on_mouse_event_ = event; @@ -108,20 +108,20 @@ class WatershedSegmentationNodelet : public opencv_apps::Nodelet void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info) { - do_work(msg, cam_info->header.frame_id); + doWork(msg, cam_info->header.frame_id); } void imageCallback(const sensor_msgs::ImageConstPtr& msg) { - do_work(msg, msg->header.frame_id); + doWork(msg, msg->header.frame_id); } - static void trackbarCallback(int, void*) + static void trackbarCallback(int /*unused*/, void* /*unused*/) { need_config_update_ = true; } - void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg) + void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg) { // Work on the image. try @@ -135,20 +135,20 @@ class WatershedSegmentationNodelet : public opencv_apps::Nodelet // Do the work // std::vector faces; - cv::Mat imgGray; + cv::Mat img_gray; /// Initialize if (markerMask.empty()) { cv::cvtColor(frame, markerMask, cv::COLOR_BGR2GRAY); - cv::cvtColor(markerMask, imgGray, cv::COLOR_GRAY2BGR); + cv::cvtColor(markerMask, img_gray, cv::COLOR_GRAY2BGR); markerMask = cv::Scalar::all(0); } if (debug_view_) { cv::imshow(window_name_, frame); - cv::setMouseCallback(window_name_, onMouse, 0); + cv::setMouseCallback(window_name_, onMouse, nullptr); if (need_config_update_) { reconfigure_server_->updateConfig(config_); @@ -182,7 +182,7 @@ class WatershedSegmentationNodelet : public opencv_apps::Nodelet cv::waitKey(1); } - int i, j, compCount = 0; + int i, j, comp_count = 0; std::vector > contours; std::vector hierarchy; @@ -196,35 +196,35 @@ class WatershedSegmentationNodelet : public opencv_apps::Nodelet cv::Mat markers(markerMask.size(), CV_32S); markers = cv::Scalar::all(0); int idx = 0; - for (; idx >= 0; idx = hierarchy[idx][0], compCount++) - cv::drawContours(markers, contours, idx, cv::Scalar::all(compCount + 1), -1, 8, hierarchy, INT_MAX); + for (; idx >= 0; idx = hierarchy[idx][0], comp_count++) + cv::drawContours(markers, contours, idx, cv::Scalar::all(comp_count + 1), -1, 8, hierarchy, INT_MAX); - if (compCount == 0) + if (comp_count == 0) { NODELET_WARN("compCount is 0"); return; // continue; } - for (size_t i = 0; i < contours.size(); i++) + for (const std::vector& contour : contours) { opencv_apps::Contour contour_msg; - for (size_t j = 0; j < contours[i].size(); j++) + for (const cv::Point& j : contour) { opencv_apps::Point2D point_msg; - point_msg.x = contours[i][j].x; - point_msg.y = contours[i][j].y; + point_msg.x = j.x; + point_msg.y = j.y; contour_msg.points.push_back(point_msg); } contours_msg.contours.push_back(contour_msg); } - std::vector colorTab; - for (i = 0; i < compCount; i++) + std::vector color_tab; + for (i = 0; i < comp_count; i++) { int b = cv::theRNG().uniform(0, 255); int g = cv::theRNG().uniform(0, 255); int r = cv::theRNG().uniform(0, 255); - colorTab.push_back(cv::Vec3b((uchar)b, (uchar)g, (uchar)r)); + color_tab.push_back(cv::Vec3b((uchar)b, (uchar)g, (uchar)r)); } double t = (double)cv::getTickCount(); @@ -241,13 +241,13 @@ class WatershedSegmentationNodelet : public opencv_apps::Nodelet int index = markers.at(i, j); if (index == -1) wshed.at(i, j) = cv::Vec3b(255, 255, 255); - else if (index <= 0 || index > compCount) + else if (index <= 0 || index > comp_count) wshed.at(i, j) = cv::Vec3b(0, 0, 0); else - wshed.at(i, j) = colorTab[index - 1]; + wshed.at(i, j) = color_tab[index - 1]; } - wshed = wshed * 0.5 + imgGray * 0.5; + wshed = wshed * 0.5 + img_gray * 0.5; //-- Show what you got if (debug_view_) @@ -276,24 +276,24 @@ class WatershedSegmentationNodelet : public opencv_apps::Nodelet prev_stamp_ = msg->header.stamp; } - void add_seed_point_cb(const opencv_apps::Point2DArray& msg) + void addSeedPointCb(const opencv_apps::Point2DArray& msg) { - if (msg.points.size() == 0) + if (msg.points.empty()) { markerMask = cv::Scalar::all(0); } else { - for (size_t i = 0; i < msg.points.size(); i++) + for (const opencv_apps::Point2D& point : msg.points) { - cv::Point pt0(msg.points[i].x, msg.points[i].y); + cv::Point pt0(point.x, point.y); cv::Point pt1(pt0.x + 1, pt0.y + 1); cv::line(markerMask, pt0, pt1, cv::Scalar::all(255), 5, 8, 0); } } } - void subscribe() + void subscribe() override { NODELET_DEBUG("Subscribing to image topic."); if (config_.use_camera_info) @@ -302,7 +302,7 @@ class WatershedSegmentationNodelet : public opencv_apps::Nodelet img_sub_ = it_->subscribe("image", queue_size_, &WatershedSegmentationNodelet::imageCallback, this); } - void unsubscribe() + void unsubscribe() override { NODELET_DEBUG("Unsubscribing from image topic."); img_sub_.shutdown(); @@ -310,7 +310,7 @@ class WatershedSegmentationNodelet : public opencv_apps::Nodelet } public: - virtual void onInit() + void onInit() override { Nodelet::onInit(); it_ = boost::shared_ptr(new image_transport::ImageTransport(*nh_)); @@ -333,8 +333,7 @@ class WatershedSegmentationNodelet : public opencv_apps::Nodelet boost::bind(&WatershedSegmentationNodelet::reconfigureCallback, this, _1, _2); reconfigure_server_->setCallback(f); - add_seed_points_sub_ = - pnh_->subscribe("add_seed_points", 1, &WatershedSegmentationNodelet::add_seed_point_cb, this); + add_seed_points_sub_ = pnh_->subscribe("add_seed_points", 1, &WatershedSegmentationNodelet::addSeedPointCb, this); img_pub_ = advertiseImage(*pnh_, "image", 1); msg_pub_ = advertise(*pnh_, "contours", 1); @@ -362,7 +361,7 @@ namespace watershed_segmentation class WatershedSegmentationNodelet : public opencv_apps::WatershedSegmentationNodelet { public: - virtual void onInit() + void onInit() override { ROS_WARN("DeprecationWarning: Nodelet watershed_segmentation/watershed_segmentation is deprecated, " "and renamed to opencv_apps/watershed_segmentation.");