Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <cv_bridge/cv_bridge.h>
00031 #include <image_transport/image_transport.h>
00032 #include <image_transport/publisher.h>
00033 #include <image_transport/subscriber.h>
00034 #include <opencv2/core/core.hpp>
00035 #include <nodelet/nodelet.h>
00036 #include <ros/ros.h>
00037 #include <sensor_msgs/Image.h>
00038 #include <swri_roscpp/parameters.h>
00039
00040 namespace swri_image_util
00041 {
00042 class WarpImageNodelet : public nodelet::Nodelet
00043 {
00044 public:
00045 WarpImageNodelet(): use_input_size_(false)
00046 {
00047 }
00048
00049 ~WarpImageNodelet()
00050 {
00051 }
00052
00053 void onInit()
00054 {
00055 ros::NodeHandle &node = getNodeHandle();
00056 ros::NodeHandle &priv = getPrivateNodeHandle();
00057
00058 std::vector<double> transform;
00059 if (priv.hasParam("width") && priv.hasParam("height"))
00060 {
00061 use_input_size_ = false;
00062 swri::getParam(priv, "width", output_size_.width);
00063 swri::getParam(priv, "height", output_size_.height);
00064 }
00065 else
00066 {
00067 use_input_size_ = true;
00068 NODELET_INFO("No ~width and ~height parameters given. Output images will be same size as input.");
00069 }
00070 priv.param("transform", transform, transform);
00071 if (transform.size() != 9)
00072 {
00073 NODELET_FATAL("~transform must be a 9-element list of doubles (3x3 matrix, row major)");
00074
00075
00076 return;
00077 }
00078 m_ = cv::Mat(transform, true).reshape(0, 3);
00079 NODELET_INFO_STREAM("Transformation matrix:" << std::endl << m_);
00080
00081 image_transport::ImageTransport it(node);
00082 image_pub_ = it.advertise("warped_image", 1);
00083 image_sub_ = it.subscribe("image", 1, &WarpImageNodelet::handleImage, this);
00084 }
00085
00086 void handleImage(sensor_msgs::ImageConstPtr const& image)
00087 {
00088 cv_bridge::CvImageConstPtr cv_image = cv_bridge::toCvShare(image);
00089
00090 cv_bridge::CvImagePtr cv_warped = boost::make_shared<cv_bridge::CvImage>();
00091 if (use_input_size_)
00092 {
00093 output_size_ = cv_image->image.size();
00094 }
00095 cv::warpPerspective(cv_image->image, cv_warped->image, m_, output_size_, CV_INTER_LANCZOS4);
00096
00097 cv_warped->encoding = cv_image->encoding;
00098 cv_warped->header = cv_image->header;
00099
00100 image_pub_.publish(cv_warped->toImageMsg());
00101 }
00102
00103 private:
00104 image_transport::Subscriber image_sub_;
00105 image_transport::Publisher image_pub_;
00106 cv::Mat m_;
00107 bool use_input_size_;
00108 cv::Size output_size_;
00109 };
00110 }
00111
00112 #include <swri_nodelet/class_list_macros.h>
00113 SWRI_NODELET_EXPORT_CLASS(swri_image_util, WarpImageNodelet);