Class FrameDecoder
Defined in File frame_decoder.hpp
Class Documentation
-
class FrameDecoder
Public Functions
-
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)
Constructor.
- Parameters:
codec_id – ID of the codec to initialize the video decoder
target_fmt – Pixel format to convert to, if necessary. AV_PIX_FMT_NONE guarantees no conversion.
scale – Scale applied to image dimensions (by multiplication, 0.5 is half size)
hw_device_type – Attempt to use hardware decoding device of this type. AV_HWDEVICE_TYPE_NONE uses software decoding only.
dbg_print – Print info about each decoded frame to stdout
- Throws:
std::invalid_argument – if hw_device_type is not supported
-
virtual ~FrameDecoder()
-
bool decode(const AVPacket &in, sensor_msgs::msg::Image &out)
Decode a compressed image packet into an image message.
Note
This method does not set the header (timestamp, tf frame) of the output image
-
bool decode(const sensor_msgs::msg::CompressedImage &in, sensor_msgs::msg::Image &out)
Convenience wrapper to represent CompressedImage as AVPacket and call decode(const AVPacket &, Image &)
- Parameters:
in – Frame to decode
out – Decoded frame to fill
- Returns:
True if decoding was successful, false otherwise
Protected Functions
-
bool decodeFrame(const AVPacket &packet_in, AVFrame &frame_out)
-
void startSkippingPFrames()
Skip new P-frames until the next I-frame.
This allows the decoder to detect when the video stream has missing I-frames that lead to the gray diff-only frames that x265 produces in an attempt to gracefully continue the stream. For the ROS user, it is probably better to have a stuttering video with only good frames, rather than a smoother one with bad gray decoded images.
Ideally this decoder class would be able to detect the condition directly, but the way it is implemented now, we can detect the bad frames only via av_log messages. The information about this case is not available to the libavcodec user, being only available in HEVC decoder internals, so we would need to use libx265 directly to detect.
Protected Attributes
-
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
-
AVPixelFormat hwPixFmt_ = AV_PIX_FMT_NONE
-
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}
Protected Static Functions
-
static void avLogCallbackWrapper(void *ptr, int level, const char *fmt, va_list vargs)
Pure-C function pointer to intercept libav log messages and direct callbacks to a class instance if necessary. Note: this handles multiple instances of FrameDecoder, but will be disabled if another part of the program also calls av_log_set_callback.
-
static AVPixelFormat getHardwarePixelFormat(AVCodecContext *ctx, const AVPixelFormat *pix_fmts)
Function to help AVCodecContext pick a pixel format that matches hwPixFmt_.
Only used if hardware decoding is enabled.
-
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)