Class Encoder
Defined in File encoder.hpp
Class Documentation
-
class Encoder
Encodes ROS image messages via libav (ffmpeg).
The Encoder class facilitates encoding of ROS images by leveraging libav, the collection of libraries used by ffmpeg. Sample code:
// handle the encoded packet in this function void packetReady( const std::string & frame_id, const rclcpp::Time & stamp, const std::string & codec, uint32_t width, uint32_t height, uint64_t pts, uint8_t flags, uint8_t * data, size_t sz) { // do something useful here ... } ffmpeg_encoder_decoder::Encoder enc; enc.setEncoder("libx265"); // set libav encoder // note: will not be lossless unless we happen to have right pixel format enc.setAVOption("x265-params", "lossless=1"); enc.setAVOption("crf", "0"); sensor_msgs::msg::Image image; image.encoding = "bgr8"; image.width = image_width; image.height = image_height; image.step = image.width * 3; // 3 bytes per pixel image.header.frame_id = "frame_id"; image.is_bigendian = false; if (!enc.initialize(image.width, image.height, callback_fn, image.encoding)) { std::cerr << "failed to initialize encoder!" << std::endl; exit (-1); } for (int64_t i = 0; i < numFrames; i++) { image.header.stamp = rclcpp::Time(i + 1, RCL_SYSTEM_TIME); image.data.resize(image.step * image.height, static_cast<uint8_t>(i)); enc.encodeImage(image); // may produce callback } enc.flush(); // may produce callback }
Public Types
-
using Callback = std::function<void(const std::string &frame_id, const rclcpp::Time &stamp, const std::string &codec, uint32_t width, uint32_t height, uint64_t pts, uint8_t flags, uint8_t *data, size_t sz)>
defines callback function signature.
The encoder will call this function when an encoded packet is ready.
- Param frame_id:
the frame_id of the message that produced the packet
- Param stamp:
the ROS time stamp of the message that produced the packet
- Param codec:
the codec used for compression: h264, hevc
- Param width:
image width
- Param height:
image height
- Param pts:
libav presentation time stamp (pts)
- Param data:
pointer to encoded packet
- Param sz:
size of encoded packet
Public Functions
-
Encoder()
Constructor. Doesn’t open codec or do anything else dangerous.
-
~Encoder()
Destructor. Clears all state and frees all memory.
-
void setEncoder(const std::string &encoder_name)
sets the name of libav encoder to be used
- Parameters:
encoder – name of the libav encoder, e.g. libx264, hevc_nvenc etc
-
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”
-
inline void setAVSourcePixelFormat(const std::string &fmt)
This is the format of the image that will be fed into the encoder. In the README, this is referred to as av_source_pixel_format.
If your ROS message format (cv_bridge_target_format) is different, the image will first be converted to the format you set here. Must be set before calling initialize(), or else the encoder will try to pick some suitable format. See README for more details about formats.
- Parameters:
fmt – The pixel format in libav naming convention, e.g. “yuv420p”
-
inline void setCVBridgeTargetFormat(const std::string &fmt)
Set cv_bridge_target_format for first image conversion.
Sets the target format of the first image conversion done via cv_bridge (cv_bridge_target_format). See explanation in the README file. Must be set before calling initialize(), or else it will default to “bgr8”. The cv_bridge_target_format must be compatible with some AV_PIX_FMT* type, or else an exception will be thrown when calling initialize().
- Parameters:
fmt – cv_bridge_target_format (see ROS image_encodings.hpp header)
-
inline void setQMax(int q)
Sets q_max parameter. See ffmpeg docs for explanation.
- Parameters:
q – q_max parameter
-
inline void setBitRate(int bitrate)
Sets bitrate parameter. See ffmpeg docs for explanation.
- Parameters:
bitrate – bitrate parameter (in bits/s)
-
inline int getBitRate() const
gets current bitrate parameter.
- Returns:
the bitrate in bits/sec
-
inline void setGOPSize(int g)
Sets gop size (max distance between keyframes). See ffmpeg docs.
- Parameters:
gop_size – max distance between keyframes
-
inline int getGOPSize() const
gets current gop size.
- Returns:
the gop_size (max distance between keyframes)
-
inline void setMaxBFrames(int b)
sets maximum number of b-frames. See ffmpeg docs.
- Parameters:
b – max number of b-frames.
-
inline int getMaxBFrames() const
gets maximum number of b-frames. See ffmpeg docs.
- Returns:
max number of b-frames.
-
inline void setFrameRate(int frames, int second)
Sets encoding frame rate as a rational number.
Not sure what it really does.
- Parameters:
frames – the number of frames during the interval
second – the time interval (integer seconds)
-
inline void setMeasurePerformance(bool p)
enables or disables performance measurements. Poorly tested, hardly used.
- Parameters:
p – true enables performance statistics
-
inline bool isInitialized() const
test if encoder is initialized
- Returns:
true if encoder is initialized
-
bool initialize(int width, int height, Callback callback, const std::string &encoding = std::string())
initializes encoder.
- Parameters:
width – image width
height – image height
callback – the function to call for handling encoded packets
encoding – the ros encoding string, e.g. bayer_rggb8, rgb8 …
-
inline void setLogger(rclcpp::Logger logger)
sets ROS logger to use for info/error messages
- Parameters:
logger – the logger to use for messages
-
void reset()
completely resets the state of the encoder.
-
void flush()
flush all packets (produces callbacks).
-
void printTimers(const std::string &prefix) const
-
void resetTimers()
-
inline void setProfile(const std::string &p)
- Deprecated:
use addAVOption(“profile”, “value”) now.
-
inline void setPreset(const std::string &p)
- Deprecated:
use addAVOption(“preset”, “value”) now.
-
inline void setTune(const std::string &p)
- Deprecated:
use addAVOption(“tune”, “value”) now.
-
inline void setDelay(const std::string &p)
- Deprecated:
use addAVOption(“delay”, “value”) now.
-
inline void setCRF(const std::string &c)
- Deprecated:
use addAVOption(“crf”, “value”) now.
-
inline void setPixelFormat(const std::string &fmt)
-
void encodeImage(const cv::Mat &img, const Header &header, const rclcpp::Time &t0)
- Deprecated:
use encodeImage(const Image &msg) instead.
-
void flush(const Header &header)
flush all packets (produces callbacks).
- Deprecated:
Only header.frame_id is used. Used flush(frame_id) now.
Public Static Functions
-
static std::string findCodec(const std::string &encoder)
finds the codec for a given encoder, i.e. returns h264 for h264_vaapi
- Parameters:
encoder – name of libav encoder
- Returns:
codec (libav naming convention)
-
using Callback = std::function<void(const std::string &frame_id, const rclcpp::Time &stamp, const std::string &codec, uint32_t width, uint32_t height, uint64_t pts, uint8_t flags, uint8_t *data, size_t sz)>