From c10a9bd409376d81aadddceda6c4e16e563813f6 Mon Sep 17 00:00:00 2001 From: Andreas Klintberg Date: Mon, 16 Sep 2019 23:19:27 -0400 Subject: [PATCH 01/12] added crop non zero composable node --- image_proc/CMakeLists.txt | 39 +++++-- image_proc/include/crop_non_zero.hpp | 69 ++++++++++++ image_proc/src/crop_non_zero.cpp | 154 +++++++++++++++++++++++++++ 3 files changed, 254 insertions(+), 8 deletions(-) create mode 100644 image_proc/include/crop_non_zero.hpp create mode 100644 image_proc/src/crop_non_zero.cpp diff --git a/image_proc/CMakeLists.txt b/image_proc/CMakeLists.txt index 2cc43a1e2..2e2a136c9 100644 --- a/image_proc/CMakeLists.txt +++ b/image_proc/CMakeLists.txt @@ -89,6 +89,19 @@ ament_target_dependencies(crop_decimate rclcpp_components_register_nodes(crop_decimate "image_proc::CropDecimateNode") set(node_plugins "${node_plugins}image_proc::CropDecimateNode;$\n") +add_library(crop_non_zero SHARED + src/crop_non_zero.cpp +) + +target_compile_definitions(crop_non_zero + PRIVATE "COMPOSITION_BUILDING_DLL") + +ament_target_dependencies(crop_non_zero + ${dependencies} +) + +rclcpp_components_register_nodes(crop_non_zero "image_proc::CropNonZeroNode") +set(node_plugins "${node_plugins}image_proc::CropNonZeroNode;$\n") add_executable(image_proc src/image_proc.cpp @@ -112,16 +125,17 @@ install(TARGETS DESTINATION lib/${PROJECT_NAME} ) + install( - TARGETS resize - EXPORT export_resize + TARGETS crop_decimate + EXPORT export_crop_decimate ARCHIVE DESTINATION lib LIBRARY DESTINATION lib RUNTIME DESTINATION bin ) install( - TARGETS crop_decimate - EXPORT export_crop_decimate + TARGETS crop_non_zero + EXPORT export_crop_non_zero ARCHIVE DESTINATION lib LIBRARY DESTINATION lib RUNTIME DESTINATION bin @@ -140,19 +154,28 @@ install( LIBRARY DESTINATION lib RUNTIME DESTINATION bin ) +install( + TARGETS resize + EXPORT export_resize + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin +) ament_export_interfaces( - export_resize HAS_LIBRARY_TARGET + export_crop_decimate HAS_LIBRARY_TARGET + export_crop_non_zero HAS_LIBRARY_TARGET export_debayer HAS_LIBRARY_TARGET export_rectify HAS_LIBRARY_TARGET - export_crop_decimate HAS_LIBRARY_TARGET + export_resize HAS_LIBRARY_TARGET ) ament_export_libraries( - resize + crop_decimate + crop_non_zero debayer rectify - crop_decimate + resize ) if(BUILD_TESTING) diff --git a/image_proc/include/crop_non_zero.hpp b/image_proc/include/crop_non_zero.hpp new file mode 100644 index 000000000..ef9f61535 --- /dev/null +++ b/image_proc/include/crop_non_zero.hpp @@ -0,0 +1,69 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, 2019, Willow Garage, Inc., Andreas Klintberg. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +#ifndef IMAGE_PROC_PROCESSOR_H +#define IMAGE_PROC_PROCESSOR_H +#include +#include +#include +#include + +#include +#include +#include +namespace image_proc { + +class CropNonZeroNode : public rclcpp::Node +{ + public: + CropNonZeroNode(const rclcpp::NodeOptions&); + private: + std::string camera_namespace_; + std::string image_pub_; + std::string image_sub_; + + // Subscriptions + image_transport::Subscriber sub_raw_; + + // Publications + std::mutex connect_mutex_; + + image_transport::Publisher pub_; + + void connectCb(); + + void imageCb(const sensor_msgs::msg::Image::ConstSharedPtr & raw_msg); +}; +} // namespace image_proc +#endif diff --git a/image_proc/src/crop_non_zero.cpp b/image_proc/src/crop_non_zero.cpp new file mode 100644 index 000000000..e80ed2a00 --- /dev/null +++ b/image_proc/src/crop_non_zero.cpp @@ -0,0 +1,154 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ +#include +#include +#include +#include +#include "crop_non_zero.hpp" +//#include // for std::max_element + +namespace image_proc +{ + +namespace enc = sensor_msgs::image_encodings; + +CropNonZeroNode::CropNonZeroNode(const rclcpp::NodeOptions& options) : Node("CropNonZeroNode", options) +{ + auto parameter_change_cb = + [this](std::vector parameters) -> rcl_interfaces::msg::SetParametersResult { + auto result = rcl_interfaces::msg::SetParametersResult(); + result.successful = true; + for (auto parameter : parameters) + { + if (parameter.get_name() == "camera_namespace") + { + camera_namespace_ = parameter.as_string(); + RCLCPP_INFO(get_logger(), "camera_namespace: %s ", camera_namespace_.c_str()); + break; + } + image_pub_ = camera_namespace_ + "/image"; + connectCb(); + // Make sure we don't enter connectCb() between advertising and assigning to pub_depth_ + std::lock_guard lock(connect_mutex_); + RCLCPP_INFO(this->get_logger(), "publish: %s", image_pub_.c_str()); + pub_ = image_transport::create_publisher(this, image_pub_); + } + return result; + }; + + this->set_on_parameters_set_callback(parameter_change_cb); +}; + +// Handles (un)subscribing when clients (un)subscribe +void CropNonZeroNode::connectCb() +{ + image_sub_ = camera_namespace_ + "/image_raw"; + std::lock_guard lock(connect_mutex_); + /*if (pub_.getNumSubscribers() == 0) + { + sub_raw_.shutdown(); + } + else if (!sub_raw_)*/ + RCLCPP_INFO(this->get_logger(), "subscribe: %s", image_sub_.c_str()); + + sub_raw_ = image_transport::create_subscription(this, image_sub_, std::bind(&CropNonZeroNode::imageCb, this, std::placeholders::_1), "raw"); +} + +void CropNonZeroNode::imageCb(const sensor_msgs::msg::Image::ConstSharedPtr &raw_msg) +{ + cv_bridge::CvImagePtr cv_ptr; + try + { + cv_ptr = cv_bridge::toCvCopy(raw_msg); + } + catch (cv_bridge::Exception &e) + { + RCLCPP_ERROR(this->get_logger(), "cv_bridge exception: %s", e.what()); + return; + } + + // Check the number of channels + if (sensor_msgs::image_encodings::numChannels(raw_msg->encoding) != 1) + { + RCLCPP_ERROR(this->get_logger(), "Only grayscale image is acceptable, got [%s]", raw_msg->encoding.c_str()); + return; + } + + std::vector> cnt; + cv::Mat1b m(raw_msg->width, raw_msg->height); + + if (raw_msg->encoding == enc::TYPE_8UC1) + { + m = cv_ptr->image; + } + else + { + double minVal, maxVal; + cv::minMaxIdx(cv_ptr->image, &minVal, &maxVal, 0, 0, cv_ptr->image != 0.); + double ra = maxVal - minVal; + + cv_ptr->image.convertTo(m, CV_8U, 255. / ra, -minVal * 255. / ra); + } + + cv::findContours(m, cnt, CV_RETR_EXTERNAL, CV_CHAIN_APPROX_NONE); + + // search the largest area + /* // -std=c++11 + std::vector >::iterator it = std::max_element(cnt.begin(), cnt.end(), [](std::vector a, std::vector b) { + return a.size() < b.size(); + }); + */ + std::vector>::iterator it = cnt.begin(); + for (std::vector>::iterator i = cnt.begin(); i != cnt.end(); ++i) + { + it = (*it).size() < (*i).size() ? i : it; + } + cv::Rect r = cv::boundingRect(cnt[std::distance(cnt.begin(), it)]); + + cv_bridge::CvImage out_msg; + out_msg.header = raw_msg->header; + out_msg.encoding = raw_msg->encoding; + out_msg.image = cv_ptr->image(r); + + pub_.publish(out_msg.toImageMsg()); +} + +} // namespace image_proc + +#include "rclcpp_components/register_node_macro.hpp" + +// Register the component with class_loader. +// This acts as a sort of entry point, allowing the component to be discoverable when its library +// is being loaded into a running process. +RCLCPP_COMPONENTS_REGISTER_NODE(image_proc::CropNonZeroNode) \ No newline at end of file From 6490281e6cc4a607244f01d7e33a8cd6b32f4404 Mon Sep 17 00:00:00 2001 From: Andreas Klintberg Date: Mon, 28 Oct 2019 21:01:45 -0400 Subject: [PATCH 02/12] fixed indentation and uncommented std11 code --- image_proc/src/crop_non_zero.cpp | 153 ++++++++++++++----------------- 1 file changed, 71 insertions(+), 82 deletions(-) diff --git a/image_proc/src/crop_non_zero.cpp b/image_proc/src/crop_non_zero.cpp index e80ed2a00..7aa4bf54c 100644 --- a/image_proc/src/crop_non_zero.cpp +++ b/image_proc/src/crop_non_zero.cpp @@ -45,103 +45,92 @@ namespace enc = sensor_msgs::image_encodings; CropNonZeroNode::CropNonZeroNode(const rclcpp::NodeOptions& options) : Node("CropNonZeroNode", options) { - auto parameter_change_cb = - [this](std::vector parameters) -> rcl_interfaces::msg::SetParametersResult { - auto result = rcl_interfaces::msg::SetParametersResult(); - result.successful = true; - for (auto parameter : parameters) - { - if (parameter.get_name() == "camera_namespace") - { - camera_namespace_ = parameter.as_string(); - RCLCPP_INFO(get_logger(), "camera_namespace: %s ", camera_namespace_.c_str()); - break; - } - image_pub_ = camera_namespace_ + "/image"; - connectCb(); - // Make sure we don't enter connectCb() between advertising and assigning to pub_depth_ - std::lock_guard lock(connect_mutex_); - RCLCPP_INFO(this->get_logger(), "publish: %s", image_pub_.c_str()); - pub_ = image_transport::create_publisher(this, image_pub_); - } - return result; - }; - - this->set_on_parameters_set_callback(parameter_change_cb); + auto parameter_change_cb = + [this](std::vector parameters) -> rcl_interfaces::msg::SetParametersResult { + auto result = rcl_interfaces::msg::SetParametersResult(); + result.successful = true; + for (auto parameter : parameters) + { + if (parameter.get_name() == "camera_namespace") + { + camera_namespace_ = parameter.as_string(); + RCLCPP_INFO(get_logger(), "camera_namespace: %s ", camera_namespace_.c_str()); + break; + } + image_pub_ = camera_namespace_ + "/image"; + connectCb(); + // Make sure we don't enter connectCb() between advertising and assigning to pub_depth_ + std::lock_guard lock(connect_mutex_); + RCLCPP_INFO(this->get_logger(), "publish: %s", image_pub_.c_str()); + pub_ = image_transport::create_publisher(this, image_pub_); + } + return result; + }; + + this->set_on_parameters_set_callback(parameter_change_cb); }; // Handles (un)subscribing when clients (un)subscribe void CropNonZeroNode::connectCb() { - image_sub_ = camera_namespace_ + "/image_raw"; - std::lock_guard lock(connect_mutex_); - /*if (pub_.getNumSubscribers() == 0) - { - sub_raw_.shutdown(); - } - else if (!sub_raw_)*/ - RCLCPP_INFO(this->get_logger(), "subscribe: %s", image_sub_.c_str()); + image_sub_ = camera_namespace_ + "/image_raw"; + std::lock_guard lock(connect_mutex_); - sub_raw_ = image_transport::create_subscription(this, image_sub_, std::bind(&CropNonZeroNode::imageCb, this, std::placeholders::_1), "raw"); + RCLCPP_INFO(this->get_logger(), "subscribe: %s", image_sub_.c_str()); + sub_raw_ = image_transport::create_subscription(this, image_sub_, std::bind(&CropNonZeroNode::imageCb, this, std::placeholders::_1), "raw"); } void CropNonZeroNode::imageCb(const sensor_msgs::msg::Image::ConstSharedPtr &raw_msg) { - cv_bridge::CvImagePtr cv_ptr; - try - { - cv_ptr = cv_bridge::toCvCopy(raw_msg); - } - catch (cv_bridge::Exception &e) - { - RCLCPP_ERROR(this->get_logger(), "cv_bridge exception: %s", e.what()); - return; - } - - // Check the number of channels - if (sensor_msgs::image_encodings::numChannels(raw_msg->encoding) != 1) - { - RCLCPP_ERROR(this->get_logger(), "Only grayscale image is acceptable, got [%s]", raw_msg->encoding.c_str()); - return; - } - - std::vector> cnt; - cv::Mat1b m(raw_msg->width, raw_msg->height); - - if (raw_msg->encoding == enc::TYPE_8UC1) - { - m = cv_ptr->image; - } - else - { - double minVal, maxVal; - cv::minMaxIdx(cv_ptr->image, &minVal, &maxVal, 0, 0, cv_ptr->image != 0.); - double ra = maxVal - minVal; - - cv_ptr->image.convertTo(m, CV_8U, 255. / ra, -minVal * 255. / ra); - } - - cv::findContours(m, cnt, CV_RETR_EXTERNAL, CV_CHAIN_APPROX_NONE); - - // search the largest area - /* // -std=c++11 + cv_bridge::CvImagePtr cv_ptr; + try + { + cv_ptr = cv_bridge::toCvCopy(raw_msg); + } + catch (cv_bridge::Exception &e) + { + RCLCPP_ERROR(this->get_logger(), "cv_bridge exception: %s", e.what()); + return; + } + + // Check the number of channels + if (sensor_msgs::image_encodings::numChannels(raw_msg->encoding) != 1) + { + RCLCPP_ERROR(this->get_logger(), "Only grayscale image is acceptable, got [%s]", raw_msg->encoding.c_str()); + return; + } + + std::vector> cnt; + cv::Mat1b m(raw_msg->width, raw_msg->height); + + if (raw_msg->encoding == enc::TYPE_8UC1) + { + m = cv_ptr->image; + } + else + { + double minVal, maxVal; + cv::minMaxIdx(cv_ptr->image, &minVal, &maxVal, 0, 0, cv_ptr->image != 0.); + double ra = maxVal - minVal; + + cv_ptr->image.convertTo(m, CV_8U, 255. / ra, -minVal * 255. / ra); + } + + cv::findContours(m, cnt, CV_RETR_EXTERNAL, CV_CHAIN_APPROX_NONE); + + // search the largest area std::vector >::iterator it = std::max_element(cnt.begin(), cnt.end(), [](std::vector a, std::vector b) { return a.size() < b.size(); }); - */ - std::vector>::iterator it = cnt.begin(); - for (std::vector>::iterator i = cnt.begin(); i != cnt.end(); ++i) - { - it = (*it).size() < (*i).size() ? i : it; - } - cv::Rect r = cv::boundingRect(cnt[std::distance(cnt.begin(), it)]); - cv_bridge::CvImage out_msg; - out_msg.header = raw_msg->header; - out_msg.encoding = raw_msg->encoding; - out_msg.image = cv_ptr->image(r); + cv::Rect r = cv::boundingRect(cnt[std::distance(cnt.begin(), it)]); + + cv_bridge::CvImage out_msg; + out_msg.header = raw_msg->header; + out_msg.encoding = raw_msg->encoding; + out_msg.image = cv_ptr->image(r); - pub_.publish(out_msg.toImageMsg()); + pub_.publish(out_msg.toImageMsg()); } } // namespace image_proc From b415ca463c2deb63cad6fa79773384031a37c2aa Mon Sep 17 00:00:00 2001 From: Andreas Klintberg Date: Mon, 28 Oct 2019 22:06:35 -0400 Subject: [PATCH 03/12] fixed some missed issues and tested --- image_proc/src/crop_non_zero.cpp | 18 ++++++++++++------ 1 file changed, 12 insertions(+), 6 deletions(-) diff --git a/image_proc/src/crop_non_zero.cpp b/image_proc/src/crop_non_zero.cpp index 7aa4bf54c..866289243 100644 --- a/image_proc/src/crop_non_zero.cpp +++ b/image_proc/src/crop_non_zero.cpp @@ -57,15 +57,21 @@ CropNonZeroNode::CropNonZeroNode(const rclcpp::NodeOptions& options) : Node("Cro RCLCPP_INFO(get_logger(), "camera_namespace: %s ", camera_namespace_.c_str()); break; } - image_pub_ = camera_namespace_ + "/image"; - connectCb(); - // Make sure we don't enter connectCb() between advertising and assigning to pub_depth_ - std::lock_guard lock(connect_mutex_); - RCLCPP_INFO(this->get_logger(), "publish: %s", image_pub_.c_str()); - pub_ = image_transport::create_publisher(this, image_pub_); } + image_pub_ = camera_namespace_ + "/image"; + connectCb(); + // Make sure we don't enter connectCb() between advertising and assigning to pub_depth_ + std::lock_guard lock(connect_mutex_); + RCLCPP_INFO(this->get_logger(), "publish: %s", image_pub_.c_str()); + pub_ = image_transport::create_publisher(this, image_pub_); return result; }; + this->declare_parameter("camera_namespace"); + + rclcpp::Parameter parameter; + if (rclcpp::PARAMETER_NOT_SET != this->get_parameter("camera_namespace", parameter)) { + parameter_change_cb(this->get_parameters({"camera_namespace"})); + } this->set_on_parameters_set_callback(parameter_change_cb); }; From 71867d20c7053f10519915c69b82582a2611194d Mon Sep 17 00:00:00 2001 From: Andreas Klintberg Date: Sat, 2 Nov 2019 17:11:05 -0400 Subject: [PATCH 04/12] fixed small miss dependencies variable --- image_proc/CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/image_proc/CMakeLists.txt b/image_proc/CMakeLists.txt index 2e2a136c9..86c6dc9a3 100644 --- a/image_proc/CMakeLists.txt +++ b/image_proc/CMakeLists.txt @@ -100,6 +100,7 @@ ament_target_dependencies(crop_non_zero ${dependencies} ) + rclcpp_components_register_nodes(crop_non_zero "image_proc::CropNonZeroNode") set(node_plugins "${node_plugins}image_proc::CropNonZeroNode;$\n") From a7af8d702e0af463e77f1887a6827829db0203e1 Mon Sep 17 00:00:00 2001 From: Andreas Klintberg Date: Sat, 2 Nov 2019 17:18:36 -0400 Subject: [PATCH 05/12] messed up, typo --- image_proc/src/crop_non_zero.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/image_proc/src/crop_non_zero.cpp b/image_proc/src/crop_non_zero.cpp index 866289243..1ffc11772 100644 --- a/image_proc/src/crop_non_zero.cpp +++ b/image_proc/src/crop_non_zero.cpp @@ -74,7 +74,7 @@ CropNonZeroNode::CropNonZeroNode(const rclcpp::NodeOptions& options) : Node("Cro } this->set_on_parameters_set_callback(parameter_change_cb); -}; +} // Handles (un)subscribing when clients (un)subscribe void CropNonZeroNode::connectCb() From b93bda399783dfcfe1d5e437031a52e0d6fd2378 Mon Sep 17 00:00:00 2001 From: Andreas Klintberg Date: Sun, 3 Nov 2019 00:58:02 -0400 Subject: [PATCH 06/12] PR feedback, topic names and mutex lock --- image_proc/include/crop_non_zero.hpp | 4 ++-- image_proc/src/crop_non_zero.cpp | 18 +++++++++--------- 2 files changed, 11 insertions(+), 11 deletions(-) diff --git a/image_proc/include/crop_non_zero.hpp b/image_proc/include/crop_non_zero.hpp index ef9f61535..7cad9a36a 100644 --- a/image_proc/include/crop_non_zero.hpp +++ b/image_proc/include/crop_non_zero.hpp @@ -50,8 +50,8 @@ class CropNonZeroNode : public rclcpp::Node CropNonZeroNode(const rclcpp::NodeOptions&); private: std::string camera_namespace_; - std::string image_pub_; - std::string image_sub_; + std::string image_pub_topic_; + std::string image_sub_topic_; // Subscriptions image_transport::Subscriber sub_raw_; diff --git a/image_proc/src/crop_non_zero.cpp b/image_proc/src/crop_non_zero.cpp index 1ffc11772..4257edee2 100644 --- a/image_proc/src/crop_non_zero.cpp +++ b/image_proc/src/crop_non_zero.cpp @@ -36,7 +36,7 @@ #include #include #include "crop_non_zero.hpp" -//#include // for std::max_element +#include namespace image_proc { @@ -58,12 +58,13 @@ CropNonZeroNode::CropNonZeroNode(const rclcpp::NodeOptions& options) : Node("Cro break; } } - image_pub_ = camera_namespace_ + "/image"; + image_pub_topic_ = camera_namespace_ + "/image"; + + std::lock_guard lock(connect_mutex_); connectCb(); // Make sure we don't enter connectCb() between advertising and assigning to pub_depth_ - std::lock_guard lock(connect_mutex_); - RCLCPP_INFO(this->get_logger(), "publish: %s", image_pub_.c_str()); - pub_ = image_transport::create_publisher(this, image_pub_); + RCLCPP_INFO(this->get_logger(), "publish: %s", image_pub_topic_.c_str()); + pub_ = image_transport::create_publisher(this, image_pub_topic_); return result; }; this->declare_parameter("camera_namespace"); @@ -79,11 +80,10 @@ CropNonZeroNode::CropNonZeroNode(const rclcpp::NodeOptions& options) : Node("Cro // Handles (un)subscribing when clients (un)subscribe void CropNonZeroNode::connectCb() { - image_sub_ = camera_namespace_ + "/image_raw"; - std::lock_guard lock(connect_mutex_); + image_sub_topic_ = camera_namespace_ + "/image_raw"; - RCLCPP_INFO(this->get_logger(), "subscribe: %s", image_sub_.c_str()); - sub_raw_ = image_transport::create_subscription(this, image_sub_, std::bind(&CropNonZeroNode::imageCb, this, std::placeholders::_1), "raw"); + RCLCPP_INFO(this->get_logger(), "subscribe: %s", image_sub_topic_.c_str()); + sub_raw_ = image_transport::create_subscription(this, image_sub_topic_, std::bind(&CropNonZeroNode::imageCb, this, std::placeholders::_1), "raw"); } void CropNonZeroNode::imageCb(const sensor_msgs::msg::Image::ConstSharedPtr &raw_msg) From aea2f9f9a4f489e9144daee09aca89b0ea903457 Mon Sep 17 00:00:00 2001 From: Andreas Klintberg Date: Sun, 3 Nov 2019 16:25:43 -0500 Subject: [PATCH 07/12] updated header guard --- image_proc/include/crop_non_zero.hpp | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/image_proc/include/crop_non_zero.hpp b/image_proc/include/crop_non_zero.hpp index 7cad9a36a..eae157283 100644 --- a/image_proc/include/crop_non_zero.hpp +++ b/image_proc/include/crop_non_zero.hpp @@ -31,9 +31,8 @@ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ - -#ifndef IMAGE_PROC_PROCESSOR_H -#define IMAGE_PROC_PROCESSOR_H +#ifndef IMAGE_PROC__CROP_NON_ZERO_HPP_ +#define IMAGE_PROC__CROP_NON_ZERO_HPP_ #include #include #include From 35cf4664cb81a3a494d7f4a47f09772b7b674cf7 Mon Sep 17 00:00:00 2001 From: Andreas Klintberg Date: Sun, 3 Nov 2019 16:35:47 -0500 Subject: [PATCH 08/12] from jwhitley review, one argument constructors should be explicit --- image_proc/include/crop_non_zero.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/image_proc/include/crop_non_zero.hpp b/image_proc/include/crop_non_zero.hpp index eae157283..915d18ae5 100644 --- a/image_proc/include/crop_non_zero.hpp +++ b/image_proc/include/crop_non_zero.hpp @@ -46,7 +46,7 @@ namespace image_proc { class CropNonZeroNode : public rclcpp::Node { public: - CropNonZeroNode(const rclcpp::NodeOptions&); + explicit CropNonZeroNode(const rclcpp::NodeOptions&); private: std::string camera_namespace_; std::string image_pub_topic_; From 0a041fd413f78aea7aca8d935e9452e3298f9442 Mon Sep 17 00:00:00 2001 From: Andreas Klintberg Date: Sun, 10 Nov 2019 00:16:29 -0800 Subject: [PATCH 09/12] fixed test issues and small crop_decimate change for compiling --- image_proc/CMakeLists.txt | 1 - image_proc/src/crop_decimate.cpp | 2 +- image_proc/src/crop_non_zero.cpp | 151 +++++++++++++++---------------- 3 files changed, 73 insertions(+), 81 deletions(-) diff --git a/image_proc/CMakeLists.txt b/image_proc/CMakeLists.txt index 86c6dc9a3..2e2a136c9 100644 --- a/image_proc/CMakeLists.txt +++ b/image_proc/CMakeLists.txt @@ -100,7 +100,6 @@ ament_target_dependencies(crop_non_zero ${dependencies} ) - rclcpp_components_register_nodes(crop_non_zero "image_proc::CropNonZeroNode") set(node_plugins "${node_plugins}image_proc::CropNonZeroNode;$\n") diff --git a/image_proc/src/crop_decimate.cpp b/image_proc/src/crop_decimate.cpp index f7d885397..daa7baa47 100644 --- a/image_proc/src/crop_decimate.cpp +++ b/image_proc/src/crop_decimate.cpp @@ -46,7 +46,7 @@ void debayer2x2toBGR( int R, int G1, int G2, int B) { typedef cv::Vec DstPixel; // 8- or 16-bit BGR - dst.create(src.rows / 2, src.cols / 2, cv::DataType::type); + dst.create(src.rows / 2, src.cols / 2, cv::traits::Type::value); int src_row_step = src.step1(); int dst_row_step = dst.step1(); diff --git a/image_proc/src/crop_non_zero.cpp b/image_proc/src/crop_non_zero.cpp index 4257edee2..3a4c48861 100644 --- a/image_proc/src/crop_non_zero.cpp +++ b/image_proc/src/crop_non_zero.cpp @@ -1,72 +1,69 @@ -/********************************************************************* -* Software License Agreement (BSD License) -* -* Copyright (c) 2008, Willow Garage, Inc. -* All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* * Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* * Redistributions in binary form must reproduce the above -* copyright notice, this list of conditions and the following -* disclaimer in the documentation and/or other materials provided -* with the distribution. -* * Neither the name of the Willow Garage nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -*********************************************************************/ -#include -#include -#include -#include -#include "crop_non_zero.hpp" +// Copyright 2008, 2019 Willow Garage, Inc., Steve Macenski, Joshua Whitley +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of {copyright_holder} nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. + #include +#include + +#include "image_proc/crop_non_zero.hpp" + namespace image_proc { namespace enc = sensor_msgs::image_encodings; -CropNonZeroNode::CropNonZeroNode(const rclcpp::NodeOptions& options) : Node("CropNonZeroNode", options) +CropNonZeroNode::CropNonZeroNode(const rclcpp::NodeOptions & options) +: Node("CropNonZeroNode", options) { auto parameter_change_cb = [this](std::vector parameters) -> rcl_interfaces::msg::SetParametersResult { - auto result = rcl_interfaces::msg::SetParametersResult(); - result.successful = true; - for (auto parameter : parameters) - { - if (parameter.get_name() == "camera_namespace") - { - camera_namespace_ = parameter.as_string(); - RCLCPP_INFO(get_logger(), "camera_namespace: %s ", camera_namespace_.c_str()); - break; + auto result = rcl_interfaces::msg::SetParametersResult(); + result.successful = true; + for (auto parameter : parameters) { + if (parameter.get_name() == "camera_namespace") { + camera_namespace_ = parameter.as_string(); + RCLCPP_INFO(get_logger(), "camera_namespace: %s ", camera_namespace_.c_str()); + break; + } } - } - image_pub_topic_ = camera_namespace_ + "/image"; - - std::lock_guard lock(connect_mutex_); - connectCb(); - // Make sure we don't enter connectCb() between advertising and assigning to pub_depth_ - RCLCPP_INFO(this->get_logger(), "publish: %s", image_pub_topic_.c_str()); - pub_ = image_transport::create_publisher(this, image_pub_topic_); - return result; - }; + image_pub_topic_ = camera_namespace_ + "/image"; + + std::lock_guard lock(connect_mutex_); + connectCb(); + // Make sure we don't enter connectCb() between advertising and assigning to pub_depth_ + RCLCPP_INFO(this->get_logger(), "publish: %s", image_pub_topic_.c_str()); + pub_ = image_transport::create_publisher(this, image_pub_topic_); + return result; + }; this->declare_parameter("camera_namespace"); rclcpp::Parameter parameter; @@ -83,38 +80,32 @@ void CropNonZeroNode::connectCb() image_sub_topic_ = camera_namespace_ + "/image_raw"; RCLCPP_INFO(this->get_logger(), "subscribe: %s", image_sub_topic_.c_str()); - sub_raw_ = image_transport::create_subscription(this, image_sub_topic_, std::bind(&CropNonZeroNode::imageCb, this, std::placeholders::_1), "raw"); + sub_raw_ = image_transport::create_subscription(this, image_sub_topic_, + std::bind(&CropNonZeroNode::imageCb, this, std::placeholders::_1), "raw"); } -void CropNonZeroNode::imageCb(const sensor_msgs::msg::Image::ConstSharedPtr &raw_msg) +void CropNonZeroNode::imageCb(const sensor_msgs::msg::Image::ConstSharedPtr & raw_msg) { cv_bridge::CvImagePtr cv_ptr; - try - { + try { cv_ptr = cv_bridge::toCvCopy(raw_msg); - } - catch (cv_bridge::Exception &e) - { + } catch (cv_bridge::Exception & e) { RCLCPP_ERROR(this->get_logger(), "cv_bridge exception: %s", e.what()); return; } // Check the number of channels - if (sensor_msgs::image_encodings::numChannels(raw_msg->encoding) != 1) - { - RCLCPP_ERROR(this->get_logger(), "Only grayscale image is acceptable, got [%s]", raw_msg->encoding.c_str()); + if (sensor_msgs::image_encodings::numChannels(raw_msg->encoding) != 1) { + RCLCPP_ERROR(this->get_logger(), "Only grayscale image is acceptable, got [%s]", + raw_msg->encoding.c_str()); return; } - std::vector> cnt; cv::Mat1b m(raw_msg->width, raw_msg->height); - if (raw_msg->encoding == enc::TYPE_8UC1) - { + if (raw_msg->encoding == enc::TYPE_8UC1) { m = cv_ptr->image; - } - else - { + } else { double minVal, maxVal; cv::minMaxIdx(cv_ptr->image, &minVal, &maxVal, 0, 0, cv_ptr->image != 0.); double ra = maxVal - minVal; @@ -125,9 +116,11 @@ void CropNonZeroNode::imageCb(const sensor_msgs::msg::Image::ConstSharedPtr &raw cv::findContours(m, cnt, CV_RETR_EXTERNAL, CV_CHAIN_APPROX_NONE); // search the largest area - std::vector >::iterator it = std::max_element(cnt.begin(), cnt.end(), [](std::vector a, std::vector b) { - return a.size() < b.size(); - }); + std::vector>::iterator it = + std::max_element(cnt.begin(), cnt.end(), [](std::vector a, + std::vector b) { + return a.size() < b.size(); + }); cv::Rect r = cv::boundingRect(cnt[std::distance(cnt.begin(), it)]); @@ -139,11 +132,11 @@ void CropNonZeroNode::imageCb(const sensor_msgs::msg::Image::ConstSharedPtr &raw pub_.publish(out_msg.toImageMsg()); } -} // namespace image_proc +} // namespace image_proc #include "rclcpp_components/register_node_macro.hpp" // Register the component with class_loader. // This acts as a sort of entry point, allowing the component to be discoverable when its library // is being loaded into a running process. -RCLCPP_COMPONENTS_REGISTER_NODE(image_proc::CropNonZeroNode) \ No newline at end of file +RCLCPP_COMPONENTS_REGISTER_NODE(image_proc::CropNonZeroNode) From 4eefcf2c467066d43e58fbe4ff13003a2ed8e67c Mon Sep 17 00:00:00 2001 From: Andreas Klintberg Date: Sun, 10 Nov 2019 00:22:59 -0800 Subject: [PATCH 10/12] include file changed and reverted crop decimate change --- image_proc/include/crop_non_zero.hpp | 68 ------------------ .../include/image_proc/crop_non_zero.hpp | 71 +++++++++++++++++++ image_proc/src/crop_decimate.cpp | 2 +- 3 files changed, 72 insertions(+), 69 deletions(-) delete mode 100644 image_proc/include/crop_non_zero.hpp create mode 100644 image_proc/include/image_proc/crop_non_zero.hpp diff --git a/image_proc/include/crop_non_zero.hpp b/image_proc/include/crop_non_zero.hpp deleted file mode 100644 index 915d18ae5..000000000 --- a/image_proc/include/crop_non_zero.hpp +++ /dev/null @@ -1,68 +0,0 @@ -/********************************************************************* -* Software License Agreement (BSD License) -* -* Copyright (c) 2008, 2019, Willow Garage, Inc., Andreas Klintberg. -* All rights reserved. -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* -* * Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* * Redistributions in binary form must reproduce the above -* copyright notice, this list of conditions and the following -* disclaimer in the documentation and/or other materials provided -* with the distribution. -* * Neither the name of the Willow Garage nor the names of its -* contributors may be used to endorse or promote products derived -* from this software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -*********************************************************************/ -#ifndef IMAGE_PROC__CROP_NON_ZERO_HPP_ -#define IMAGE_PROC__CROP_NON_ZERO_HPP_ -#include -#include -#include -#include - -#include -#include -#include -namespace image_proc { - -class CropNonZeroNode : public rclcpp::Node -{ - public: - explicit CropNonZeroNode(const rclcpp::NodeOptions&); - private: - std::string camera_namespace_; - std::string image_pub_topic_; - std::string image_sub_topic_; - - // Subscriptions - image_transport::Subscriber sub_raw_; - - // Publications - std::mutex connect_mutex_; - - image_transport::Publisher pub_; - - void connectCb(); - - void imageCb(const sensor_msgs::msg::Image::ConstSharedPtr & raw_msg); -}; -} // namespace image_proc -#endif diff --git a/image_proc/include/image_proc/crop_non_zero.hpp b/image_proc/include/image_proc/crop_non_zero.hpp new file mode 100644 index 000000000..488e6e628 --- /dev/null +++ b/image_proc/include/image_proc/crop_non_zero.hpp @@ -0,0 +1,71 @@ +// Copyright 2008, 2019 Willow Garage, Inc., Steve Macenski, Joshua Whitley +// All rights reserved. +// +// Software License Agreement (BSD License 2.0) +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions +// are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of {copyright_holder} nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. + +#ifndef IMAGE_PROC__CROP_NON_ZERO_HPP_ +#define IMAGE_PROC__CROP_NON_ZERO_HPP_ + +#include +#include +#include + +#include +#include +#include +#include + +namespace image_proc +{ + +class CropNonZeroNode : public rclcpp::Node +{ +public: + explicit CropNonZeroNode(const rclcpp::NodeOptions &); + +private: + std::string camera_namespace_; + std::string image_pub_topic_; + std::string image_sub_topic_; + + // Subscriptions + image_transport::Subscriber sub_raw_; + + // Publications + std::mutex connect_mutex_; + + image_transport::Publisher pub_; + + void connectCb(); + + void imageCb(const sensor_msgs::msg::Image::ConstSharedPtr & raw_msg); +}; +} // namespace image_proc +#endif // IMAGE_PROC__CROP_NON_ZERO_HPP_ diff --git a/image_proc/src/crop_decimate.cpp b/image_proc/src/crop_decimate.cpp index daa7baa47..f7d885397 100644 --- a/image_proc/src/crop_decimate.cpp +++ b/image_proc/src/crop_decimate.cpp @@ -46,7 +46,7 @@ void debayer2x2toBGR( int R, int G1, int G2, int B) { typedef cv::Vec DstPixel; // 8- or 16-bit BGR - dst.create(src.rows / 2, src.cols / 2, cv::traits::Type::value); + dst.create(src.rows / 2, src.cols / 2, cv::DataType::type); int src_row_step = src.step1(); int dst_row_step = dst.step1(); From 87f83c3e7063dabbfee52bf811086aef3fc41293 Mon Sep 17 00:00:00 2001 From: Andreas Klintberg Date: Sat, 23 Nov 2019 15:57:33 -0800 Subject: [PATCH 11/12] preprocessor condition for different opencv version --- image_proc/src/crop_decimate.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/image_proc/src/crop_decimate.cpp b/image_proc/src/crop_decimate.cpp index f7d885397..df542f3ef 100644 --- a/image_proc/src/crop_decimate.cpp +++ b/image_proc/src/crop_decimate.cpp @@ -46,7 +46,11 @@ void debayer2x2toBGR( int R, int G1, int G2, int B) { typedef cv::Vec DstPixel; // 8- or 16-bit BGR - dst.create(src.rows / 2, src.cols / 2, cv::DataType::type); + #if CV_MAJOR_VERSION >= 3 && CV_MINOR_VERSION > 2 + dst.create(src.rows / 2, src.cols / 2, cv::traits::Type::value); + #else + dst.create(src.rows / 2, src.cols / 2, cv::DataType::type); + #endif int src_row_step = src.step1(); int dst_row_step = dst.step1(); From 42ed31e4e91d7dbd5140a0d9a704e72fbcd4bea0 Mon Sep 17 00:00:00 2001 From: Andreas Klintberg Date: Sat, 23 Nov 2019 16:40:32 -0800 Subject: [PATCH 12/12] fixed linting issues --- image_proc/src/crop_decimate.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/image_proc/src/crop_decimate.cpp b/image_proc/src/crop_decimate.cpp index df542f3ef..68a6eb871 100644 --- a/image_proc/src/crop_decimate.cpp +++ b/image_proc/src/crop_decimate.cpp @@ -47,9 +47,9 @@ void debayer2x2toBGR( { typedef cv::Vec DstPixel; // 8- or 16-bit BGR #if CV_MAJOR_VERSION >= 3 && CV_MINOR_VERSION > 2 - dst.create(src.rows / 2, src.cols / 2, cv::traits::Type::value); + dst.create(src.rows / 2, src.cols / 2, cv::traits::Type::value); #else - dst.create(src.rows / 2, src.cols / 2, cv::DataType::type); + dst.create(src.rows / 2, src.cols / 2, cv::DataType::type); #endif int src_row_step = src.step1();