Program Listing for File frame_decoder.hpp

Return to documentation for file (include/broll/frame_decoder.hpp)

// Copyright 2023 Bonsai Robotics, Inc - All Rights Reserved
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
//     http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef BROLL__FRAME_DECODER_HPP_
#define BROLL__FRAME_DECODER_HPP_

extern "C" {
#include <libavcodec/avcodec.h>
#include <libavformat/avformat.h>
#include <libavutil/pixdesc.h>
#include <libswscale/swscale.h>
}

#include <atomic>

#include "sensor_msgs/msg/compressed_image.hpp"
#include "sensor_msgs/msg/image.hpp"

namespace broll
{

class FrameDecoder
{
public:
  FrameDecoder(
    AVCodecID codec_id,
    AVPixelFormat target_fmt = AV_PIX_FMT_NONE,
    double scale = 1.0f,
    AVHWDeviceType hw_device_type = AV_HWDEVICE_TYPE_NONE,
    bool dbg_print = false);
  virtual ~FrameDecoder();

  bool decode(const AVPacket & in, sensor_msgs::msg::Image & out);

  bool decode(const sensor_msgs::msg::CompressedImage & in, sensor_msgs::msg::Image & out);

protected:
  bool decodeFrame(const AVPacket & packet_in, AVFrame & frame_out);

  static void avLogCallbackWrapper(void * ptr, int level, const char * fmt, va_list vargs);

  void startSkippingPFrames();

  static AVPixelFormat getHardwarePixelFormat(AVCodecContext * ctx, const AVPixelFormat * pix_fmts);

  AVPacket * packet_ = nullptr;
  const AVCodec * codec_ = nullptr;
  AVCodecContext * codecCtx_ = nullptr;
  AVPixelFormat targetPixFmt_ = AV_PIX_FMT_NONE;
  SwsContext * swsCtx_ = nullptr;
  AVFrame * decodedFrame_ = nullptr;
  AVFrame * convertedFrame_ = nullptr;

  // Hardware decoding extras
  // Pixel format reported for an on-hardware DMA frame, such as "cuda", which isn't
  // a real pixel format but how the frame reports that it isn't in CPU memory.
  AVPixelFormat hwPixFmt_ = AV_PIX_FMT_NONE;
  // Pixel format to convert to when transferring the frame from hardware into CPU memory.
  // Hardware devices offer several options, but not all that we might want so this
  // is the pre-conversion format before sws.
  AVPixelFormat hwSoftwarePixFmt_ = AV_PIX_FMT_NONE;
  AVBufferRef * hwDeviceCtx_ = nullptr;
  AVFrame * hwFrame_ = nullptr;

  float scale_ = 1.0f;
  uint scaled_width_ = 0u;
  uint scaled_height_ = 0u;
  uint consecutive_receive_failures_ = 0;
  bool dbg_print_ = false;

  std::atomic<bool> skip_pframes_{false};
  std::atomic<uint> skipped_pframes_{0};
};

}  // namespace broll

#endif  // BROLL__FRAME_DECODER_HPP_