$search
00001 #include "theora_imagem_transport/theora_publisher.h" 00002 #include <sensor_msgs/image_encodings.h> 00003 #include <opencv/highgui.h> 00004 00005 #include <sensor_msgs/image_encodings.h> 00006 #include <std_msgs/Header.h> 00007 00008 #include <vector> 00009 #include <cstdio> //for memcpy 00010 00011 using namespace std; 00012 00013 namespace tit = theora_image_transport; 00014 00015 namespace theora_imagem_transport 00016 { 00017 00018 TheoraPublisher::TheoraPublisher() 00019 { 00020 // Initialize info structure fields that don't change 00021 th_info_init(&encoder_setup_); 00022 00023 encoder_setup_.pic_x = 0; 00024 encoder_setup_.pic_y = 0; 00025 encoder_setup_.colorspace = TH_CS_UNSPECIFIED; 00026 encoder_setup_.pixel_fmt = TH_PF_420; // See bottom of http://www.theora.org/doc/libtheora-1.1beta1/codec_8h.html 00027 encoder_setup_.aspect_numerator = 1; 00028 encoder_setup_.aspect_denominator = 1; 00029 encoder_setup_.fps_numerator = 1; // don't know the frame rate ahead of time 00030 encoder_setup_.fps_denominator = 1; 00031 encoder_setup_.keyframe_granule_shift = 6; // A good default for streaming applications 00032 // Note: target_bitrate and quality set to correct values in configCb 00033 encoder_setup_.target_bitrate = -1; 00034 encoder_setup_.quality = -1; 00035 } 00036 00037 TheoraPublisher::~TheoraPublisher() 00038 { 00039 th_info_clear(&encoder_setup_); 00040 } 00041 00042 00043 void TheoraPublisher::advertiseImpl(ros::NodeHandle & nh, const std::string& base_topic, uint32_t queue_size, 00044 const message_transport::SingleSubscriberPublisher<sensor_msgs::Image>::StatusCB& user_connect_cb, 00045 const message_transport::SingleSubscriberPublisher<sensor_msgs::Image>::StatusCB& user_disconnect_cb, 00046 const ros::VoidPtr& tracked_object, bool latch) 00047 { 00048 // queue_size doesn't account for the 3 header packets, so we correct (with a little extra) here. 00049 queue_size += 4; 00050 // Latching doesn't make a lot of sense with this transport. Could try to save the last keyframe, 00051 // but do you then send all following delta frames too? 00052 latch = false; 00053 typedef message_transport::SimplePublisherPlugin<sensor_msgs::Image,theora_image_transport::Packet> Base; 00054 Base::advertiseImpl(nh, base_topic, queue_size, user_connect_cb, user_disconnect_cb, tracked_object, latch); 00055 00056 // Set up reconfigure server for this topic 00057 reconfigure_server_ = boost::make_shared<ReconfigureServer>(this->getParamNode()); 00058 ReconfigureServer::CallbackType f = boost::bind(&TheoraPublisher::configCb, this, _1, _2); 00059 reconfigure_server_->setCallback(f); 00060 } 00061 00062 void TheoraPublisher::configCb(Config& config, uint32_t level) 00063 { 00064 // target_bitrate must be 0 if we're using quality. 00065 long bitrate = 0; 00066 if (config.optimize_for == theora_imagem_transport::TheoraPublisher_Bitrate) 00067 bitrate = config.target_bitrate; 00068 bool update_bitrate = bitrate && encoder_setup_.target_bitrate != bitrate; 00069 bool update_quality = !bitrate && ((encoder_setup_.quality != config.quality) || encoder_setup_.target_bitrate > 0); 00070 encoder_setup_.quality = config.quality; 00071 encoder_setup_.target_bitrate = bitrate; 00072 keyframe_frequency_ = config.keyframe_frequency; 00073 00074 if (encoding_context_) { 00075 int err = 0; 00076 // libtheora 1.1 lets us change quality or bitrate on the fly, 1.0 does not. 00077 #ifdef TH_ENCCTL_SET_BITRATE 00078 if (update_bitrate) { 00079 err = th_encode_ctl(encoding_context_.get(), TH_ENCCTL_SET_BITRATE, &bitrate, sizeof(long)); 00080 if (err) 00081 ROS_ERROR("Failed to update bitrate dynamically"); 00082 } 00083 #else 00084 err |= update_bitrate; 00085 #endif 00086 00087 #ifdef TH_ENCCTL_SET_QUALITY 00088 if (update_quality) { 00089 err = th_encode_ctl(encoding_context_.get(), TH_ENCCTL_SET_QUALITY, &config.quality, sizeof(int)); 00090 // In 1.1 above call will fail if a bitrate has previously been set. That restriction may 00091 // be relaxed in a future version. Complain on other failures. 00092 if (err && err != TH_EINVAL) 00093 ROS_ERROR("Failed to update quality dynamically"); 00094 } 00095 #else 00096 err |= update_quality; 00097 #endif 00098 00099 // If unable to change parameters dynamically, just create a new encoding context. 00100 if (err) { 00101 encoding_context_.reset(); 00102 } 00103 // Otherwise, do the easy updates and keep going! 00104 else { 00105 updateKeyframeFrequency(); 00106 config.keyframe_frequency = keyframe_frequency_; // In case desired value was unattainable 00107 } 00108 } 00109 } 00110 00111 void TheoraPublisher::connectCallback(const ros::SingleSubscriberPublisher& pub) 00112 { 00113 // Send the header packets to new subscribers 00114 for (unsigned int i = 0; i < stream_header_.size(); i++) { 00115 pub.publish(stream_header_[i]); 00116 } 00117 } 00118 00119 static void cvToTheoraPlane(cv::Mat& mat, th_img_plane& plane) 00120 { 00121 plane.width = mat.cols; 00122 plane.height = mat.rows; 00123 plane.stride = mat.step; 00124 plane.data = mat.data; 00125 } 00126 00127 void TheoraPublisher::publish(const sensor_msgs::Image& message, 00128 const message_transport::SimplePublisherPlugin<sensor_msgs::Image,theora_image_transport::Packet>::PublishFn& publish_fn) const 00129 { 00130 if (!ensureEncodingContext(message, publish_fn)) 00131 return; 00132 00133 // Temporary boost pointer to define the life time of cv_image_ptr 00134 // below 00135 boost::shared_ptr<int> tracked_object(new int(0)); 00136 00140 cv_bridge::CvImageConstPtr cv_image_ptr = cv_bridge::toCvShare(message,tracked_object, "bgr8"); 00141 if (!cv_image_ptr) { 00142 ROS_ERROR("Unable to convert from '%s' to bgr8", message.encoding.c_str()); 00143 return; 00144 } 00145 00146 const cv::Mat bgr = cv_image_ptr->image; 00147 cv::Mat bgr_padded; 00148 int frame_width = encoder_setup_.frame_width, frame_height = encoder_setup_.frame_height; 00149 if (frame_width == bgr.cols && frame_height == bgr.rows) { 00150 bgr_padded = bgr; 00151 } 00152 else { 00153 bgr_padded = cv::Mat::zeros(frame_height, frame_width, bgr.type()); 00154 cv::Mat pic_roi = bgr_padded(cv::Rect(0, 0, bgr.cols, bgr.rows)); 00155 bgr.copyTo(pic_roi); 00156 } 00157 00158 // Convert image to Y'CbCr color space used by Theora 00159 cv::Mat ycrcb; 00160 cv::cvtColor(bgr_padded, ycrcb, CV_BGR2YCrCb); 00161 00162 // Split channels 00163 cv::Mat ycrcb_planes[3]; 00164 cv::split(ycrcb, ycrcb_planes); 00165 00166 // Use Y as-is but subsample chroma channels 00167 cv::Mat y = ycrcb_planes[0], cr, cb; 00168 cv::pyrDown(ycrcb_planes[1], cr); 00169 cv::pyrDown(ycrcb_planes[2], cb); 00170 00171 // Construct Theora image buffer 00172 th_ycbcr_buffer ycbcr_buffer; 00173 cvToTheoraPlane(y, ycbcr_buffer[0]); 00174 cvToTheoraPlane(cb, ycbcr_buffer[1]); 00175 cvToTheoraPlane(cr, ycbcr_buffer[2]); 00176 00177 // Submit frame to the encoder 00178 int rval = th_encode_ycbcr_in(encoding_context_.get(), ycbcr_buffer); 00179 if (rval == TH_EFAULT) { 00180 ROS_ERROR("[theora] EFAULT in submitting uncompressed frame to encoder"); 00181 return; 00182 } 00183 if (rval == TH_EINVAL) { 00184 ROS_ERROR("[theora] EINVAL in submitting uncompressed frame to encoder"); 00185 return; 00186 } 00187 00188 // Retrieve and publish encoded video data packets 00189 ogg_packet oggpacket; 00190 theora_image_transport::Packet output; 00191 while ((rval = th_encode_packetout(encoding_context_.get(), 0, &oggpacket)) > 0) { 00192 oggPacketToMsg(message.header, oggpacket, output); 00193 publish_fn(output); 00194 } 00195 if (rval == TH_EFAULT) 00196 ROS_ERROR("[theora] EFAULT in retrieving encoded video data packets"); 00197 } 00198 00199 void freeContext(th_enc_ctx* context) 00200 { 00201 if (context) th_encode_free(context); 00202 } 00203 00204 bool TheoraPublisher::ensureEncodingContext(const sensor_msgs::Image& image, const PublishFn& publish_fn) const 00205 { 00207 if (encoding_context_ && encoder_setup_.pic_width == image.width && 00208 encoder_setup_.pic_height == image.height) 00209 return true; 00210 00211 // Theora has a divisible-by-sixteen restriction for the encoded frame size, so 00212 // scale the picture size up to the nearest multiple of 16 and calculate offsets. 00213 encoder_setup_.frame_width = (image.width + 15) & ~0xF; 00214 encoder_setup_.frame_height = (image.height + 15) & ~0xF; 00215 encoder_setup_.pic_width = image.width; 00216 encoder_setup_.pic_height = image.height; 00217 00218 // Allocate encoding context. Smart pointer ensures that th_encode_free gets called. 00219 encoding_context_.reset(th_encode_alloc(&encoder_setup_), freeContext); 00220 if (!encoding_context_) { 00221 ROS_ERROR("[theora] Failed to create encoding context"); 00222 return false; 00223 } 00224 00225 updateKeyframeFrequency(); 00226 00227 th_comment comment; 00228 th_comment_init(&comment); 00229 boost::shared_ptr<th_comment> clear_guard(&comment, th_comment_clear); 00231 comment.vendor = strdup("Willow Garage theora_image_transport"); 00232 00233 // Construct the header and stream it in case anyone is already listening 00235 stream_header_.clear(); 00236 ogg_packet oggpacket; 00237 while (th_encode_flushheader(encoding_context_.get(), &comment, &oggpacket) > 0) { 00238 stream_header_.push_back(theora_image_transport::Packet()); 00239 oggPacketToMsg(image.header, oggpacket, stream_header_.back()); 00240 publish_fn(stream_header_.back()); 00241 } 00242 return true; 00243 } 00244 00245 void TheoraPublisher::oggPacketToMsg(const std_msgs::Header& header, const ogg_packet &oggpacket, 00246 theora_image_transport::Packet &msg) const 00247 { 00248 msg.header = header; 00249 msg.b_o_s = oggpacket.b_o_s; 00250 msg.e_o_s = oggpacket.e_o_s; 00251 msg.granulepos = oggpacket.granulepos; 00252 msg.packetno = oggpacket.packetno; 00253 msg.data.resize(oggpacket.bytes); 00254 memcpy(&msg.data[0], oggpacket.packet, oggpacket.bytes); 00255 } 00256 00257 void TheoraPublisher::updateKeyframeFrequency() const 00258 { 00259 ogg_uint32_t desired_frequency = keyframe_frequency_; 00260 if (th_encode_ctl(encoding_context_.get(), TH_ENCCTL_SET_KEYFRAME_FREQUENCY_FORCE, 00261 &keyframe_frequency_, sizeof(ogg_uint32_t))) 00262 ROS_ERROR("Failed to change keyframe frequency"); 00263 if (keyframe_frequency_ != desired_frequency) 00264 ROS_WARN("Couldn't set keyframe frequency to %d, actually set to %d", 00265 desired_frequency, keyframe_frequency_); 00266 } 00267 00268 00269 } //namespace theora_imagem_transport