warp_image_nodelet.cpp
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2017, Southwest Research Institute® (SwRI®)
4 // All rights reserved.
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are met:
8 // * Redistributions of source code must retain the above copyright
9 // notice, this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of Southwest Research Institute® (SwRI®) nor the
14 // names of its contributors may be used to endorse or promote products
15 // derived from this software without specific prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //
28 // *****************************************************************************
29 
30 #include <cv_bridge/cv_bridge.h>
34 #include <opencv2/core/core.hpp>
35 #include <nodelet/nodelet.h>
36 #include <ros/ros.h>
37 #include <sensor_msgs/Image.h>
38 #include <swri_roscpp/parameters.h>
39 
40 namespace swri_image_util
41 {
43  {
44  public:
46  {
47  }
48 
50  {
51  }
52 
53  void onInit()
54  {
57 
58  std::vector<double> transform;
59  if (priv.hasParam("width") && priv.hasParam("height"))
60  {
61  use_input_size_ = false;
62  swri::getParam(priv, "width", output_size_.width);
63  swri::getParam(priv, "height", output_size_.height);
64  }
65  else
66  {
67  use_input_size_ = true;
68  NODELET_INFO("No ~width and ~height parameters given. Output images will be same size as input.");
69  }
70  priv.param("transform", transform, transform);
71  if (transform.size() != 9)
72  {
73  NODELET_FATAL("~transform must be a 9-element list of doubles (3x3 matrix, row major)");
74  // Return without setting up callbacks
75  // Don't shut down, because that would bring down all other nodelets as well
76  return;
77  }
78  m_ = cv::Mat(transform, true).reshape(0, 3);
79  NODELET_INFO_STREAM("Transformation matrix:" << std::endl << m_);
80 
82  image_pub_ = it.advertise("warped_image", 1);
83  image_sub_ = it.subscribe("image", 1, &WarpImageNodelet::handleImage, this);
84  }
85 
86  void handleImage(sensor_msgs::ImageConstPtr const& image)
87  {
89 
90  cv_bridge::CvImagePtr cv_warped = boost::make_shared<cv_bridge::CvImage>();
91  if (use_input_size_)
92  {
93  output_size_ = cv_image->image.size();
94  }
95  cv::warpPerspective(cv_image->image, cv_warped->image, m_, output_size_, CV_INTER_LANCZOS4);
96 
97  cv_warped->encoding = cv_image->encoding;
98  cv_warped->header = cv_image->header;
99 
100  image_pub_.publish(cv_warped->toImageMsg());
101  }
102 
103  private:
106  cv::Mat m_;
108  cv::Size output_size_;
109  };
110 }
111 
112 // Register nodelet plugin
NODELET_FATAL
#define NODELET_FATAL(...)
swri_image_util::WarpImageNodelet::~WarpImageNodelet
~WarpImageNodelet()
Definition: warp_image_nodelet.cpp:49
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
SWRI_NODELET_EXPORT_CLASS
SWRI_NODELET_EXPORT_CLASS(swri_image_util, DrawPolygonNodelet)
swri_image_util::WarpImageNodelet::WarpImageNodelet
WarpImageNodelet()
Definition: warp_image_nodelet.cpp:45
image_transport::ImageTransport
boost::shared_ptr
swri_image_util::WarpImageNodelet::image_sub_
image_transport::Subscriber image_sub_
Definition: warp_image_nodelet.cpp:104
ros.h
swri_image_util::WarpImageNodelet::m_
cv::Mat m_
Definition: warp_image_nodelet.cpp:106
swri_image_util::WarpImageNodelet::image_pub_
image_transport::Publisher image_pub_
Definition: warp_image_nodelet.cpp:105
swri_image_util::WarpImageNodelet::handleImage
void handleImage(sensor_msgs::ImageConstPtr const &image)
Definition: warp_image_nodelet.cpp:86
swri_image_util
Definition: draw_util.h:37
nodelet::Nodelet::getPrivateNodeHandle
ros::NodeHandle & getPrivateNodeHandle() const
publisher.h
image_transport::ImageTransport::advertise
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
image_transport::Subscriber
class_list_macros.h
swri::getParam
static bool getParam(const ros::NodeHandle &nh, const std::string &name, bool &variable)
image_transport::ImageTransport::subscribe
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
subscriber.h
parameters.h
swri_image_util::WarpImageNodelet
Definition: warp_image_nodelet.cpp:42
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
image_transport::Publisher::publish
void publish(const sensor_msgs::Image &message) const
swri_image_util::WarpImageNodelet::output_size_
cv::Size output_size_
Definition: warp_image_nodelet.cpp:108
image_transport.h
swri_image_util::WarpImageNodelet::onInit
void onInit()
Definition: warp_image_nodelet.cpp:53
NODELET_INFO
#define NODELET_INFO(...)
nodelet::Nodelet
nodelet.h
image_transport::Publisher
cv_bridge.h
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
swri_image_util::WarpImageNodelet::use_input_size_
bool use_input_size_
Definition: warp_image_nodelet.cpp:107
cv_bridge::toCvShare
CvImageConstPtr toCvShare(const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
NODELET_INFO_STREAM
#define NODELET_INFO_STREAM(...)
ros::NodeHandle


swri_image_util
Author(s): Kris Kozak
autogenerated on Fri Aug 2 2024 08:39:19