00001 #include "theora_image_transport/theora_publisher.h"
00002 #include <sensor_msgs/image_encodings.h>
00003
00004 #include <vector>
00005 #include <cstdio>
00006
00007 using namespace std;
00008
00009 namespace theora_image_transport {
00010
00011 TheoraPublisher::TheoraPublisher()
00012 {
00013
00014 th_info_init(&encoder_setup_);
00015
00016 encoder_setup_.pic_x = 0;
00017 encoder_setup_.pic_y = 0;
00018 encoder_setup_.colorspace = TH_CS_UNSPECIFIED;
00019 encoder_setup_.pixel_fmt = TH_PF_420;
00020 encoder_setup_.aspect_numerator = 1;
00021 encoder_setup_.aspect_denominator = 1;
00022 encoder_setup_.fps_numerator = 1;
00023 encoder_setup_.fps_denominator = 1;
00024 encoder_setup_.keyframe_granule_shift = 6;
00025
00026 encoder_setup_.target_bitrate = -1;
00027 encoder_setup_.quality = -1;
00028 }
00029
00030 TheoraPublisher::~TheoraPublisher()
00031 {
00032 th_info_clear(&encoder_setup_);
00033 }
00034
00035 void TheoraPublisher::advertiseImpl(ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size,
00036 const image_transport::SubscriberStatusCallback &user_connect_cb,
00037 const image_transport::SubscriberStatusCallback &user_disconnect_cb,
00038 const ros::VoidPtr &tracked_object, bool latch)
00039 {
00040
00041 queue_size += 4;
00042
00043
00044 latch = false;
00045 typedef image_transport::SimplePublisherPlugin<theora_image_transport::Packet> Base;
00046 Base::advertiseImpl(nh, base_topic, queue_size, user_connect_cb, user_disconnect_cb, tracked_object, latch);
00047
00048
00049 reconfigure_server_ = boost::make_shared<ReconfigureServer>(this->nh());
00050 ReconfigureServer::CallbackType f = boost::bind(&TheoraPublisher::configCb, this, _1, _2);
00051 reconfigure_server_->setCallback(f);
00052 }
00053
00054 void TheoraPublisher::configCb(Config& config, uint32_t level)
00055 {
00056
00057 long bitrate = 0;
00058 if (config.optimize_for == theora_image_transport::TheoraPublisher_Bitrate)
00059 bitrate = config.target_bitrate;
00060 bool update_bitrate = bitrate && encoder_setup_.target_bitrate != bitrate;
00061 bool update_quality = !bitrate && ((encoder_setup_.quality != config.quality) || encoder_setup_.target_bitrate > 0);
00062 encoder_setup_.quality = config.quality;
00063 encoder_setup_.target_bitrate = bitrate;
00064 keyframe_frequency_ = config.keyframe_frequency;
00065
00066 if (encoding_context_) {
00067 int err = 0;
00068
00069 #ifdef TH_ENCCTL_SET_BITRATE
00070 if (update_bitrate) {
00071 err = th_encode_ctl(encoding_context_.get(), TH_ENCCTL_SET_BITRATE, &bitrate, sizeof(long));
00072 if (err)
00073 ROS_ERROR("Failed to update bitrate dynamically");
00074 }
00075 #else
00076 err |= update_bitrate;
00077 #endif
00078
00079 #ifdef TH_ENCCTL_SET_QUALITY
00080 if (update_quality) {
00081 err = th_encode_ctl(encoding_context_.get(), TH_ENCCTL_SET_QUALITY, &config.quality, sizeof(int));
00082
00083
00084 if (err && err != TH_EINVAL)
00085 ROS_ERROR("Failed to update quality dynamically");
00086 }
00087 #else
00088 err |= update_quality;
00089 #endif
00090
00091
00092 if (err) {
00093 encoding_context_.reset();
00094 }
00095
00096 else {
00097 updateKeyframeFrequency();
00098 config.keyframe_frequency = keyframe_frequency_;
00099 }
00100 }
00101 }
00102
00103 void TheoraPublisher::connectCallback(const ros::SingleSubscriberPublisher& pub)
00104 {
00105
00106 for (unsigned int i = 0; i < stream_header_.size(); i++) {
00107 pub.publish(stream_header_[i]);
00108 }
00109 }
00110
00111 static void cvToTheoraPlane(cv::Mat& mat, th_img_plane& plane)
00112 {
00113 plane.width = mat.cols;
00114 plane.height = mat.rows;
00115 plane.stride = mat.step;
00116 plane.data = mat.data;
00117 }
00118
00119 void TheoraPublisher::publish(const sensor_msgs::Image& message, const PublishFn& publish_fn) const
00120 {
00121 if (!ensureEncodingContext(message, publish_fn))
00122 return;
00123
00127 if (!img_bridge_.fromImage(message, "bgr8")) {
00128 ROS_ERROR("Unable to convert from '%s' to bgr8", message.encoding.c_str());
00129 return;
00130 }
00131
00132 cv::Mat bgr(img_bridge_.toIpl()), bgr_padded;
00133 int frame_width = encoder_setup_.frame_width, frame_height = encoder_setup_.frame_height;
00134 if (frame_width == bgr.cols && frame_height == bgr.rows) {
00135 bgr_padded = bgr;
00136 }
00137 else {
00138 bgr_padded = cv::Mat::zeros(frame_height, frame_width, bgr.type());
00139 cv::Mat pic_roi = bgr_padded(cv::Rect(0, 0, bgr.cols, bgr.rows));
00140 bgr.copyTo(pic_roi);
00141 }
00142
00143
00144 cv::Mat ycrcb;
00145 cv::cvtColor(bgr_padded, ycrcb, CV_BGR2YCrCb);
00146
00147
00148 cv::Mat ycrcb_planes[3];
00149 cv::split(ycrcb, ycrcb_planes);
00150
00151
00152 cv::Mat y = ycrcb_planes[0], cr, cb;
00153 cv::pyrDown(ycrcb_planes[1], cr);
00154 cv::pyrDown(ycrcb_planes[2], cb);
00155
00156
00157 th_ycbcr_buffer ycbcr_buffer;
00158 cvToTheoraPlane(y, ycbcr_buffer[0]);
00159 cvToTheoraPlane(cb, ycbcr_buffer[1]);
00160 cvToTheoraPlane(cr, ycbcr_buffer[2]);
00161
00162
00163 int rval = th_encode_ycbcr_in(encoding_context_.get(), ycbcr_buffer);
00164 if (rval == TH_EFAULT) {
00165 ROS_ERROR("[theora] EFAULT in submitting uncompressed frame to encoder");
00166 return;
00167 }
00168 if (rval == TH_EINVAL) {
00169 ROS_ERROR("[theora] EINVAL in submitting uncompressed frame to encoder");
00170 return;
00171 }
00172
00173
00174 ogg_packet oggpacket;
00175 theora_image_transport::Packet output;
00176 while ((rval = th_encode_packetout(encoding_context_.get(), 0, &oggpacket)) > 0) {
00177 oggPacketToMsg(message.header, oggpacket, output);
00178 publish_fn(output);
00179 }
00180 if (rval == TH_EFAULT)
00181 ROS_ERROR("[theora] EFAULT in retrieving encoded video data packets");
00182 }
00183
00184 void freeContext(th_enc_ctx* context)
00185 {
00186 if (context) th_encode_free(context);
00187 }
00188
00189 bool TheoraPublisher::ensureEncodingContext(const sensor_msgs::Image& image, const PublishFn& publish_fn) const
00190 {
00192 if (encoding_context_ && encoder_setup_.pic_width == image.width &&
00193 encoder_setup_.pic_height == image.height)
00194 return true;
00195
00196
00197
00198 encoder_setup_.frame_width = (image.width + 15) & ~0xF;
00199 encoder_setup_.frame_height = (image.height + 15) & ~0xF;
00200 encoder_setup_.pic_width = image.width;
00201 encoder_setup_.pic_height = image.height;
00202
00203
00204 encoding_context_.reset(th_encode_alloc(&encoder_setup_), freeContext);
00205 if (!encoding_context_) {
00206 ROS_ERROR("[theora] Failed to create encoding context");
00207 return false;
00208 }
00209
00210 updateKeyframeFrequency();
00211
00212 th_comment comment;
00213 th_comment_init(&comment);
00214 boost::shared_ptr<th_comment> clear_guard(&comment, th_comment_clear);
00216 comment.vendor = strdup("Willow Garage theora_image_transport");
00217
00218
00220 stream_header_.clear();
00221 ogg_packet oggpacket;
00222 while (th_encode_flushheader(encoding_context_.get(), &comment, &oggpacket) > 0) {
00223 stream_header_.push_back(theora_image_transport::Packet());
00224 oggPacketToMsg(image.header, oggpacket, stream_header_.back());
00225 publish_fn(stream_header_.back());
00226 }
00227 return true;
00228 }
00229
00230 void TheoraPublisher::oggPacketToMsg(const roslib::Header& header, const ogg_packet &oggpacket,
00231 theora_image_transport::Packet &msg) const
00232 {
00233 msg.header = header;
00234 msg.b_o_s = oggpacket.b_o_s;
00235 msg.e_o_s = oggpacket.e_o_s;
00236 msg.granulepos = oggpacket.granulepos;
00237 msg.packetno = oggpacket.packetno;
00238 msg.data.resize(oggpacket.bytes);
00239 memcpy(&msg.data[0], oggpacket.packet, oggpacket.bytes);
00240 }
00241
00242 void TheoraPublisher::updateKeyframeFrequency() const
00243 {
00244 ogg_uint32_t desired_frequency = keyframe_frequency_;
00245 if (th_encode_ctl(encoding_context_.get(), TH_ENCCTL_SET_KEYFRAME_FREQUENCY_FORCE,
00246 &keyframe_frequency_, sizeof(ogg_uint32_t)))
00247 ROS_ERROR("Failed to change keyframe frequency");
00248 if (keyframe_frequency_ != desired_frequency)
00249 ROS_WARN("Couldn't set keyframe frequency to %d, actually set to %d",
00250 desired_frequency, keyframe_frequency_);
00251 }
00252
00253 }