Skip to content
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -79,6 +79,10 @@ nvmpi like so:
'ffmpeg_image_transport.preset': 'll',
'ffmpeg_image_transport.gop_size': 15}]
```
Sometimes the ffmpeg parameters show up under different names. If the above
settings don't work, try the command ``ros2 param dump <name_of_your_node>``
*after* subscribing to the ffmpeg image topic with e.g. ``ros2 topic hz``.
From the output you can see what the correct parameter names are.
## License

This software is issued under the Apache License Version 2.0.
83 changes: 73 additions & 10 deletions include/ffmpeg_encoder_decoder/decoder.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,27 +44,90 @@ class Decoder

Decoder();
~Decoder();
/**
* Test if decoder is initialized.
* @return true if the decoder is initialized.
*/
bool isInitialized() const { return (codecContext_ != NULL); }
// Initialize decoder upon first packet received,
// providing callback to be called when frame is complete.
// You must still call decodePacket(msg) afterward!
bool initialize(const std::string & encoding, Callback callback, const std::string & dec);
// clears all state, but leaves config intact
/**
* Initialize decoder, with multiple decoders to pick from.
* Will pick hardware accelerated decoders first if available.
* If decoders.empty() a default decoder will be chosen (if available).
* @param encoding the encoding from the first packet. Can never change!
* @param callback the function to call when frame has been decoded
* @param decoder the decoder to use. If empty string,
* the decoder will try to find a suitable one based on the encoding
* @return true if successful
*/

bool initialize(const std::string & encoding, Callback callback, const std::string & decoder);
/**
* Initialize decoder with multiple decoders to pick from.
* Will pick hardware accelerated decoders first if available.
* If decoders.empty() a default decoder will be chosen (if available).
* @param encoding the encoding from the first packet. Can never change!
* @param callback the function to call when frame has been decoded
* @param decoders the set of decoders to try sequentially. If empty()
* the decoder will try to find a suitable one based on the encoding
* @return true if successful
*/
bool initialize(
const std::string & encoding, Callback callback, const std::vector<std::string> & decoders);
/**
* Clears all decoder state but not timers, loggers, and other settings.
*/
void reset();
// decode packet (may result in frame callback!)
/**
* Decodes packet. Decoder must have been initialized beforehand. Calling this
* function may result in callback with decoded frame.
* @param encoding the name of the encoding (typically from msg encoding)
* @param data pointer to packet data
* @param size size of packet data
* @param pts presentation time stamp of data packet
* @param frame_id ros frame id (from message header)
* @param stamp ros message header time stamp
*/
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);

/**
* Override default logger
* @param logger the logger to override the default with
*/
void setLogger(rclcpp::Logger logger) { logger_ = logger; }
/**
* deprecated, don't use!
*/
static const std::unordered_map<std::string, std::string> & getDefaultEncoderToDecoderMap();
/**
* Finds the name of hardware and software decoders that match a
* certain encoding (or encoder)
*/
static void findDecoders(
const std::string & encoding, std::vector<std::string> * hw_decoders,
std::vector<std::string> * sw_decoders);
/**
* Finds the name of all hardware and software decoders that match
* a certain encoding (or encoder)
*/
static std::vector<std::string> findDecoders(const std::string & encoding);
/**
* For performance debugging
*/
void setMeasurePerformance(bool p) { measurePerformance_ = p; }
/**
* For performance debugging
*/
void printTimers(const std::string & prefix) const;
/**
* For performance debugging
*/
void resetTimers();
void setLogger(rclcpp::Logger logger) { logger_ = logger; }
static const std::unordered_map<std::string, std::string> & getDefaultEncoderToDecoderMap();

private:
rclcpp::Logger logger_;
bool initDecoder(const std::string & encoding, const std::string & decoder);
bool initSingleDecoder(const std::string & decoder);
bool initDecoder(const std::vector<std::string> & decoders);
// --------------- variables
Callback callback_;
PTSMap ptsToStamp_; // mapping of header
Expand Down
59 changes: 42 additions & 17 deletions include/ffmpeg_encoder_decoder/encoder.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,11 +50,8 @@ class Encoder
Encoder();
~Encoder();
// ------- various encoding settings
void setEncoder(const std::string & n)
{
Lock lock(mutex_);
encoder_ = n;
}
void setEncoder(const std::string & n);

void setProfile(const std::string & p)
{
Lock lock(mutex_);
Expand Down Expand Up @@ -105,6 +102,16 @@ class Encoder
Lock lock(mutex_);
GOPSize_ = g;
}
int getMaxBFrames() const
{
Lock lock(mutex_);
return (maxBFrames_);
}
void setMaxBFrames(int b)
{
Lock lock(mutex_);
maxBFrames_ = b;
}
void setFrameRate(int frames, int second)
{
Lock lock(mutex_);
Expand All @@ -130,8 +137,22 @@ class Encoder
// encode image
void encodeImage(const cv::Mat & img, const Header & header, const rclcpp::Time & t0);
void encodeImage(const Image & msg);
// flush all packets. Need header to generate callback message
/**!
* flush all packets (produces callbacks).
* \param frame_id the frame id that will be presented on callback
*/
void flush(const std::string & frame_id);
/**!
* flush all packets (produces callbacks).
* \deprecated Only header.frame_id is used. Used flush(frame_id) now.
*/
void flush(const Header & header);

/**!
* finds the encoding for a given encoder, i.e. returns h264 for h264_vaapi
*/
static std::string findEncoding(const std::string & encoder);

// ------- performance statistics
void printTimers(const std::string & prefix) const;
void resetTimers();
Expand All @@ -142,27 +163,31 @@ class Encoder
bool openCodec(int width, int height);
void doOpenCodec(int width, int height);
void closeCodec();
int drainPacket(const Header & hdr, int width, int height);
int drainPacket(const std::string & frame_id, int width, int height);
AVPixelFormat pixelFormat(const std::string & f) const;
void openVAAPIDevice(const AVCodec * codec, int width, int height);
void openHardwareDevice(
const AVCodec * codec, enum AVHWDeviceType hwDevType, int width, int height);
void setAVOption(const std::string & field, const std::string & value);
// --------- variables
rclcpp::Logger logger_;
mutable std::recursive_mutex mutex_;
Callback callback_;
// config
std::string encoder_; // e.g. "libx264"
std::string preset_; // e.g. "slow", "medium", "lossless"
std::string profile_; // e.g. "main", "high", "rext"
std::string tune_; // e.g. "tune"
std::string delay_; // default is 4 frames for parallel processing. 0 is lowest latency
std::string crf_; // constant rate factor. 0 is lossless, 51 is worst quality
int qmax_{0}; // max allowed quantization. The lower the better quality
int GOPSize_{15}; // distance between two keyframes
std::string encoder_; // e.g. "libx264"
std::string encoding_; // e.g. "h264"
std::string preset_; // e.g. "slow", "medium", "lossless"
std::string profile_; // e.g. "main", "high", "rext"
std::string tune_; // e.g. "tune"
std::string delay_; // default is 4 frames for parallel processing. 0 is lowest latency
std::string crf_; // constant rate factor. 0 is lossless, 51 is worst quality
int qmax_{-1}; // max allowed quantization. The lower the better quality
int GOPSize_{-1}; // distance between two keyframes
int maxBFrames_{-1}; // maximum number of b-frames
int64_t bitRate_{0}; // max rate in bits/s

AVPixelFormat pixFormat_{AV_PIX_FMT_NONE};
AVRational timeBase_{1, 100};
AVRational frameRate_{100, 1};
int64_t bitRate_{1000000};
bool usesHardwareFrames_{false};
// ------ libav state
AVCodecContext * codecContext_{nullptr};
Expand Down
25 changes: 24 additions & 1 deletion include/ffmpeg_encoder_decoder/utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#ifndef FFMPEG_ENCODER_DECODER__UTILS_HPP_
#define FFMPEG_ENCODER_DECODER__UTILS_HPP_

#include <map>
#include <opencv2/core.hpp>
#include <string>
#include <vector>
Expand Down Expand Up @@ -62,7 +63,29 @@ std::vector<enum AVPixelFormat> get_encoder_formats(
* picks from a vector of formats the "best" pixel format for a given encoder
*/
enum AVPixelFormat get_preferred_pixel_format(
const std::string & encoder, const std::vector<AVPixelFormat> & fmts);
bool useHWFormat, const std::vector<AVPixelFormat> & fmts);

/**!
* finds the names of all available decoders for a given encoding (or encoder)
*/
void find_decoders(
const std::string & encoding, std::vector<std::string> * hw_decoders,
std::vector<std::string> * sw_decoders);

/**!
* * get hardware device types
*/
std::vector<std::string> get_hwdevice_types();

/**!
* find encoding for given encoder
*/
std::string find_encoding(const std::string & encoder);

/**!
* gets hardware device type for specific codec
*/
enum AVHWDeviceType find_hw_device_type(const AVCodec * codec);

} // namespace utils
} // namespace ffmpeg_encoder_decoder
Expand Down
Loading