Skip to content

Commit

Permalink
[rolling] image_publisher: Fix image, constantly flipping when static…
Browse files Browse the repository at this point in the history
… image is published (#986)

Continuation of
#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`.

(cherry picked from commit 7f25ec9)
  • Loading branch information
Kotochleb authored and mergify[bot] committed May 27, 2024
1 parent 544562b commit 4c07f5b
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,7 @@ class ImagePublisher : public rclcpp::Node
std::string filename_;
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

Expand Down
5 changes: 4 additions & 1 deletion image_publisher/src/image_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -137,9 +137,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 =
Expand Down Expand Up @@ -206,6 +208,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;
Expand Down

0 comments on commit 4c07f5b

Please sign in to comment.