resized_subscriber.cpp
Go to the documentation of this file.
2 #include <cv_bridge/cv_bridge.h>
3 #include <opencv2/imgproc/imgproc.hpp>
4 
5 void ResizedSubscriber::internalCallback(const image_transport_tutorial::ResizedImage::ConstPtr& msg,
6  const Callback& user_cb)
7 {
8  // This is only for optimization, not to copy the image
9  boost::shared_ptr<void const> tracked_object_tmp;
10  cv::Mat img_rsz = cv_bridge::toCvShare(msg->image, tracked_object_tmp)->image;
11  // Resize the image to its original size
12  cv::Mat img_restored;
13  cv::resize(img_rsz, img_restored, cv::Size(msg->original_width, msg->original_height));
14 
15  // Call the user callback with the restored image
16  cv_bridge::CvImage cv_img(msg->image.header, msg->image.encoding, img_restored);
17  user_cb(cv_img.toImageMsg());
18 };
boost::shared_ptr
image_transport::SubscriberPlugin::Callback
boost::function< void(const sensor_msgs::ImageConstPtr &)> Callback
Definition: subscriber_plugin.h:115
resized_subscriber.h
ResizedSubscriber::internalCallback
virtual void internalCallback(const typename image_transport_tutorial::ResizedImage::ConstPtr &message, const Callback &user_cb)
Definition: resized_subscriber.cpp:5


image_transport
Author(s): Patrick Mihelich
autogenerated on Sat Jan 20 2024 03:14:50