decoding_subscribers.hpp
Go to the documentation of this file.
1 #ifndef CODEC_IMAGE_TRANSPORT_DECODING_SUBSCRIBERS_HPP
2 #define CODEC_IMAGE_TRANSPORT_DECODING_SUBSCRIBERS_HPP
3 
4 #include <string>
5 
8 #include <ros/console.h>
9 #include <ros/exception.h>
10 #include <ros/node_handle.h>
11 #include <sensor_msgs/CompressedImage.h>
12 #include <sensor_msgs/Image.h>
14 
15 #include <boost/mpl/string.hpp>
16 #include <boost/shared_ptr.hpp>
17 
18 extern "C" {
19 #include <libavcodec/avcodec.h>
20 #include <libavutil/imgutils.h>
21 #include <libswscale/swscale.h>
22 }
23 
25 
26 template < AVCodecID CodecID, typename TransportName >
28  : public image_transport::SimpleSubscriberPlugin< sensor_msgs::CompressedImage > {
29 public:
31 
32  virtual ~DecodingSubscriber() {}
33 
34  virtual std::string getTransportName() const { return boost::mpl::c_str< TransportName >::value; }
35 
36 private:
37  virtual void subscribeImpl(ros::NodeHandle &nh, const std::string &base_topic,
38  uint32_t queue_size, const Callback &callback,
39  const ros::VoidPtr &tracked_object,
40  const image_transport::TransportHints &transport_hints) {
41  if (!decoder_ctx_) {
42  // init libavformat
43  av_log_set_level(AV_LOG_FATAL);
44 
45  // find a decoder
46  AVCodec *const decoder(avcodec_find_decoder(CodecID));
47  if (!decoder) {
48  throw ros::Exception("Cannot find a decoder");
49  }
50 
51  // allocate a decoder context
52  decoder_ctx_.reset(avcodec_alloc_context3(decoder), deleteAVCodecContext);
53  if (!decoder_ctx_) {
54  throw ros::Exception("Cannot allocate a decoder context");
55  }
56 
57  // open decoder
58  if (avcodec_open2(decoder_ctx_.get(), decoder, NULL) < 0) {
59  throw ros::Exception("Failed to open codec");
60  }
61  }
62 
63  Base::subscribeImpl(nh, base_topic, queue_size, callback, tracked_object, transport_hints);
64  }
65 
66  virtual void internalCallback(const sensor_msgs::CompressedImage::ConstPtr &message,
67  const Callback &user_cb) {
68  // set packet data from the input message
69  AVPacket packet;
70  av_init_packet(&packet);
71  packet.size = message->data.size();
72  packet.data = const_cast< uint8_t * >(&message->data[0]);
73 
74  // send the packet to the decoder
75  if (avcodec_send_packet(decoder_ctx_.get(), &packet) < 0) {
76  ROS_ERROR("Cannot send a packet to decoder");
77  return;
78  }
79 
80  while (true) {
81  // allocate a frame for decoded data
82  boost::shared_ptr< AVFrame > frame(av_frame_alloc(), deleteAVFrame);
83  if (!frame) {
84  ROS_ERROR("Cannot allocate frame");
85  return;
86  }
87 
88  // receive the decoded data from the decoder
89  const int res(avcodec_receive_frame(decoder_ctx_.get(), frame.get()));
90  if (res == AVERROR(EAGAIN) || res == AVERROR_EOF) {
91  // no more frames in the packet
92  return;
93  } else if (res < 0) {
94  ROS_ERROR("Cannot receive a frame");
95  return;
96  }
97 
98  // allocate output message
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;
103  out->encoding = sensor_msgs::image_encodings::BGR8;
104  out->step = 3 * frame->width;
105  out->data.resize(3 * frame->width * frame->height);
106 
107  // layout data by converting color spaces (YUV -> RGB)
109  sws_getContext(
110  // src formats
111  frame->width, frame->height,
112  toUndeprecated(static_cast< AVPixelFormat >(frame->format)),
113  // dst formats
114  frame->width, frame->height, AV_PIX_FMT_BGR24,
115  // flags & filters
116  SWS_FAST_BILINEAR, NULL, NULL, NULL),
117  sws_freeContext);
118  int stride(out->step);
119  uint8_t *dst(&out->data[0]);
120  sws_scale(convert_ctx.get(),
121  // src data
122  frame->data, frame->linesize, 0, frame->height,
123  // dst data
124  &dst, &stride);
125 
126  // exec user callback
127  user_cb(out);
128  }
129  }
130 
131  // Deleter for auto free/close of libav objects
132  static void deleteAVFrame(AVFrame *frame) {
133  if (frame) {
134  av_frame_free(&frame);
135  }
136  }
137 
138  static void deleteAVCodecContext(AVCodecContext *ctx) {
139  if (ctx) {
140  avcodec_free_context(&ctx);
141  }
142  }
143 
144  // Workaround to avoid deprecated pixel format warning
145  static AVPixelFormat toUndeprecated(const AVPixelFormat format) {
146  switch (format) {
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;
157  default:
158  return format;
159  }
160  }
161 
162 private:
164 
166 };
167 
170 
171 } // namespace decoding_image_transport
172 
173 #endif
codec_image_transport::DecodingSubscriber::~DecodingSubscriber
virtual ~DecodingSubscriber()
Definition: decoding_subscribers.hpp:32
node_handle.h
image_encodings.h
boost::shared_ptr< void >
codec_image_transport::H264Subscriber
DecodingSubscriber< AV_CODEC_ID_H264, boost::mpl::string< 'h', '2', '6', '4' > > H264Subscriber
Definition: decoding_subscribers.hpp:169
image_transport::SubscriberPlugin::Callback
boost::function< void(const sensor_msgs::ImageConstPtr &)> Callback
ros::Exception
codec_image_transport::DecodingSubscriber::getTransportName
virtual std::string getTransportName() const
Definition: decoding_subscribers.hpp:34
image_transport::SimpleSubscriberPlugin< sensor_msgs::CompressedImage >::subscribeImpl
virtual void subscribeImpl(ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, const Callback &callback, const ros::VoidPtr &tracked_object, const TransportHints &transport_hints)
codec_image_transport::DecodingSubscriber::decoder_ctx_
boost::shared_ptr< AVCodecContext > decoder_ctx_
Definition: decoding_subscribers.hpp:165
simple_subscriber_plugin.h
codec_image_transport::DecodingSubscriber
Definition: decoding_subscribers.hpp:27
console.h
transport_hints.h
codec_image_transport::DecodingSubscriber::internalCallback
virtual void internalCallback(const sensor_msgs::CompressedImage::ConstPtr &message, const Callback &user_cb)
Definition: decoding_subscribers.hpp:66
codec_image_transport::DecodingSubscriber::toUndeprecated
static AVPixelFormat toUndeprecated(const AVPixelFormat format)
Definition: decoding_subscribers.hpp:145
codec_image_transport
Definition: decoding_subscribers.hpp:24
codec_image_transport::DecodingSubscriber::deleteAVCodecContext
static void deleteAVCodecContext(AVCodecContext *ctx)
Definition: decoding_subscribers.hpp:138
codec_image_transport::DecodingSubscriber::Base
image_transport::SimpleSubscriberPlugin< sensor_msgs::CompressedImage > Base
Definition: decoding_subscribers.hpp:163
image_transport::SimpleSubscriberPlugin< sensor_msgs::CompressedImage >::nh
const ros::NodeHandle & nh() const
codec_image_transport::DecodingSubscriber::DecodingSubscriber
DecodingSubscriber()
Definition: decoding_subscribers.hpp:30
ROS_ERROR
#define ROS_ERROR(...)
sensor_msgs::image_encodings::BGR8
const std::string BGR8
codec_image_transport::DecodingSubscriber::deleteAVFrame
static void deleteAVFrame(AVFrame *frame)
Definition: decoding_subscribers.hpp:132
image_transport::TransportHints
image_transport::SimpleSubscriberPlugin
codec_image_transport::DecodingSubscriber::subscribeImpl
virtual void subscribeImpl(ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, const Callback &callback, const ros::VoidPtr &tracked_object, const image_transport::TransportHints &transport_hints)
Definition: decoding_subscribers.hpp:37
ros::NodeHandle
exception.h


codec_image_transport
Author(s):
autogenerated on Wed Mar 2 2022 00:02:38