From 9b1265456f060b27c4e92902673828b5ba76dfcf Mon Sep 17 00:00:00 2001
From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com>
Date: Mon, 10 Jun 2024 08:51:40 -0400
Subject: [PATCH] image_publisher: Fix image, constantly flipping when static
image is published (backport #986) (#987)
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
Continuation of
https://github.com/ros-perception/image_pipeline/pull/984.
When publishing video stream from a camera, the image was flipped
correctly. Yet for a static image, which was loaded once, the flip
function was applied every time `ImagePublisher::doWork()` was called,
resulting in the published image being flipped back and forth all the
time.
This PR should be straightforward to port it to `Humble`, `Iron` and
`Jazzy`.
This is an automatic backport of pull request #986 done by
[Mergify](https://mergify.com).
Co-authored-by: Krzysztof Wojciechowski <49921081+Kotochleb@users.noreply.github.com>
Co-authored-by: Alejandro Hernández Cordero
---
image_publisher/include/image_publisher/image_publisher.hpp | 1 +
image_publisher/src/image_publisher.cpp | 5 ++++-
2 files changed, 5 insertions(+), 1 deletion(-)
diff --git a/image_publisher/include/image_publisher/image_publisher.hpp b/image_publisher/include/image_publisher/image_publisher.hpp
index ae31210d0..1ad1dcdea 100644
--- a/image_publisher/include/image_publisher/image_publisher.hpp
+++ b/image_publisher/include/image_publisher/image_publisher.hpp
@@ -68,6 +68,7 @@ class ImagePublisher : public rclcpp::Node
double field_of_view_;
bool flip_horizontal_;
bool flip_vertical_;
+ bool image_flipped_;
bool retry_; // If enabled will retry loading image from the filename_
int timeout_; // Time after which retrying starts
diff --git a/image_publisher/src/image_publisher.cpp b/image_publisher/src/image_publisher.cpp
index dc6649e39..939656899 100644
--- a/image_publisher/src/image_publisher.cpp
+++ b/image_publisher/src/image_publisher.cpp
@@ -152,9 +152,11 @@ void ImagePublisher::doWork()
if (!cap_.read(image_)) {
cap_.set(cv::CAP_PROP_POS_FRAMES, 0);
}
+ image_flipped_ = false;
}
- if (flip_image_) {
+ if (flip_image_ && !image_flipped_) {
cv::flip(image_, image_, flip_value_);
+ image_flipped_ = true;
}
sensor_msgs::msg::Image::SharedPtr out_img =
@@ -221,6 +223,7 @@ void ImagePublisher::onInit()
} else {
flip_image_ = false;
}
+ image_flipped_ = false; // Image newly read, needs to be flipped
camera_info_.width = image_.cols;
camera_info_.height = image_.rows;