1 #ifndef CODEC_IMAGE_TRANSPORT_DECODING_SUBSCRIBERS_HPP
2 #define CODEC_IMAGE_TRANSPORT_DECODING_SUBSCRIBERS_HPP
11 #include <sensor_msgs/CompressedImage.h>
12 #include <sensor_msgs/Image.h>
15 #include <boost/mpl/string.hpp>
16 #include <boost/shared_ptr.hpp>
19 #include <libavcodec/avcodec.h>
20 #include <libavutil/imgutils.h>
21 #include <libswscale/swscale.h>
26 template < AVCodecID CodecID,
typename TransportName >
34 virtual std::string
getTransportName()
const {
return boost::mpl::c_str< TransportName >::value; }
38 uint32_t queue_size,
const Callback &callback,
43 av_log_set_level(AV_LOG_FATAL);
46 AVCodec *
const decoder(avcodec_find_decoder(CodecID));
58 if (avcodec_open2(
decoder_ctx_.get(), decoder, NULL) < 0) {
70 av_init_packet(&packet);
71 packet.size = message->data.size();
72 packet.data =
const_cast< uint8_t *
>(&message->data[0]);
75 if (avcodec_send_packet(
decoder_ctx_.get(), &packet) < 0) {
76 ROS_ERROR(
"Cannot send a packet to decoder");
89 const int res(avcodec_receive_frame(
decoder_ctx_.get(), frame.get()));
90 if (res == AVERROR(EAGAIN) || res == AVERROR_EOF) {
99 const sensor_msgs::ImagePtr out(
new sensor_msgs::Image());
100 out->header = message->header;
101 out->height = frame->height;
102 out->width = frame->width;
104 out->step = 3 * frame->width;
105 out->data.resize(3 * frame->width * frame->height);
111 frame->width, frame->height,
114 frame->width, frame->height, AV_PIX_FMT_BGR24,
116 SWS_FAST_BILINEAR, NULL, NULL, NULL),
118 int stride(out->step);
119 uint8_t *dst(&out->data[0]);
120 sws_scale(convert_ctx.get(),
122 frame->data, frame->linesize, 0, frame->height,
134 av_frame_free(&frame);
140 avcodec_free_context(&ctx);
147 case AV_PIX_FMT_YUVJ420P:
148 return AV_PIX_FMT_YUV420P;
149 case AV_PIX_FMT_YUVJ411P:
150 return AV_PIX_FMT_YUV411P;
151 case AV_PIX_FMT_YUVJ422P:
152 return AV_PIX_FMT_YUV422P;
153 case AV_PIX_FMT_YUVJ440P:
154 return AV_PIX_FMT_YUV440P;
155 case AV_PIX_FMT_YUVJ444P:
156 return AV_PIX_FMT_YUV444P;