Skip to content

Commit

Permalink
Add support for alpha pngs by adding per stream type decode functions…
Browse files Browse the repository at this point in the history
… (backport #106) (#163)

* Add support for alpha pngs by adding per stream type decode functions (backport #106)

Co-authored-by: Matthew Bries <matthew.bries@swri.org>

* Fix cv_bridge headers

---------

Co-authored-by: Matthew Bries <matthew.bries@swri.org>
  • Loading branch information
bjsowa and Matthew Bries authored Oct 6, 2024
1 parent bc92480 commit c8bdc7a
Show file tree
Hide file tree
Showing 4 changed files with 52 additions and 16 deletions.
1 change: 1 addition & 0 deletions include/web_video_server/image_streamer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,7 @@ class ImageTransportImageStreamer : public ImageStreamer
virtual void start();

protected:
virtual cv::Mat decodeImage(const sensor_msgs::msg::Image::ConstSharedPtr & msg);
virtual void sendImage(const cv::Mat &, const rclcpp::Time & time) = 0;
virtual void restreamFrame(double max_age);
virtual void initialize(const cv::Mat &);
Expand Down
2 changes: 2 additions & 0 deletions include/web_video_server/png_streamers.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@ class PngStreamer : public ImageTransportImageStreamer

protected:
virtual void sendImage(const cv::Mat &, const rclcpp::Time & time);
virtual cv::Mat decodeImage(const sensor_msgs::msg::Image::ConstSharedPtr & msg);

private:
MultipartStream stream_;
Expand All @@ -47,6 +48,7 @@ class PngSnapshotStreamer : public ImageTransportImageStreamer

protected:
virtual void sendImage(const cv::Mat &, const rclcpp::Time & time);
virtual cv::Mat decodeImage(const sensor_msgs::msg::Image::ConstSharedPtr & msg);

private:
int quality_;
Expand Down
37 changes: 21 additions & 16 deletions src/image_streamer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -108,6 +108,26 @@ void ImageTransportImageStreamer::restreamFrame(double max_age)
}
}

cv::Mat ImageTransportImageStreamer::decodeImage(
const sensor_msgs::msg::Image::ConstSharedPtr & msg)
{
if (msg->encoding.find("F") != std::string::npos) {
// scale floating point images
cv::Mat float_image_bridge = cv_bridge::toCvCopy(msg, msg->encoding)->image;
cv::Mat_<float> float_image = float_image_bridge;
double max_val;
cv::minMaxIdx(float_image, 0, &max_val);

if (max_val > 0) {
float_image *= (255 / max_val);
}
return float_image;
} else {
// Convert to OpenCV native BGR color
return cv_bridge::toCvCopy(msg, "bgr8")->image;
}
}

void ImageTransportImageStreamer::imageCallback(const sensor_msgs::msg::Image::ConstSharedPtr & msg)
{
if (inactive_) {
Expand All @@ -116,22 +136,7 @@ void ImageTransportImageStreamer::imageCallback(const sensor_msgs::msg::Image::C

cv::Mat img;
try {
if (msg->encoding.find("F") != std::string::npos) {
// scale floating point images
cv::Mat float_image_bridge = cv_bridge::toCvCopy(msg, msg->encoding)->image;
cv::Mat_<float> float_image = float_image_bridge;
double max_val;
cv::minMaxIdx(float_image, 0, &max_val);

if (max_val > 0) {
float_image *= (255 / max_val);
}
img = float_image;
} else {
// Convert to OpenCV native BGR color
img = cv_bridge::toCvCopy(msg, "bgr8")->image;
}

img = decodeImage(msg);
int input_width = img.cols;
int input_height = img.rows;

Expand Down
28 changes: 28 additions & 0 deletions src/png_streamers.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,12 @@
#include "web_video_server/png_streamers.hpp"
#include "async_web_server_cpp/http_reply.hpp"

#ifdef CV_BRIDGE_USES_OLD_HEADERS
#include "cv_bridge/cv_bridge.h"
#else
#include "cv_bridge/cv_bridge.hpp"
#endif

namespace web_video_server
{

Expand All @@ -20,6 +26,17 @@ PngStreamer::~PngStreamer()
boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage.
}

cv::Mat PngStreamer::decodeImage(const sensor_msgs::msg::Image::ConstSharedPtr & msg)
{
// Handle alpha values since PNG supports it
if (sensor_msgs::image_encodings::hasAlpha(msg->encoding)) {
return cv_bridge::toCvCopy(msg, "bgra8")->image;
} else {
// Use the normal decode otherwise
return ImageTransportImageStreamer::decodeImage(msg);
}
}

void PngStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & time)
{
std::vector<int> encode_params;
Expand Down Expand Up @@ -64,6 +81,17 @@ PngSnapshotStreamer::~PngSnapshotStreamer()
boost::mutex::scoped_lock lock(send_mutex_); // protects sendImage.
}

cv::Mat PngSnapshotStreamer::decodeImage(const sensor_msgs::msg::Image::ConstSharedPtr & msg)
{
// Handle alpha values since PNG supports it
if (sensor_msgs::image_encodings::hasAlpha(msg->encoding)) {
return cv_bridge::toCvCopy(msg, "bgra8")->image;
} else {
// Use the normal decode otherwise
return ImageTransportImageStreamer::decodeImage(msg);
}
}

void PngSnapshotStreamer::sendImage(const cv::Mat & img, const rclcpp::Time & time)
{
std::vector<int> encode_params;
Expand Down

0 comments on commit c8bdc7a

Please sign in to comment.