Class Decoder
Defined in File decoder.hpp
Class Documentation
-
class Decoder
Decodes ffmpeg encoded messages via libav (ffmpeg).
The Decoder class facilitates decoding of messages that have been encoded with the Encoder class by leveraging libav, the collection of libraries used by ffmpeg. Sample code:
void imageCallback(const sensor_msgs::msg::Image::ConstSharedPtr & img, bool isKeyFrame, const std::string &avPixFmt) { // process decoded image here... } ffmpeg_encoder_decoder::Decoder decoder; ffmpeg_image_transport_msgs::msg::FFMPEGPacket msg; msg.header.frame_id = "frame_id"; msg.width = 640; msg.height = 480; msg.step = 640 * 3; msg.encoding = "hevc"; msg.data.resize(msg.height * msg.step, 0); // not valid data! if (!decoder.isInitialized()) { decoder.initialize(msg.encoding, imageCallback, "hevc_cuvid"); } for (int64_t i = 0; i < 10; i++) { msg.header.stamp = rclcpp::Time(i, RCL_SYSTEM_TIME); if (!decoder.decodePacket( msg.encoding, &msg.data[0], msg.data.size(), msg.pts, msg.header.frame_id, msg.header.stamp)) { throw(std::runtime_error("error decoding packet!")); } } decoder.flush();
Public Types
-
using Callback = std::function<void(const ImageConstPtr &img, bool isKeyFrame, const std::string &avPixFormat)>
callback function signature
- Param img:
pointer to decoded image
- Param isKeyFrame:
true if the decoded image is a keyframe
- Param avPixFormat:
the original libav format of the encoded picture
Public Functions
-
Decoder()
Constructor.
-
~Decoder()
Destructor.
-
inline bool isInitialized() const
Test if decoder is initialized.
- Returns:
true if the decoder is initialized.
-
bool initialize(const std::string &codec, Callback callback, const std::string &decoder)
Initializes the decoder for a given codec and libav decoder.
Initializes the decoder, with multiple decoders to pick from.
- Parameters:
codec – the codec (encoding) from the first packet. Can never change!
callback – the function to call when frame has been decoded.
decoder – the name of the libav decoder to use.
- Returns:
true if initialized successfully.
-
void setOutputMessageEncoding(const std::string &output_encoding)
Sets the ROS output message encoding format.
Sets the ROS output message encoding format. Must be compatible with one of the libav encoding formats, or else exception will be thrown. If not set, the output encoding will default to bgr8.
- Parameters:
output_encoding – defaults to bgr8
- Throws:
std::runtime_error() – if no matching libav pixel format could be found
-
void reset()
Clears all decoder state except for timers, loggers, and other settings.
-
bool decodePacket(const std::string &encoding, const uint8_t *data, size_t size, uint64_t pts, const std::string &frame_id, const rclcpp::Time &stamp)
Decodes encoded packet.
Decodes packet. Decoder must have been initialized beforehand. Calling this function may result in callback with decoded frame.
- Parameters:
encoding – the name of the encoding/codec (typically from msg encoding)
data – pointer to packet data
size – size of packet data
pts – presentation time stamp of data packet
frame_id – ros frame id (from message header)
stamp – ros message header time stamp
- Returns:
true if decoding was successful
-
bool flush()
Flush decoder.
This method can only be called once at the end of the decoding stream. It will force any buffered packets to be delivered as frames. No further packets can be fed to the decoder after calling flush().
- Returns:
true if flush was successful (libav returns EOF)
-
inline void setLogger(rclcpp::Logger logger)
Overrides the default (“Decoder”) logger.
- Parameters:
logger – the logger to override the default (“Decoder”) with.
-
inline void setMeasurePerformance(bool p)
Enables or disables performance measurements. Poorly tested, may be broken.
- Parameters:
p – set to true to enable performance debugging.
-
void printTimers(const std::string &prefix) const
Prints performance timers. Poorly tested, may be broken.
- Parameters:
prefix – for labeling the printout
-
void resetTimers()
resets performance debugging timers. Poorly tested, may be broken.
-
inline void addAVOption(const std::string &key, const std::string &value)
adds AVOption setting to list of options to be applied before opening the encoder
- Parameters:
key – name of AVOption to set, e.g. “preset”
value – value of AVOption e.g. “slow”
Public Static Functions
-
static void findDecoders(const std::string &codec, std::vector<std::string> *hw_decoders, std::vector<std::string> *sw_decoders)
Finds all hardware and software decoders for a given codec.
Finds the name of all hardware and software decoders that match a certain codec (or encoder).
- Parameters:
codec – name of the codec, i.e. h264, hevc etc
hw_decoders – non-null pointer for returning list of hardware decoders
sw_decoders – non-null pointer for returning list of software decoders
-
static std::string findDecoders(const std::string &codec)
Finds all decoders that can decode a given codec.
Finds the name of all hardware and software decoders (combined) that match a certain codec (or encoder).
- Parameters:
codec – name of the codec, i.e. h264, hevc etc
- Returns:
string with comma-separated list of libav decoders
-
static const std::unordered_map<std::string, std::string> &getDefaultEncoderToDecoderMap()
- Deprecated:
Use findDecoders(codec) instead.
-
using Callback = std::function<void(const ImageConstPtr &img, bool isKeyFrame, const std::string &avPixFormat)>