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