Use doubles instead of api/units for jitter estimation.
For now use doubles as units in api/units have insufficient precision for jitter estimation. Bug: webrtc:14381 Change-Id: I5a691b6a404b734a5bef11d677b72040bc02ff0f Reviewed-on: https://webrtc-review.googlesource.com/c/src/+/272367 Reviewed-by: Rasmus Brandt <brandtr@webrtc.org> Commit-Queue: Philip Eliasson <philipel@webrtc.org> Cr-Commit-Position: refs/heads/main@{#37841}
This commit is contained in:
@ -36,12 +36,12 @@ FrameDelayDeltaKalmanFilter::FrameDelayDeltaKalmanFilter() {
|
||||
}
|
||||
|
||||
void FrameDelayDeltaKalmanFilter::PredictAndUpdate(
|
||||
TimeDelta frame_delay_variation,
|
||||
double frame_delay_variation_ms,
|
||||
double frame_size_variation_bytes,
|
||||
DataSize max_frame_size,
|
||||
double max_frame_size_bytes,
|
||||
double var_noise) {
|
||||
// Sanity checks.
|
||||
if (max_frame_size < DataSize::Bytes(1)) {
|
||||
if (max_frame_size_bytes < 1) {
|
||||
return;
|
||||
}
|
||||
if (var_noise <= 0.0) {
|
||||
@ -65,7 +65,7 @@ void FrameDelayDeltaKalmanFilter::PredictAndUpdate(
|
||||
// This is the part of the measurement that cannot be explained by the current
|
||||
// estimate.
|
||||
double innovation =
|
||||
frame_delay_variation.ms() -
|
||||
frame_delay_variation_ms -
|
||||
GetFrameDelayVariationEstimateTotal(frame_size_variation_bytes);
|
||||
|
||||
// 4) Innovation variance: `s = H*P*H' + r`.
|
||||
@ -76,7 +76,7 @@ void FrameDelayDeltaKalmanFilter::PredictAndUpdate(
|
||||
estimate_cov_[1][0] * frame_size_variation_bytes + estimate_cov_[1][1];
|
||||
double observation_noise_stddev =
|
||||
(300.0 * exp(-fabs(frame_size_variation_bytes) /
|
||||
(1e0 * max_frame_size.bytes())) +
|
||||
(1e0 * max_frame_size_bytes)) +
|
||||
1) *
|
||||
sqrt(var_noise);
|
||||
if (observation_noise_stddev < 1.0) {
|
||||
|
||||
@ -60,21 +60,25 @@ class FrameDelayDeltaKalmanFilter {
|
||||
// and frame size variation.
|
||||
//
|
||||
// Inputs:
|
||||
// `frame_delay_variation`:
|
||||
// `frame_delay_variation_ms`:
|
||||
// Frame delay variation as calculated by the `InterFrameDelay` estimator.
|
||||
//
|
||||
// `frame_size_variation_bytes`:
|
||||
// Frame size variation, i.e., the current frame size minus the previous
|
||||
// frame size (in bytes). Note that this quantity may be negative.
|
||||
//
|
||||
// `max_frame_size`:
|
||||
// `max_frame_size_bytes`:
|
||||
// Filtered largest frame size received since the last reset.
|
||||
//
|
||||
// `var_noise`:
|
||||
// Variance of the estimated random jitter.
|
||||
void PredictAndUpdate(TimeDelta frame_delay_variation,
|
||||
//
|
||||
// TODO(bugs.webrtc.org/14381): For now use doubles as input parameters as
|
||||
// units defined in api/units have insufficient underlying precision for
|
||||
// jitter estimation.
|
||||
void PredictAndUpdate(double frame_delay_variation_ms,
|
||||
double frame_size_variation_bytes,
|
||||
DataSize max_frame_size,
|
||||
double max_frame_size_bytes,
|
||||
double var_noise);
|
||||
|
||||
// Given a frame size variation, returns the estimated frame delay variation
|
||||
|
||||
@ -10,9 +10,6 @@
|
||||
|
||||
#include "modules/video_coding/timing/frame_delay_delta_kalman_filter.h"
|
||||
|
||||
#include "api/units/data_size.h"
|
||||
#include "api/units/frequency.h"
|
||||
#include "api/units/time_delta.h"
|
||||
#include "test/gtest.h"
|
||||
|
||||
namespace webrtc {
|
||||
@ -64,9 +61,9 @@ TEST(FrameDelayDeltaKalmanFilterTest,
|
||||
|
||||
// Negative variance...
|
||||
double var_noise = -0.1;
|
||||
filter.PredictAndUpdate(/*frame_delay_variation=*/TimeDelta::Millis(3),
|
||||
filter.PredictAndUpdate(/*frame_delay_variation_ms=*/3,
|
||||
/*frame_size_variation_bytes=*/200.0,
|
||||
/*max_frame_size=*/DataSize::Bytes(2000), var_noise);
|
||||
/*max_frame_size_bytes=*/2000, var_noise);
|
||||
|
||||
// ...does _not_ update the filter.
|
||||
EXPECT_EQ(filter.GetFrameDelayVariationEstimateTotal(
|
||||
@ -75,9 +72,9 @@ TEST(FrameDelayDeltaKalmanFilterTest,
|
||||
|
||||
// Positive variance...
|
||||
var_noise = 0.1;
|
||||
filter.PredictAndUpdate(/*frame_delay_variation=*/TimeDelta::Millis(3),
|
||||
filter.PredictAndUpdate(/*frame_delay_variation_ms=*/3,
|
||||
/*frame_size_variation_bytes=*/200.0,
|
||||
/*max_frame_size=*/DataSize::Bytes(2000), var_noise);
|
||||
/*max_frame_size_bytes=*/2000, var_noise);
|
||||
|
||||
// ...does update the filter.
|
||||
EXPECT_GT(filter.GetFrameDelayVariationEstimateTotal(
|
||||
@ -92,9 +89,9 @@ TEST(FrameDelayDeltaKalmanFilterTest,
|
||||
// One frame every 33 ms.
|
||||
int framerate_fps = 30;
|
||||
// Let's assume approximately 10% delay variation.
|
||||
TimeDelta frame_delay_variation = TimeDelta::Millis(3);
|
||||
double frame_delay_variation_ms = 3;
|
||||
// With a bitrate of 512 kbps, each frame will be around 2000 bytes.
|
||||
DataSize max_frame_size = DataSize::Bytes(2000);
|
||||
double max_frame_size_bytes = 2000;
|
||||
// And again, let's assume 10% size deviation.
|
||||
double frame_size_variation_bytes = 200;
|
||||
double var_noise = 0.1;
|
||||
@ -103,15 +100,15 @@ TEST(FrameDelayDeltaKalmanFilterTest,
|
||||
for (int i = 0; i < test_duration_s * framerate_fps; ++i) {
|
||||
// For simplicity, assume alternating variations.
|
||||
double sign = (i % 2 == 0) ? 1.0 : -1.0;
|
||||
filter.PredictAndUpdate(sign * frame_delay_variation,
|
||||
sign * frame_size_variation_bytes, max_frame_size,
|
||||
var_noise);
|
||||
filter.PredictAndUpdate(sign * frame_delay_variation_ms,
|
||||
sign * frame_size_variation_bytes,
|
||||
max_frame_size_bytes, var_noise);
|
||||
}
|
||||
|
||||
// Verify that the filter has converged within a margin of 0.1 ms.
|
||||
EXPECT_NEAR(
|
||||
filter.GetFrameDelayVariationEstimateTotal(frame_size_variation_bytes),
|
||||
frame_delay_variation.ms(), 0.1);
|
||||
frame_delay_variation_ms, 0.1);
|
||||
}
|
||||
|
||||
} // namespace
|
||||
|
||||
@ -33,6 +33,7 @@ static constexpr int64_t kFsAccuStartupSamples = 5;
|
||||
static constexpr Frequency kMaxFramerateEstimate = Frequency::Hertz(200);
|
||||
static constexpr TimeDelta kNackCountTimeout = TimeDelta::Seconds(60);
|
||||
static constexpr double kDefaultMaxTimestampDeviationInSigmas = 3.5;
|
||||
static constexpr double kDefaultAvgAndMaxFrameSize = 500;
|
||||
|
||||
constexpr double kPhi = 0.97;
|
||||
constexpr double kPsi = 0.9999;
|
||||
@ -61,8 +62,8 @@ JitterEstimator::~JitterEstimator() = default;
|
||||
void JitterEstimator::Reset() {
|
||||
var_noise_ = 4.0;
|
||||
|
||||
avg_frame_size_ = kDefaultAvgAndMaxFrameSize;
|
||||
max_frame_size_ = kDefaultAvgAndMaxFrameSize;
|
||||
avg_frame_size_bytes_ = kDefaultAvgAndMaxFrameSize;
|
||||
max_frame_size_bytes_ = kDefaultAvgAndMaxFrameSize;
|
||||
var_frame_size_ = 100;
|
||||
last_update_time_ = absl::nullopt;
|
||||
prev_estimate_ = absl::nullopt;
|
||||
@ -72,7 +73,7 @@ void JitterEstimator::Reset() {
|
||||
filter_jitter_estimate_ = TimeDelta::Zero();
|
||||
latest_nack_ = Timestamp::Zero();
|
||||
nack_count_ = 0;
|
||||
frame_size_sum_ = DataSize::Zero();
|
||||
frame_size_sum_bytes_ = 0;
|
||||
frame_size_count_ = 0;
|
||||
startup_count_ = 0;
|
||||
rtt_filter_.Reset();
|
||||
@ -91,27 +92,30 @@ void JitterEstimator::UpdateEstimate(TimeDelta frame_delay,
|
||||
double delta_frame_bytes =
|
||||
frame_size.bytes() - prev_frame_size_.value_or(DataSize::Zero()).bytes();
|
||||
if (frame_size_count_ < kFsAccuStartupSamples) {
|
||||
frame_size_sum_ += frame_size;
|
||||
frame_size_sum_bytes_ += frame_size.bytes();
|
||||
frame_size_count_++;
|
||||
} else if (frame_size_count_ == kFsAccuStartupSamples) {
|
||||
// Give the frame size filter.
|
||||
avg_frame_size_ = frame_size_sum_ / static_cast<double>(frame_size_count_);
|
||||
avg_frame_size_bytes_ =
|
||||
frame_size_sum_bytes_ / static_cast<double>(frame_size_count_);
|
||||
frame_size_count_++;
|
||||
}
|
||||
|
||||
DataSize avg_frame_size = kPhi * avg_frame_size_ + (1 - kPhi) * frame_size;
|
||||
DataSize deviation_size = DataSize::Bytes(2 * sqrt(var_frame_size_));
|
||||
if (frame_size < avg_frame_size_ + deviation_size) {
|
||||
double avg_frame_size_bytes =
|
||||
kPhi * avg_frame_size_bytes_ + (1 - kPhi) * frame_size.bytes();
|
||||
double deviation_size_bytes = 2 * sqrt(var_frame_size_);
|
||||
if (frame_size.bytes() < avg_frame_size_bytes_ + deviation_size_bytes) {
|
||||
// Only update the average frame size if this sample wasn't a key frame.
|
||||
avg_frame_size_ = avg_frame_size;
|
||||
avg_frame_size_bytes_ = avg_frame_size_bytes;
|
||||
}
|
||||
|
||||
double delta_bytes = frame_size.bytes() - avg_frame_size.bytes();
|
||||
double delta_bytes = frame_size.bytes() - avg_frame_size_bytes;
|
||||
var_frame_size_ = std::max(
|
||||
kPhi * var_frame_size_ + (1 - kPhi) * (delta_bytes * delta_bytes), 1.0);
|
||||
|
||||
// Update max_frame_size_ estimate.
|
||||
max_frame_size_ = std::max(kPsi * max_frame_size_, frame_size);
|
||||
// Update max_frame_size_bytes_ estimate.
|
||||
max_frame_size_bytes_ =
|
||||
std::max<double>(kPsi * max_frame_size_bytes_, frame_size.bytes());
|
||||
|
||||
if (!prev_frame_size_) {
|
||||
prev_frame_size_ = frame_size;
|
||||
@ -133,9 +137,8 @@ void JitterEstimator::UpdateEstimate(TimeDelta frame_delay,
|
||||
kalman_filter_.GetFrameDelayVariationEstimateTotal(delta_frame_bytes);
|
||||
|
||||
if (fabs(deviation) < kNumStdDevDelayOutlier * sqrt(var_noise_) ||
|
||||
frame_size.bytes() >
|
||||
avg_frame_size_.bytes() +
|
||||
kNumStdDevFrameSizeOutlier * sqrt(var_frame_size_)) {
|
||||
frame_size.bytes() > avg_frame_size_bytes_ + kNumStdDevFrameSizeOutlier *
|
||||
sqrt(var_frame_size_)) {
|
||||
// Update the variance of the deviation from the line given by the Kalman
|
||||
// filter.
|
||||
EstimateRandomJitter(deviation);
|
||||
@ -145,10 +148,10 @@ void JitterEstimator::UpdateEstimate(TimeDelta frame_delay,
|
||||
// delayed. The next frame is of normal size (delta frame), and thus deltaFS
|
||||
// will be << 0. This removes all frame samples which arrives after a key
|
||||
// frame.
|
||||
if (delta_frame_bytes > -0.25 * max_frame_size_.bytes()) {
|
||||
if (delta_frame_bytes > -0.25 * max_frame_size_bytes_) {
|
||||
// Update the Kalman filter with the new data
|
||||
kalman_filter_.PredictAndUpdate(frame_delay, delta_frame_bytes,
|
||||
max_frame_size_, var_noise_);
|
||||
kalman_filter_.PredictAndUpdate(frame_delay.ms(), delta_frame_bytes,
|
||||
max_frame_size_bytes_, var_noise_);
|
||||
}
|
||||
} else {
|
||||
int nStdDev =
|
||||
@ -230,7 +233,7 @@ double JitterEstimator::NoiseThreshold() const {
|
||||
// Calculates the current jitter estimate from the filtered estimates.
|
||||
TimeDelta JitterEstimator::CalculateEstimate() {
|
||||
double retMs = kalman_filter_.GetFrameDelayVariationEstimateSizeBased(
|
||||
max_frame_size_.bytes() - avg_frame_size_.bytes()) +
|
||||
max_frame_size_bytes_ - avg_frame_size_bytes_) +
|
||||
NoiseThreshold();
|
||||
|
||||
TimeDelta ret = TimeDelta::Millis(retMs);
|
||||
|
||||
@ -92,12 +92,17 @@ class JitterEstimator {
|
||||
// a linear Kalman filter.
|
||||
FrameDelayDeltaKalmanFilter kalman_filter_;
|
||||
|
||||
static constexpr DataSize kDefaultAvgAndMaxFrameSize = DataSize::Bytes(500);
|
||||
DataSize avg_frame_size_ = kDefaultAvgAndMaxFrameSize; // Average frame size
|
||||
// TODO(bugs.webrtc.org/14381): Update `avg_frame_size_bytes_` to DataSize
|
||||
// when api/units have sufficient precision.
|
||||
double avg_frame_size_bytes_; // Average frame size
|
||||
double var_frame_size_; // Frame size variance. Unit is bytes^2.
|
||||
// Largest frame size received (descending with a factor kPsi)
|
||||
DataSize max_frame_size_ = kDefaultAvgAndMaxFrameSize;
|
||||
DataSize frame_size_sum_ = DataSize::Zero();
|
||||
// TODO(bugs.webrtc.org/14381): Update `max_frame_size_bytes_` to DataSize
|
||||
// when api/units have sufficient precision.
|
||||
double max_frame_size_bytes_;
|
||||
// TODO(bugs.webrtc.org/14381): Update `frame_size_sum_bytes_` to DataSize
|
||||
// when api/units have sufficient precision.
|
||||
double frame_size_sum_bytes_;
|
||||
uint32_t frame_size_count_;
|
||||
|
||||
absl::optional<Timestamp> last_update_time_;
|
||||
|
||||
Reference in New Issue
Block a user