resized_publisher.cpp
Go to the documentation of this file.
2 #include <opencv2/imgproc/imgproc.hpp>
3 #include <cv_bridge/cv_bridge.h>
4 
5 void ResizedPublisher::publish(const sensor_msgs::Image& message,
6  const PublishFn& publish_fn) const
7 {
8  cv::Mat cv_image;
9  boost::shared_ptr<void const> tracked_object;
10  try
11  {
12  cv_image = cv_bridge::toCvShare(message, tracked_object, message.encoding)->image;
13  }
14  catch (cv::Exception &e)
15  {
16  ROS_ERROR("Could not convert from '%s' to '%s'.", message.encoding.c_str(), message.encoding.c_str());
17  return;
18  }
19 
20  // Retrieve subsampling factor from the parameter server
21  double subsampling_factor;
22  std::string param_name;
23  nh().param<double>("resized_image_transport_subsampling_factor", subsampling_factor, 2.0);
24 
25  // Rescale image
26  int new_width = cv_image.cols / subsampling_factor + 0.5;
27  int new_height = cv_image.rows / subsampling_factor + 0.5;
28  cv::Mat buffer;
29  cv::resize(cv_image, buffer, cv::Size(new_width, new_height));
30 
31  // Set up ResizedImage and publish
32  image_transport_tutorial::ResizedImage resized_image;
33  resized_image.original_height = cv_image.rows;
34  resized_image.original_width = cv_image.cols;
35  resized_image.image = *(cv_bridge::CvImage(message.header, "bgr8", cv_image).toImageMsg());
36  publish_fn(resized_image);
37 }
boost::shared_ptr
ResizedPublisher::publish
virtual void publish(const sensor_msgs::Image &message, const PublishFn &publish_fn) const
Publish an image using the specified publish function. Must be implemented by the subclass.
Definition: resized_publisher.cpp:5
image_transport::SimplePublisherPlugin< image_transport_tutorial::ResizedImage >::nh
const ros::NodeHandle & nh() const
Returns the ros::NodeHandle to be used for parameter lookup.
Definition: simple_publisher_plugin.h:212
ROS_ERROR
#define ROS_ERROR(...)
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
resized_publisher.h


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