1 #ifndef USB_CAM_CONTROLLERS_DECODING_CONTROLLERS
2 #define USB_CAM_CONTROLLERS_DECODING_CONTROLLERS
12 #include <sensor_msgs/Image.h>
18 #include <libavcodec/avcodec.h>
19 #include <libavutil/imgutils.h>
20 #include <libswscale/swscale.h>
25 template < AVCodecID CodecId, AVPixelFormat DstFormat, const std::
string *DstEncoding >
36 av_log_set_level(AV_LOG_FATAL);
39 AVCodec *
const decoder(avcodec_find_decoder(CodecId));
48 ROS_ERROR_STREAM(
"Cannot allocate a decoder context (codec id: " << CodecId <<
")");
53 if (avcodec_open2(
decoder_ctx_.get(), decoder, NULL) < 0) {
71 av_init_packet(&packet);
76 if (avcodec_send_packet(
decoder_ctx_.get(), &packet) < 0) {
77 ROS_ERROR_STREAM(
"Cannot send a packet to decoder (codec id: " << CodecId <<
")");
90 const int res(avcodec_receive_frame(
decoder_ctx_.get(), frame.get()));
91 if (res == AVERROR(EAGAIN) || res == AVERROR_EOF) {
100 const sensor_msgs::ImagePtr out(
new sensor_msgs::Image());
101 const int data_size(av_image_get_buffer_size(DstFormat, frame->width, frame->height, 1));
103 out->height = frame->height;
104 out->width = frame->width;
105 out->encoding = *DstEncoding;
106 out->step = data_size / frame->height;
107 out->data.resize(data_size);
113 frame->width, frame->height,
116 frame->width, frame->height, DstFormat,
118 SWS_FAST_BILINEAR, NULL, NULL, NULL),
120 int stride(out->step);
121 uint8_t *dst(&out->data[0]);
122 sws_scale(convert_ctx.get(),
124 frame->data, frame->linesize, 0, frame->height,
140 av_frame_free(&frame);
146 avcodec_free_context(&ctx);
153 case AV_PIX_FMT_YUVJ420P:
154 return AV_PIX_FMT_YUV420P;
155 case AV_PIX_FMT_YUVJ411P:
156 return AV_PIX_FMT_YUV411P;
157 case AV_PIX_FMT_YUVJ422P:
158 return AV_PIX_FMT_YUV422P;
159 case AV_PIX_FMT_YUVJ440P:
160 return AV_PIX_FMT_YUV440P;
161 case AV_PIX_FMT_YUVJ444P:
162 return AV_PIX_FMT_YUV444P;