decoding_controllers.hpp
Go to the documentation of this file.
1 #ifndef USB_CAM_CONTROLLERS_DECODING_CONTROLLERS
2 #define USB_CAM_CONTROLLERS_DECODING_CONTROLLERS
3 
4 #include <string>
5 
8 #include <ros/console.h>
9 #include <ros/duration.h>
10 #include <ros/node_handle.h>
11 #include <ros/time.h>
12 #include <sensor_msgs/Image.h>
16 
17 extern "C" {
18 #include <libavcodec/avcodec.h>
19 #include <libavutil/imgutils.h>
20 #include <libswscale/swscale.h>
21 }
22 
23 namespace usb_cam_controllers {
24 
25 template < AVCodecID CodecId, AVPixelFormat DstFormat, const std::string *DstEncoding >
27 public:
29 
30  virtual ~DecodingController() {}
31 
32 protected:
34  ros::NodeHandle &controller_nh) {
35  // init libavcodec
36  av_log_set_level(AV_LOG_FATAL);
37 
38  // find h264 decoder
39  AVCodec *const decoder(avcodec_find_decoder(CodecId));
40  if (!decoder) {
41  ROS_ERROR_STREAM("Cannot find the decoder (codec id: " << CodecId << ")");
42  return false;
43  }
44 
45  // allocate h264 decoder context
46  decoder_ctx_.reset(avcodec_alloc_context3(decoder), deleteAVCodecContext);
47  if (!decoder_ctx_) {
48  ROS_ERROR_STREAM("Cannot allocate a decoder context (codec id: " << CodecId << ")");
49  return false;
50  }
51 
52  // open decoder
53  if (avcodec_open2(decoder_ctx_.get(), decoder, NULL) < 0) {
54  ROS_ERROR_STREAM("Failed to open the codec (codec id: " << CodecId << ")");
55  return false;
56  }
57 
58  // init publisher for decoded images
59  publisher_ = image_transport::ImageTransport(controller_nh).advertise("image", 1);
60 
61  return true;
62  }
63 
64  virtual void startingImpl(const ros::Time &time) {
65  // nothing to do
66  }
67 
68  virtual void updateImpl(const ros::Time &time, const ros::Duration &period) {
69  // set packet data from the input message
70  AVPacket packet;
71  av_init_packet(&packet);
72  packet.size = packet_iface_.getLength();
73  packet.data = const_cast< uint8_t * >(packet_iface_.getStartAs< uint8_t >());
74 
75  // send the packet to the decoder
76  if (avcodec_send_packet(decoder_ctx_.get(), &packet) < 0) {
77  ROS_ERROR_STREAM("Cannot send a packet to decoder (codec id: " << CodecId << ")");
78  return;
79  }
80 
81  while (true) {
82  // allocate a frame for decoded data
83  boost::shared_ptr< AVFrame > frame(av_frame_alloc(), deleteAVFrame);
84  if (!frame) {
85  ROS_ERROR_STREAM("Cannot allocate a frame");
86  return;
87  }
88 
89  // receive the decoded data from the decoder
90  const int res(avcodec_receive_frame(decoder_ctx_.get(), frame.get()));
91  if (res == AVERROR(EAGAIN) || res == AVERROR_EOF) {
92  // no more frames in the packet
93  return;
94  } else if (res < 0) {
95  ROS_ERROR("Cannot receive a frame");
96  return;
97  }
98 
99  // allocate output message
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));
102  out->header.stamp = packet_iface_.getStamp();
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);
108 
109  // layout data by converting color spaces
111  sws_getContext(
112  // src formats
113  frame->width, frame->height,
114  toUndeprecated(static_cast< AVPixelFormat >(frame->format)),
115  // dst formats
116  frame->width, frame->height, DstFormat,
117  // flags & filters
118  SWS_FAST_BILINEAR, NULL, NULL, NULL),
119  sws_freeContext);
120  int stride(out->step);
121  uint8_t *dst(&out->data[0]);
122  sws_scale(convert_ctx.get(),
123  // src data
124  frame->data, frame->linesize, 0, frame->height,
125  // dst data
126  &dst, &stride);
127 
128  publisher_.publish(out);
129  }
130  }
131 
132  virtual void stoppingImpl(const ros::Time &time) {
133  // nothing to do
134  }
135 
136 private:
137  // Deleter for auto free/close of libav objects
138  static void deleteAVFrame(AVFrame *frame) {
139  if (frame) {
140  av_frame_free(&frame);
141  }
142  }
143 
144  static void deleteAVCodecContext(AVCodecContext *ctx) {
145  if (ctx) {
146  avcodec_free_context(&ctx);
147  }
148  }
149 
150  // Workaround to avoid deprecated pixel format warning
151  static AVPixelFormat toUndeprecated(const AVPixelFormat format) {
152  switch (format) {
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;
163  default:
164  return format;
165  }
166  }
167 
168 private:
171 };
172 
173 typedef DecodingController< AV_CODEC_ID_H264, AV_PIX_FMT_BGR24,
176 typedef DecodingController< AV_CODEC_ID_MJPEG, AV_PIX_FMT_BGR24,
179 
180 } // namespace usb_cam_controllers
181 
182 #endif
usb_cam_controllers
Definition: camera_info_controller.hpp:17
usb_cam_controllers::SimplePacketController::packet_iface_
usb_cam_hardware_interface::PacketHandle packet_iface_
Definition: simple_packet_controller.hpp:85
usb_cam_controllers::MjpegController
DecodingController< AV_CODEC_ID_MJPEG, AV_PIX_FMT_BGR24, &sensor_msgs::image_encodings::BGR8 > MjpegController
Definition: decoding_controllers.hpp:178
node_handle.h
usb_cam_controllers::DecodingController::toUndeprecated
static AVPixelFormat toUndeprecated(const AVPixelFormat format)
Definition: decoding_controllers.hpp:151
image_encodings.h
usb_cam_hardware_interface::PacketHandle::getStamp
ros::Time getStamp() const
image_transport::ImageTransport
usb_cam_controllers::DecodingController
Definition: decoding_controllers.hpp:26
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
boost::shared_ptr
usb_cam_controllers::DecodingController::initImpl
virtual bool initImpl(usb_cam_hardware_interface::PacketInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Definition: decoding_controllers.hpp:33
time.h
usb_cam_controllers::H264Controller
DecodingController< AV_CODEC_ID_H264, AV_PIX_FMT_BGR24, &sensor_msgs::image_encodings::BGR8 > H264Controller
Definition: decoding_controllers.hpp:175
usb_cam_controllers::DecodingController::~DecodingController
virtual ~DecodingController()
Definition: decoding_controllers.hpp:30
usb_cam_hardware_interface::PacketHandle::getStartAs
const Byte * getStartAs() const
packet_interface.hpp
publisher.h
image_transport::ImageTransport::advertise
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
console.h
duration.h
usb_cam_controllers::DecodingController::publisher_
image_transport::Publisher publisher_
Definition: decoding_controllers.hpp:170
usb_cam_hardware_interface::PacketHandle::getLength
std::size_t getLength() const
image_transport::Publisher::publish
void publish(const sensor_msgs::Image &message) const
simple_packet_controller.hpp
usb_cam_controllers::DecodingController::deleteAVFrame
static void deleteAVFrame(AVFrame *frame)
Definition: decoding_controllers.hpp:138
image_transport.h
usb_cam_controllers::DecodingController::decoder_ctx_
boost::shared_ptr< AVCodecContext > decoder_ctx_
Definition: decoding_controllers.hpp:169
usb_cam_hardware_interface::PacketInterface
usb_cam_controllers::DecodingController::startingImpl
virtual void startingImpl(const ros::Time &time)
Definition: decoding_controllers.hpp:64
ros::Time
usb_cam_controllers::DecodingController::updateImpl
virtual void updateImpl(const ros::Time &time, const ros::Duration &period)
Definition: decoding_controllers.hpp:68
image_transport::Publisher
usb_cam_controllers::DecodingController::stoppingImpl
virtual void stoppingImpl(const ros::Time &time)
Definition: decoding_controllers.hpp:132
ROS_ERROR
#define ROS_ERROR(...)
sensor_msgs::image_encodings::BGR8
const std::string BGR8
usb_cam_controllers::DecodingController::deleteAVCodecContext
static void deleteAVCodecContext(AVCodecContext *ctx)
Definition: decoding_controllers.hpp:144
usb_cam_controllers::SimplePacketController
Definition: simple_packet_controller.hpp:19
ros::Duration
usb_cam_controllers::DecodingController::DecodingController
DecodingController()
Definition: decoding_controllers.hpp:28
ros::NodeHandle


usb_cam_controllers
Author(s):
autogenerated on Wed Mar 2 2022 01:11:38