image_streamer.cpp
Go to the documentation of this file.
00001 #include "web_video_server/image_streamer.h"
00002 #include <cv_bridge/cv_bridge.h>
00003 
00004 namespace web_video_server
00005 {
00006 
00007 ImageStreamer::ImageStreamer(const async_web_server_cpp::HttpRequest &request,
00008                              async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh) :
00009     request_(request), connection_(connection), nh_(nh), inactive_(false)
00010 {
00011   topic_ = request.get_query_param_value_or_default("topic", "");
00012 }
00013 
00014 ImageTransportImageStreamer::ImageTransportImageStreamer(const async_web_server_cpp::HttpRequest &request,
00015                              async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh) :
00016   ImageStreamer(request, connection, nh), it_(nh), initialized_(false)
00017 {
00018   output_width_ = request.get_query_param_value_or_default<int>("width", -1);
00019   output_height_ = request.get_query_param_value_or_default<int>("height", -1);
00020   invert_ = request.has_query_param("invert");
00021   default_transport_ = request.get_query_param_value_or_default("default_transport", "raw");
00022 }
00023 
00024 void ImageTransportImageStreamer::start()
00025 {
00026   image_transport::TransportHints hints(default_transport_);
00027   image_sub_ = it_.subscribe(topic_, 1, &ImageTransportImageStreamer::imageCallback, this, hints);
00028 }
00029 
00030 void ImageTransportImageStreamer::initialize(const cv::Mat &)
00031 {
00032 }
00033 
00034 void ImageTransportImageStreamer::imageCallback(const sensor_msgs::ImageConstPtr &msg)
00035 {
00036   if (inactive_)
00037     return;
00038 
00039   cv::Mat img;
00040   try
00041   {
00042     if (msg->encoding.find("F") != std::string::npos)
00043     {
00044       // scale floating point images
00045       cv::Mat float_image_bridge = cv_bridge::toCvCopy(msg, msg->encoding)->image;
00046       cv::Mat_<float> float_image = float_image_bridge;
00047       double max_val;
00048       cv::minMaxIdx(float_image, 0, &max_val);
00049 
00050       if (max_val > 0)
00051       {
00052         float_image *= (255 / max_val);
00053       }
00054       img = float_image;
00055     }
00056     else
00057     {
00058       // Convert to OpenCV native BGR color
00059       img = cv_bridge::toCvCopy(msg, "bgr8")->image;
00060     }
00061 
00062     int input_width = img.cols;
00063     int input_height = img.rows;
00064 
00065     if (output_width_ == -1)
00066       output_width_ = input_width;
00067     if (output_height_ == -1)
00068       output_height_ = input_height;
00069 
00070     if (invert_)
00071     {
00072       // Rotate 180 degrees
00073       cv::flip(img, img, false);
00074       cv::flip(img, img, true);
00075     }
00076 
00077     cv::Mat output_size_image;
00078     if (output_width_ != input_width || output_height_ != input_height)
00079     {
00080       cv::Mat img_resized;
00081       cv::Size new_size(output_width_, output_height_);
00082       cv::resize(img, img_resized, new_size);
00083       output_size_image = img_resized;
00084     }
00085     else
00086     {
00087       output_size_image = img;
00088     }
00089 
00090     if (!initialized_)
00091     {
00092       initialize(output_size_image);
00093       initialized_ = true;
00094     }
00095     sendImage(output_size_image, msg->header.stamp);
00096 
00097   }
00098   catch (cv_bridge::Exception &e)
00099   {
00100     ROS_ERROR_THROTTLE(30, "cv_bridge exception: %s", e.what());
00101     inactive_ = true;
00102     return;
00103   }
00104   catch (cv::Exception &e)
00105   {
00106     ROS_ERROR_THROTTLE(30, "cv_bridge exception: %s", e.what());
00107     inactive_ = true;
00108     return;
00109   }
00110   catch (boost::system::system_error &e)
00111   {
00112     // happens when client disconnects
00113     ROS_DEBUG("system_error exception: %s", e.what());
00114     inactive_ = true;
00115     return;
00116   }
00117   catch (std::exception &e)
00118   {
00119     ROS_ERROR_THROTTLE(30, "exception: %s", e.what());
00120     inactive_ = true;
00121     return;
00122   }
00123   catch (...)
00124   {
00125     ROS_ERROR_THROTTLE(30, "exception");
00126     inactive_ = true;
00127     return;
00128   }
00129 }
00130 
00131 }


web_video_server
Author(s): Mitchell Wills
autogenerated on Thu Aug 27 2015 15:42:12