theora_subscriber.cpp
Go to the documentation of this file.
00001 #include "theora_image_transport/theora_subscriber.h"
00002 #include <cv_bridge/cv_bridge.h>
00003 #include <sensor_msgs/image_encodings.h>
00004 #include <opencv/cvwimage.h>
00005 #include <opencv2/imgproc/imgproc.hpp>
00006 #include <boost/scoped_array.hpp>
00007 #include <vector>
00008 
00009 using namespace std;
00010 
00011 namespace theora_image_transport {
00012 
00013 TheoraSubscriber::TheoraSubscriber()
00014   : pplevel_(0),
00015     received_header_(false),
00016     received_keyframe_(false),
00017     decoding_context_(NULL),
00018     setup_info_(NULL)
00019 {
00020   th_info_init(&header_info_);
00021   th_comment_init(&header_comment_);
00022 }
00023 
00024 TheoraSubscriber::~TheoraSubscriber()
00025 {
00026   if (decoding_context_) th_decode_free(decoding_context_);
00027   th_setup_free(setup_info_);
00028   th_info_clear(&header_info_);
00029   th_comment_clear(&header_comment_);
00030 }
00031 
00032 void TheoraSubscriber::subscribeImpl(ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size,
00033                                      const Callback &callback, const ros::VoidPtr &tracked_object,
00034                                      const image_transport::TransportHints &transport_hints)
00035 {
00036   // queue_size doesn't account for the 3 header packets, so we correct (with a little extra) here.
00037   queue_size += 4;
00038   typedef image_transport::SimpleSubscriberPlugin<theora_image_transport::Packet> Base;
00039   Base::subscribeImpl(nh, base_topic, queue_size, callback, tracked_object, transport_hints);
00040 
00041   // Set up reconfigure server for this topic
00042   reconfigure_server_ = boost::make_shared<ReconfigureServer>(this->nh());
00043   ReconfigureServer::CallbackType f = boost::bind(&TheoraSubscriber::configCb, this, _1, _2);
00044   reconfigure_server_->setCallback(f);
00045 }
00046 
00047 void TheoraSubscriber::configCb(Config& config, uint32_t level)
00048 {
00049   if (decoding_context_ && pplevel_ != config.post_processing_level) {
00050     pplevel_ = updatePostProcessingLevel(config.post_processing_level);
00051     config.post_processing_level = pplevel_; // In case more than PPLEVEL_MAX
00052   }
00053   else
00054     pplevel_ = config.post_processing_level;
00055 }
00056 
00057 int TheoraSubscriber::updatePostProcessingLevel(int level)
00058 {
00059   int pplevel_max;
00060   int err = th_decode_ctl(decoding_context_, TH_DECCTL_GET_PPLEVEL_MAX, &pplevel_max, sizeof(int));
00061   if (err)
00062     ROS_WARN("Failed to get maximum post-processing level, error code %d", err);
00063   else if (level > pplevel_max) {
00064     ROS_WARN("Post-processing level %d is above the maximum, clamping to %d", level, pplevel_max);
00065     level = pplevel_max;
00066   }
00067 
00068   err = th_decode_ctl(decoding_context_, TH_DECCTL_SET_PPLEVEL, &level, sizeof(int));
00069   if (err) {
00070     ROS_ERROR("Failed to set post-processing level, error code %d", err);
00071     return pplevel_; // old value
00072   }
00073   return level;
00074 }
00075 
00076 //When using this caller is responsible for deleting oggpacket.packet!!
00077 void TheoraSubscriber::msgToOggPacket(const theora_image_transport::Packet &msg, ogg_packet &ogg)
00078 {
00079   ogg.bytes      = msg.data.size();
00080   ogg.b_o_s      = msg.b_o_s;
00081   ogg.e_o_s      = msg.e_o_s;
00082   ogg.granulepos = msg.granulepos;
00083   ogg.packetno   = msg.packetno;
00084   ogg.packet = new unsigned char[ogg.bytes];
00085   memcpy(ogg.packet, &msg.data[0], ogg.bytes);
00086 }
00087 
00088 void TheoraSubscriber::internalCallback(const theora_image_transport::PacketConstPtr& message, const Callback& callback)
00089 {
00091   ogg_packet oggpacket;
00092   msgToOggPacket(*message, oggpacket);
00093   boost::scoped_array<unsigned char> packet_guard(oggpacket.packet); // Make sure packet memory gets deleted
00094 
00095   // Beginning of logical stream flag means we're getting new headers
00096   if (oggpacket.b_o_s == 1) {
00097     // Clear all state, everything we knew is wrong
00098     received_header_ = false;
00099     received_keyframe_ = false;
00100     if (decoding_context_) {
00101       th_decode_free(decoding_context_);
00102       decoding_context_ = NULL;
00103     }
00104     th_setup_free(setup_info_);
00105     setup_info_ = NULL;
00106     th_info_clear(&header_info_);
00107     th_info_init(&header_info_);
00108     th_comment_clear(&header_comment_);
00109     th_comment_init(&header_comment_);
00110     latest_image_.reset();
00111   }
00112 
00113   // Decode header packets until we get the first video packet
00114   if (received_header_ == false) {
00115     int rval = th_decode_headerin(&header_info_, &header_comment_, &setup_info_, &oggpacket);
00116     switch (rval) {
00117       case 0:
00118         // We've received the full header; this is the first video packet.
00119         decoding_context_ = th_decode_alloc(&header_info_, setup_info_);
00120         if (!decoding_context_) {
00121           ROS_ERROR("[theora] Decoding parameters were invalid");
00122           return;
00123         }
00124         received_header_ = true;
00125         pplevel_ = updatePostProcessingLevel(pplevel_);
00126         break; // Continue on the video decoding
00127       case TH_EFAULT:
00128         ROS_WARN("[theora] EFAULT when processing header packet");
00129         return;
00130       case TH_EBADHEADER:
00131         ROS_WARN("[theora] Bad header packet");
00132         return;
00133       case TH_EVERSION:
00134         ROS_WARN("[theora] Header packet not decodable with this version of libtheora");
00135         return;
00136       case TH_ENOTFORMAT:
00137         ROS_WARN("[theora] Packet was not a Theora header");
00138         return;
00139       default:
00140         // If rval > 0, we successfully received a header packet.
00141         if (rval < 0)
00142           ROS_WARN("[theora] Error code %d when processing header packet", rval);
00143         return;
00144     }
00145   }
00146 
00147   // Wait for a keyframe if we haven't received one yet - delta frames are useless to us in that case
00148   received_keyframe_ = received_keyframe_ || (th_packet_iskeyframe(&oggpacket) == 1);
00149   if (!received_keyframe_)
00150     return;
00151   
00152   // We have a video packet we can handle, let's decode it
00153   int rval = th_decode_packetin(decoding_context_, &oggpacket, NULL);
00154   switch (rval) {
00155     case 0:
00156       break; // Yay, we got a frame. Carry on below.
00157     case TH_DUPFRAME:
00158       // Video data hasn't changed, so we update the timestamp and reuse the last received frame.
00159       ROS_DEBUG("[theora] Got a duplicate frame");
00160       if (latest_image_) {
00161         latest_image_->header = message->header;
00162         callback(latest_image_);
00163       }
00164       return;
00165     case TH_EFAULT:
00166       ROS_WARN("[theora] EFAULT processing video packet");
00167       return;
00168     case TH_EBADPACKET:
00169       ROS_WARN("[theora] Packet does not contain encoded video data");
00170       return;
00171     case TH_EIMPL:
00172       ROS_WARN("[theora] The video data uses bitstream features not supported by this version of libtheora");
00173       return;
00174     default:
00175       ROS_WARN("[theora] Error code %d when decoding video packet", rval);
00176       return;
00177   }
00178 
00179   // We have a new decoded frame available
00180   th_ycbcr_buffer ycbcr_buffer;
00181   th_decode_ycbcr_out(decoding_context_, ycbcr_buffer);
00182 
00183   // Wrap YCbCr channel data into OpenCV format
00184   th_img_plane &y_plane = ycbcr_buffer[0], &cb_plane = ycbcr_buffer[1], &cr_plane = ycbcr_buffer[2];
00185   cv::Mat y(y_plane.height, y_plane.width, CV_8UC1, y_plane.data, y_plane.stride);
00186   cv::Mat cb_sub(cb_plane.height, cb_plane.width, CV_8UC1, cb_plane.data, cb_plane.stride);
00187   cv::Mat cr_sub(cr_plane.height, cr_plane.width, CV_8UC1, cr_plane.data, cr_plane.stride);
00188 
00189   // Upsample chroma channels
00190   cv::Mat cb, cr;
00191   cv::pyrUp(cb_sub, cb);
00192   cv::pyrUp(cr_sub, cr);
00193 
00194   // Merge into interleaved image. Note OpenCV uses YCrCb, so we swap the chroma channels.
00195   cv::Mat ycrcb, channels[] = {y, cr, cb};
00196   cv::merge(channels, 3, ycrcb);
00197 
00198   // Convert to BGR color
00199   cv::Mat bgr, bgr_padded;
00200   cv::cvtColor(ycrcb, bgr_padded, CV_YCrCb2BGR);
00201   // Pull out original (non-padded) image region
00202   bgr = bgr_padded(cv::Rect(header_info_.pic_x, header_info_.pic_y,
00203                             header_info_.pic_width, header_info_.pic_height));
00204 
00205   latest_image_ = cv_bridge::CvImage(message->header, sensor_msgs::image_encodings::BGR8, bgr).toImageMsg();
00206   latest_image_->__connection_header = message->__connection_header;
00208   callback(latest_image_);
00209 }
00210 
00211 } //namespace theora_image_transport


theora_image_transport
Author(s): Patrick Mihelich, Ethan Dreyfuss
autogenerated on Sat Dec 28 2013 17:06:15