in h264_video_encoder/src/h264_video_encoder.cpp [74:109]
void ImageCallback(sensor_msgs::msg::Image::ConstSharedPtr msg, const H264Encoder * encoder,
uint64_t & frame_num, kinesis_video_msgs::msg::KinesisImageMetadata & metadata,
std::shared_ptr<rclcpp::Publisher<kinesis_video_msgs::msg::KinesisVideoFrame>> pub)
{
thread_local H264EncoderResult encoder_output;
AwsError retcode = encoder->Encode(msg->data.data(), encoder_output);
if (retcode != AWS_ERR_OK) {
if (retcode == AWS_ERR_NULL_PARAM) {
AWS_LOG_ERROR(__func__, "Encoder received empty data!");
} else if (retcode == AWS_ERR_FAILURE) {
AWS_LOG_ERROR(__func__, "Unknown encoding error occurred");
} else if (retcode == AWS_ERR_EMPTY) {
AWS_LOG_WARN(__func__, "Encoder returned empty frame");
}
return;
}
kinesis_video_msgs::msg::KinesisVideoFrame frame;
frame.index = frame_num;
frame.flags = (encoder_output.key_frame) ? kKeyFrameFlag : kBPFrameFlag;
frame.decoding_ts = encoder_output.frame_dts;
frame.presentation_ts = encoder_output.frame_pts;
frame.duration = encoder_output.frame_duration / 2; // duration recommended to be set shorter
frame.codec_private_data = encoder->GetExtraData();
frame.frame_data = encoder_output.frame_data;
frame.metadata.swap(metadata.metadata);
pub->publish(frame);
constexpr int kDbgMsgThrottlePeriod = 10; // 10 seconds throttling period
RCUTILS_LOG_DEBUG_THROTTLE("", kDbgMsgThrottlePeriod, "Published Frame #%lu (timestamp: %lu)\n", frame_num,
encoder_output.frame_pts);
++frame_num;
}