Refactor class SendSideBandwidthEstimation
The goal is to make states more clear and be able to log where a certain decision come from.
In this cl:
- loss bases BWE handling moved to separate files
- remove field trial WebRTC-Bwe-ReceiverLimitCapsOnly
Bug: webrtc:423841921, webrtc:42222445
Change-Id: I502bee094e18606f8a188214fafa421a868023ca
Reviewed-on: https://webrtc-review.googlesource.com/c/src/+/396342
Reviewed-by: Diep Bui <diepbp@webrtc.org>
Commit-Queue: Per Kjellander <perkj@webrtc.org>
Cr-Commit-Position: refs/heads/main@{#45056}
diff --git a/experiments/field_trials.py b/experiments/field_trials.py
index dc1e127..bb50746 100755
--- a/experiments/field_trials.py
+++ b/experiments/field_trials.py
@@ -583,9 +583,6 @@
FieldTrial('WebRTC-Bwe-ReceiveTimeFix',
42234228,
date(2024, 4, 1)),
- FieldTrial('WebRTC-Bwe-ReceiverLimitCapsOnly',
- 42222445,
- date(2024, 4, 1)),
FieldTrial('WebRTC-Bwe-RobustThroughputEstimatorSettings',
42220312,
date(2024, 4, 1)),
@@ -905,7 +902,7 @@
]) # yapf: disable
POLICY_EXEMPT_FIELD_TRIALS_DIGEST: str = \
- '625f8d689ab8bcfe4118347c6f8c852e3ac372c7'
+ 'cf604f3ec3a4fa7cf0857f8e1f9201366abe2e5f'
REGISTERED_FIELD_TRIALS: FrozenSet[FieldTrial] = ACTIVE_FIELD_TRIALS.union(
POLICY_EXEMPT_FIELD_TRIALS)
diff --git a/modules/congestion_controller/goog_cc/BUILD.gn b/modules/congestion_controller/goog_cc/BUILD.gn
index e1cd1c4..9b0660c 100644
--- a/modules/congestion_controller/goog_cc/BUILD.gn
+++ b/modules/congestion_controller/goog_cc/BUILD.gn
@@ -142,6 +142,27 @@
"//third_party/abseil-cpp/absl/algorithm:container",
]
}
+rtc_library("loss_based_bwe") {
+ sources = [
+ "loss_based_bwe.cc",
+ "loss_based_bwe.h",
+ ]
+ deps = [
+ ":loss_based_bwe_v2",
+ "../../../api:array_view",
+ "../../../api:field_trials_view",
+ "../../../api/transport:network_control",
+ "../../../api/units:data_rate",
+ "../../../api/units:data_size",
+ "../../../api/units:time_delta",
+ "../../../api/units:timestamp",
+ "../../../rtc_base:checks",
+ "../../../rtc_base:logging",
+ "../../../rtc_base/experiments:field_trial_parser",
+ "../../remote_bitrate_estimator",
+ "//third_party/abseil-cpp/absl/algorithm:container",
+ ]
+}
rtc_library("send_side_bwe") {
sources = [
@@ -149,6 +170,7 @@
"send_side_bandwidth_estimation.h",
]
deps = [
+ ":loss_based_bwe",
":loss_based_bwe_v2",
"../../../api:field_trials_view",
"../../../api/rtc_event_log",
@@ -263,6 +285,7 @@
"delay_based_bwe_unittest_helper.cc",
"delay_based_bwe_unittest_helper.h",
"goog_cc_network_control_unittest.cc",
+ "loss_based_bwe_unittest.cc",
"loss_based_bwe_v2_test.cc",
"probe_bitrate_estimator_unittest.cc",
"probe_controller_unittest.cc",
@@ -275,6 +298,7 @@
":delay_based_bwe",
":estimators",
":goog_cc",
+ ":loss_based_bwe",
":loss_based_bwe_v2",
":probe_controller",
":pushback_controller",
diff --git a/modules/congestion_controller/goog_cc/goog_cc_network_control.cc b/modules/congestion_controller/goog_cc/goog_cc_network_control.cc
index 45dda7b..2a64b31 100644
--- a/modules/congestion_controller/goog_cc/goog_cc_network_control.cc
+++ b/modules/congestion_controller/goog_cc/goog_cc_network_control.cc
@@ -220,7 +220,7 @@
congestion_window_pushback_controller_->UpdatePacingQueue(
msg.pacer_queue->bytes());
}
- bandwidth_estimation_->UpdateEstimate(msg.at_time);
+ bandwidth_estimation_->OnPeriodicUpdate(msg.at_time);
std::optional<int64_t> start_time_ms =
alr_detector_->GetApplicationLimitedRegionStartTime();
probe_controller_->SetAlrStartTimeMs(start_time_ms);
@@ -380,10 +380,8 @@
NetworkControlUpdate GoogCcNetworkController::OnTransportLossReport(
TransportLossReport msg) {
- int64_t total_packets_delta =
- msg.packets_received_delta + msg.packets_lost_delta;
bandwidth_estimation_->UpdatePacketsLost(
- msg.packets_lost_delta, total_packets_delta, msg.receive_time);
+ msg.packets_lost_delta, msg.packets_received_delta, msg.receive_time);
return NetworkControlUpdate();
}
@@ -454,11 +452,7 @@
probe_controller_->SetAlrEndedTimeMs(now_ms);
}
previously_in_alr_ = alr_start_time.has_value();
- acknowledged_bitrate_estimator_->IncomingPacketFeedbackVector(
- report.SortedByReceiveTime());
- auto acknowledged_bitrate = acknowledged_bitrate_estimator_->bitrate();
- bandwidth_estimation_->SetAcknowledgedRate(acknowledged_bitrate,
- report.feedback_time);
+
for (const auto& feedback : report.SortedByReceiveTime()) {
if (feedback.sent_packet.pacing_info.probe_cluster_id !=
PacedPacketInfo::kNotAProbe) {
@@ -477,6 +471,9 @@
*probe_bitrate < estimate_->link_capacity_lower) {
probe_bitrate.reset();
}
+ acknowledged_bitrate_estimator_->IncomingPacketFeedbackVector(
+ report.SortedByReceiveTime());
+ auto acknowledged_bitrate = acknowledged_bitrate_estimator_->bitrate();
if (limit_probes_lower_than_throughput_estimate_ && probe_bitrate &&
acknowledged_bitrate) {
// Limit the backoff to something slightly below the acknowledged
@@ -500,19 +497,9 @@
report, acknowledged_bitrate, probe_bitrate, estimate_,
alr_start_time.has_value());
- if (result.updated) {
- if (result.probe) {
- bandwidth_estimation_->SetSendBitrate(result.target_bitrate,
- report.feedback_time);
- }
- // Since SetSendBitrate now resets the delay-based estimate, we have to
- // call UpdateDelayBasedEstimate after SetSendBitrate.
- bandwidth_estimation_->UpdateDelayBasedEstimate(report.feedback_time,
- result.target_bitrate);
- }
- bandwidth_estimation_->UpdateLossBasedEstimator(
- report, result.delay_detector_state, probe_bitrate,
- alr_start_time.has_value());
+ bandwidth_estimation_->OnTransportPacketsFeedback(
+ report, delay_based_bwe_->last_estimate(), acknowledged_bitrate,
+ /*is_probe_rate=*/result.probe, alr_start_time.has_value());
if (result.updated) {
// Update the estimate in the ProbeController, in case we want to probe.
MaybeTriggerOnNetworkChanged(&update, report.feedback_time);
diff --git a/modules/congestion_controller/goog_cc/loss_based_bwe.cc b/modules/congestion_controller/goog_cc/loss_based_bwe.cc
new file mode 100644
index 0000000..ed40fc7
--- /dev/null
+++ b/modules/congestion_controller/goog_cc/loss_based_bwe.cc
@@ -0,0 +1,293 @@
+/*
+ * Copyright (c) 2025 The WebRTC project authors. All Rights Reserved.
+ *
+ * Use of this source code is governed by a BSD-style license
+ * that can be found in the LICENSE file in the root of the source
+ * tree. An additional intellectual property rights grant can be found
+ * in the file PATENTS. All contributing project authors may
+ * be found in the AUTHORS file in the root of the source tree.
+ */
+
+#include "modules/congestion_controller/goog_cc/loss_based_bwe.h"
+
+#include <algorithm>
+#include <cstdint>
+#include <cstdio>
+#include <limits>
+#include <memory>
+#include <optional>
+#include <string>
+#include <utility>
+
+#include "api/field_trials_view.h"
+#include "api/transport/network_types.h"
+#include "api/units/data_rate.h"
+#include "api/units/time_delta.h"
+#include "api/units/timestamp.h"
+#include "modules/congestion_controller/goog_cc/loss_based_bwe_v2.h"
+#include "rtc_base/checks.h"
+#include "rtc_base/logging.h"
+
+namespace webrtc {
+
+namespace {
+
+constexpr float kDefaultLowLossThreshold = 0.02f;
+constexpr float kDefaultHighLossThreshold = 0.1f;
+constexpr DataRate kDefaultBitrateThreshold = DataRate::Zero();
+constexpr TimeDelta kBweIncreaseInterval = TimeDelta::Millis(1000);
+constexpr TimeDelta kBweDecreaseInterval = TimeDelta::Millis(300);
+constexpr TimeDelta kMaxRtcpFeedbackInterval = TimeDelta::Millis(5000);
+constexpr int kLimitNumPackets = 20;
+
+const char kBweLosExperiment[] = "WebRTC-BweLossExperiment";
+
+bool BweLossExperimentIsEnabled(const FieldTrialsView& field_trials) {
+ return field_trials.IsEnabled(kBweLosExperiment);
+}
+
+bool ReadBweLossExperimentParameters(const FieldTrialsView& field_trials,
+ float* low_loss_threshold,
+ float* high_loss_threshold,
+ uint32_t* bitrate_threshold_kbps) {
+ RTC_DCHECK(low_loss_threshold);
+ RTC_DCHECK(high_loss_threshold);
+ RTC_DCHECK(bitrate_threshold_kbps);
+ std::string experiment_string = field_trials.Lookup(kBweLosExperiment);
+ int parsed_values =
+ sscanf(experiment_string.c_str(), "Enabled-%f,%f,%u", low_loss_threshold,
+ high_loss_threshold, bitrate_threshold_kbps);
+ if (parsed_values == 3) {
+ RTC_CHECK_GT(*low_loss_threshold, 0.0f)
+ << "Loss threshold must be greater than 0.";
+ RTC_CHECK_LE(*low_loss_threshold, 1.0f)
+ << "Loss threshold must be less than or equal to 1.";
+ RTC_CHECK_GT(*high_loss_threshold, 0.0f)
+ << "Loss threshold must be greater than 0.";
+ RTC_CHECK_LE(*high_loss_threshold, 1.0f)
+ << "Loss threshold must be less than or equal to 1.";
+ RTC_CHECK_LE(*low_loss_threshold, *high_loss_threshold)
+ << "The low loss threshold must be less than or equal to the high loss "
+ "threshold.";
+ RTC_CHECK_GE(*bitrate_threshold_kbps, 0)
+ << "Bitrate threshold can't be negative.";
+ RTC_CHECK_LT(*bitrate_threshold_kbps,
+ std::numeric_limits<int>::max() / 1000)
+ << "Bitrate must be smaller enough to avoid overflows.";
+ return true;
+ }
+ RTC_LOG(LS_WARNING) << "Failed to parse parameters for BweLossExperiment "
+ "experiment from field trial string. Using default.";
+ *low_loss_threshold = kDefaultLowLossThreshold;
+ *high_loss_threshold = kDefaultHighLossThreshold;
+ *bitrate_threshold_kbps = kDefaultBitrateThreshold.kbps();
+ return false;
+}
+} // namespace
+
+LossBasedBwe::LossBasedBwe(const FieldTrialsView* field_trials)
+ : field_trials_(field_trials),
+ loss_based_bwe_v2_(std::make_unique<LossBasedBweV2>(field_trials)),
+ low_loss_threshold_(kDefaultLowLossThreshold),
+ high_loss_threshold_(kDefaultHighLossThreshold),
+ bitrate_threshold_(kDefaultBitrateThreshold) {
+ if (BweLossExperimentIsEnabled(*field_trials)) {
+ uint32_t bitrate_threshold_kbps;
+ if (ReadBweLossExperimentParameters(*field_trials, &low_loss_threshold_,
+ &high_loss_threshold_,
+ &bitrate_threshold_kbps)) {
+ RTC_LOG(LS_INFO) << "Enabled BweLossExperiment with parameters "
+ << low_loss_threshold_ << ", " << high_loss_threshold_
+ << ", " << bitrate_threshold_kbps;
+ bitrate_threshold_ = DataRate::KilobitsPerSec(bitrate_threshold_kbps);
+ }
+ }
+}
+
+void LossBasedBwe::OnTransportPacketsFeedback(
+ const TransportPacketsFeedback& report,
+ DataRate delay_based,
+ std::optional<DataRate> acknowledged_bitrate,
+ bool is_probe_rate,
+ bool in_alr) {
+ if (is_probe_rate) {
+ // delay_based bitrate overrides loss based BWE unless
+ // loss_based_bandwidth_estimator_v2_ is used or until
+ // loss_based_bandwidth_estimator_v2_ is ready.
+ SetStartRate(delay_based);
+ }
+ delay_based_bwe_ = delay_based;
+ if (!loss_based_bwe_v2_->IsEnabled()) {
+ return;
+ }
+ if (acknowledged_bitrate.has_value()) {
+ loss_based_bwe_v2_->SetAcknowledgedBitrate(*acknowledged_bitrate);
+ }
+ loss_based_bwe_v2_->UpdateBandwidthEstimate(report.packet_feedbacks,
+ delay_based, in_alr);
+}
+
+void LossBasedBwe::OnRouteChanged() {
+ current_state_ = LossBasedState::kDelayBasedEstimate;
+ lost_packets_since_last_loss_update_ = 0;
+ expected_packets_since_last_loss_update_ = 0;
+ min_bitrate_history_.clear();
+ delay_based_bwe_ = DataRate::PlusInfinity();
+ fallback_estimate_ = DataRate::Zero();
+ has_decreased_since_last_fraction_loss_ = false;
+ last_loss_feedback_ = Timestamp::MinusInfinity();
+ last_loss_packet_report_ = Timestamp::MinusInfinity();
+ last_fraction_loss_ = 0;
+ last_logged_fraction_loss_ = 0;
+ last_round_trip_time_ = TimeDelta::Zero();
+ time_last_decrease_ = Timestamp::MinusInfinity();
+ first_report_time_ = Timestamp::MinusInfinity();
+ loss_based_bwe_v2_ = std::make_unique<LossBasedBweV2>(field_trials_);
+}
+
+void LossBasedBwe::SetConfiguredMinMaxBitrate(DataRate min_rate,
+ DataRate max_rate) {
+ configured_min_rate_ = min_rate;
+ configured_max_rate_ = max_rate;
+ loss_based_bwe_v2_->SetMinMaxBitrate(min_rate, max_rate);
+}
+
+void LossBasedBwe::SetStartRate(DataRate fallback_rate) {
+ // Clear last sent bitrate history so the new value can be used directly
+ // and not capped.
+ min_bitrate_history_.clear();
+ fallback_estimate_ = fallback_rate;
+}
+
+void LossBasedBwe::OnPacketLossReport(int64_t packets_lost,
+ int64_t packets_received,
+ TimeDelta round_trip_time,
+ Timestamp at_time) {
+ last_loss_feedback_ = at_time;
+ last_round_trip_time_ = round_trip_time;
+ if (first_report_time_.IsInfinite()) {
+ first_report_time_ = at_time;
+ }
+ int64_t number_of_packets = packets_lost + packets_received;
+ // Check sequence number diff and weight loss report
+ if (number_of_packets <= 0) {
+ return;
+ }
+ int64_t expected =
+ expected_packets_since_last_loss_update_ + number_of_packets;
+
+ // Don't generate a loss rate until it can be based on enough packets.
+ if (expected < kLimitNumPackets) {
+ // Accumulate reports.
+ expected_packets_since_last_loss_update_ = expected;
+ lost_packets_since_last_loss_update_ += packets_lost;
+ return;
+ }
+
+ has_decreased_since_last_fraction_loss_ = false;
+ int64_t lost_q8 =
+ std::max<int64_t>(lost_packets_since_last_loss_update_ + packets_lost, 0)
+ << 8;
+ last_fraction_loss_ = std::min<int>(lost_q8 / expected, 255);
+
+ // Reset accumulators.
+ lost_packets_since_last_loss_update_ = 0;
+ expected_packets_since_last_loss_update_ = 0;
+ last_loss_packet_report_ = at_time;
+}
+
+bool LossBasedBwe::OnPeriodicProcess(Timestamp at_time) {
+ UpdateMinHistory(at_time);
+ if (loss_based_bwe_v2_->IsReady()) {
+ return false;
+ }
+
+ TimeDelta time_since_loss_packet_report = at_time - last_loss_packet_report_;
+ if (time_since_loss_packet_report < 1.2 * kMaxRtcpFeedbackInterval) {
+ // We only care about loss above a given bitrate threshold.
+ float loss = last_fraction_loss_ / 256.0f;
+ // We only make decisions based on loss when the bitrate is above a
+ // threshold. This is a crude way of handling loss which is uncorrelated
+ // to congestion.
+ if (fallback_estimate_ < bitrate_threshold_ ||
+ loss <= low_loss_threshold_) {
+ // Loss < 2%: Increase rate by 8% of the min bitrate in the last
+ // kBweIncreaseInterval.
+ // Note that by remembering the bitrate over the last second one can
+ // rampup up one second faster than if only allowed to start ramping
+ // at 8% per second rate now. E.g.:
+ // If sending a constant 100kbps it can rampup immediately to 108kbps
+ // whenever a receiver report is received with lower packet loss.
+ // If instead one would do: current_bitrate_ *= 1.08^(delta time),
+ // it would take over one second since the lower packet loss to
+ // achieve 108kbps.
+ // Add 1 kbps extra, just to make sure that we do not get stuck
+ // (gives a little extra increase at low rates, negligible at higher
+ // rates).
+ UpdateFallbackEstimate(
+ DataRate::BitsPerSec(
+ min_bitrate_history_.front().second.bps() * 1.08 + 0.5) +
+ DataRate::BitsPerSec(1000));
+ return true;
+ } else if (fallback_estimate_ > bitrate_threshold_) {
+ if (loss <= high_loss_threshold_) {
+ // Loss between 2% - 10%: Do nothing.
+ } else {
+ // Loss > 10%: Limit the rate decreases to once a kBweDecreaseInterval
+ // + rtt.
+ if (!has_decreased_since_last_fraction_loss_ &&
+ (at_time - time_last_decrease_) >=
+ (kBweDecreaseInterval + last_round_trip_time_)) {
+ time_last_decrease_ = at_time;
+
+ // Reduce rate:
+ // newRate = rate * (1 - 0.5*lossRate);
+ // where packetLoss = 256*lossRate;
+ UpdateFallbackEstimate(DataRate::BitsPerSec(
+ (fallback_estimate_.bps() *
+ static_cast<double>(512 - last_fraction_loss_)) /
+ 512.0));
+ has_decreased_since_last_fraction_loss_ = true;
+ return true;
+ }
+ }
+ }
+ }
+ return false;
+}
+
+void LossBasedBwe::UpdateMinHistory(Timestamp at_time) {
+ // Remove old data points from history.
+ // Since history precision is in ms, add one so it is able to increase
+ // bitrate if it is off by as little as 0.5ms.
+ while (!min_bitrate_history_.empty() &&
+ at_time - min_bitrate_history_.front().first + TimeDelta::Millis(1) >
+ kBweIncreaseInterval) {
+ min_bitrate_history_.pop_front();
+ }
+
+ // Typical minimum sliding-window algorithm: Pop values higher than current
+ // bitrate before pushing it.
+ while (!min_bitrate_history_.empty() &&
+ fallback_estimate_ <= min_bitrate_history_.back().second) {
+ min_bitrate_history_.pop_back();
+ }
+
+ min_bitrate_history_.push_back(std::make_pair(at_time, fallback_estimate_));
+}
+
+DataRate LossBasedBwe::GetEstimate() {
+ if (loss_based_bwe_v2_->IsReady()) {
+ LossBasedBweV2::Result result = loss_based_bwe_v2_->GetLossBasedResult();
+ current_state_ = result.state;
+ return result.bandwidth_estimate;
+ }
+ return fallback_estimate_;
+}
+
+void LossBasedBwe::UpdateFallbackEstimate(DataRate new_estimate) {
+ fallback_estimate_ = std::min({delay_based_bwe_, new_estimate});
+ fallback_estimate_ = std::max(configured_min_rate_, new_estimate);
+}
+
+} // namespace webrtc
diff --git a/modules/congestion_controller/goog_cc/loss_based_bwe.h b/modules/congestion_controller/goog_cc/loss_based_bwe.h
new file mode 100644
index 0000000..b2ff8f4
--- /dev/null
+++ b/modules/congestion_controller/goog_cc/loss_based_bwe.h
@@ -0,0 +1,107 @@
+/*
+ * Copyright (c) 2025 The WebRTC project authors. All Rights Reserved.
+ *
+ * Use of this source code is governed by a BSD-style license
+ * that can be found in the LICENSE file in the root of the source
+ * tree. An additional intellectual property rights grant can be found
+ * in the file PATENTS. All contributing project authors may
+ * be found in the AUTHORS file in the root of the source tree.
+ */
+
+#ifndef MODULES_CONGESTION_CONTROLLER_GOOG_CC_LOSS_BASED_BWE_H_
+#define MODULES_CONGESTION_CONTROLLER_GOOG_CC_LOSS_BASED_BWE_H_
+
+#include <cstdint>
+#include <deque>
+#include <memory>
+#include <optional>
+#include <utility>
+
+#include "api/field_trials_view.h"
+#include "api/transport/network_types.h"
+#include "api/units/data_rate.h"
+#include "api/units/time_delta.h"
+#include "api/units/timestamp.h"
+#include "modules/congestion_controller/goog_cc/loss_based_bwe_v2.h"
+
+namespace webrtc {
+
+// Estimates bandwidth available to WebRTC if there is packet loss.
+// The estimate will depend on loss calculated from transport feedback if it
+// exist, or (RTCP) receiver report otherwise.
+class LossBasedBwe {
+ public:
+ explicit LossBasedBwe(const FieldTrialsView* field_trials);
+
+ // Called when the network route change. Resets state.
+ void OnRouteChanged();
+
+ // Called when new transport feedback is received.
+ void OnTransportPacketsFeedback(const TransportPacketsFeedback& report,
+ DataRate delay_based,
+ std::optional<DataRate> acknowledged_bitrate,
+ bool is_probe_rate,
+ bool in_alr);
+
+ // Called when a new loss report (RTCP receiver report) is received.
+ void OnPacketLossReport(int64_t packets_lost,
+ int64_t packets_received,
+ TimeDelta round_trip_time,
+ Timestamp at_time);
+
+ // Returns true if estimate changed.
+ bool OnPeriodicProcess(Timestamp at_time);
+
+ void SetConfiguredMinMaxBitrate(DataRate min_rate, DataRate max_rate);
+ // Sets the rate used as reference if there is no transport feedback. It is
+ // also used as loss based estimate until enough transport feedback messages
+ // has been received.
+ void SetStartRate(DataRate fallback_rate);
+
+ LossBasedState state() const { return current_state_; }
+ DataRate GetEstimate();
+
+ // Returns (number of packets lost << 8) / total number of packets. There has
+ // to be at least 20 packets received or lost between each update.
+ uint8_t fraction_loss() const { return last_fraction_loss_; }
+
+ private:
+ // Updates history of min bitrates.
+ // After this method returns min_bitrate_history_.front().second contains the
+ // min bitrate used during last kBweIncreaseIntervalMs.
+ void UpdateMinHistory(Timestamp at_time);
+
+ void UpdateFallbackEstimate(DataRate new_estimate);
+
+ const FieldTrialsView* field_trials_;
+ std::unique_ptr<LossBasedBweV2> loss_based_bwe_v2_;
+
+ DataRate configured_min_rate_;
+ DataRate configured_max_rate_;
+ DataRate delay_based_bwe_ = DataRate::PlusInfinity();
+
+ DataRate fallback_estimate_ = DataRate::Zero();
+ LossBasedState current_state_ = LossBasedState::kDelayBasedEstimate;
+
+ TimeDelta last_round_trip_time_;
+ int lost_packets_since_last_loss_update_ = 0;
+ int expected_packets_since_last_loss_update_ = 0;
+ // State variables used before LossBasedBweV2 is ready to be used or if
+ // LossBasedBweV2 is disabled.
+ std::deque<std::pair<Timestamp, DataRate> > min_bitrate_history_;
+ bool has_decreased_since_last_fraction_loss_ = false;
+ Timestamp time_last_decrease_ = Timestamp::MinusInfinity();
+ float low_loss_threshold_;
+ float high_loss_threshold_;
+ DataRate bitrate_threshold_;
+
+ Timestamp first_report_time_ = Timestamp::MinusInfinity();
+ Timestamp last_loss_feedback_ = Timestamp::MinusInfinity();
+
+ Timestamp last_loss_packet_report_ = Timestamp::MinusInfinity();
+ uint8_t last_fraction_loss_ = 0;
+ uint8_t last_logged_fraction_loss_ = 0;
+};
+
+} // namespace webrtc
+#endif // MODULES_CONGESTION_CONTROLLER_GOOG_CC_LOSS_BASED_BWE_H_
diff --git a/modules/congestion_controller/goog_cc/loss_based_bwe_unittest.cc b/modules/congestion_controller/goog_cc/loss_based_bwe_unittest.cc
new file mode 100644
index 0000000..5256191
--- /dev/null
+++ b/modules/congestion_controller/goog_cc/loss_based_bwe_unittest.cc
@@ -0,0 +1,157 @@
+/*
+ * Copyright (c) 2025 The WebRTC project authors. All Rights Reserved.
+ *
+ * Use of this source code is governed by a BSD-style license
+ * that can be found in the LICENSE file in the root of the source
+ * tree. An additional intellectual property rights grant can be found
+ * in the file PATENTS. All contributing project authors may
+ * be found in the AUTHORS file in the root of the source tree.
+ */
+
+#include "modules/congestion_controller/goog_cc/loss_based_bwe.h"
+
+#include <optional>
+
+#include "api/field_trials.h"
+#include "api/transport/network_types.h"
+#include "api/units/data_rate.h"
+#include "api/units/time_delta.h"
+#include "api/units/timestamp.h"
+#include "modules/congestion_controller/goog_cc/loss_based_bwe_v2.h"
+#include "test/create_test_field_trials.h"
+#include "test/gtest.h"
+
+namespace webrtc {
+namespace {
+
+TEST(LossBasedBweTest, ReturnFractionLoss) {
+ FieldTrials field_trials = CreateTestFieldTrials();
+ LossBasedBwe loss_based_bwe(&field_trials);
+ loss_based_bwe.SetConfiguredMinMaxBitrate(DataRate::KilobitsPerSec(50),
+ DataRate::KilobitsPerSec(500));
+ loss_based_bwe.SetStartRate(DataRate::KilobitsPerSec(100));
+ EXPECT_EQ(loss_based_bwe.GetEstimate(), DataRate::KilobitsPerSec(100));
+
+ // 25% packet loss.
+ loss_based_bwe.OnPacketLossReport(/*packets_lost=*/5,
+ /*packets_received=*/20,
+ /*round_trip_time=*/TimeDelta::Millis(10),
+ Timestamp::Seconds(123));
+ EXPECT_EQ(loss_based_bwe.fraction_loss(), (5 << 8) / (20 + 5));
+
+ loss_based_bwe.OnPacketLossReport(
+ /*packets_lost=*/0,
+ /*packets_received=*/2,
+ /*round_trip_time=*/TimeDelta::Millis(10),
+ Timestamp::Seconds(123) + TimeDelta::Millis(50));
+ // Not enough packets for a new update. Expect old value.
+ EXPECT_EQ(loss_based_bwe.fraction_loss(), (5 << 8) / (20 + 5));
+
+ loss_based_bwe.OnPacketLossReport(
+ /*packets_lost=*/0,
+ /*packets_received=*/20,
+ /*round_trip_time=*/TimeDelta::Millis(10),
+ Timestamp::Seconds(123) + TimeDelta::Millis(70));
+ EXPECT_EQ(loss_based_bwe.fraction_loss(), 0);
+}
+
+// Test that BWE react to loss even if no transport feedback is received.
+TEST(LossBasedBweTest, EstimateReactToLossReport) {
+ FieldTrials field_trials = CreateTestFieldTrials();
+ LossBasedBwe loss_based_bwe(&field_trials);
+ loss_based_bwe.SetConfiguredMinMaxBitrate(DataRate::KilobitsPerSec(50),
+ DataRate::KilobitsPerSec(500));
+ loss_based_bwe.SetStartRate(DataRate::KilobitsPerSec(100));
+ EXPECT_EQ(loss_based_bwe.GetEstimate(), DataRate::KilobitsPerSec(100));
+
+ Timestamp now = Timestamp::Seconds(123);
+ for (int i = 0; i < 3; ++i) {
+ now += TimeDelta::Millis(30);
+ // 25% packet loss.
+ loss_based_bwe.OnPacketLossReport(
+ /*packets_lost=*/5,
+ /*packets_received=*/20,
+ /*round_trip_time=*/TimeDelta::Millis(10), now);
+ loss_based_bwe.OnPeriodicProcess(now);
+ }
+ EXPECT_LT(loss_based_bwe.GetEstimate(), DataRate::KilobitsPerSec(100));
+ // V0 loss based estimator does not change state. Probing is still allowed?
+ EXPECT_EQ(loss_based_bwe.state(), LossBasedState::kDelayBasedEstimate);
+
+ // If there is no loss, BWE eventually increase to current delay based
+ // estimate.
+ while (now < Timestamp::Seconds(123) + TimeDelta::Seconds(20)) {
+ now += TimeDelta::Millis(30);
+ loss_based_bwe.OnPacketLossReport(
+ /*packets_lost=*/0,
+ /*packets_received=*/20,
+ /*round_trip_time=*/TimeDelta::Millis(10), now);
+ loss_based_bwe.OnPeriodicProcess(now);
+ }
+ EXPECT_GT(loss_based_bwe.GetEstimate(), DataRate::KilobitsPerSec(100));
+ EXPECT_LE(loss_based_bwe.GetEstimate(), DataRate::KilobitsPerSec(500));
+ EXPECT_EQ(loss_based_bwe.state(), LossBasedState::kDelayBasedEstimate);
+}
+
+TEST(LossBasedBweTest, IsProbeRateResetBweEvenIfLossLimitedInStartPhase) {
+ FieldTrials field_trials = CreateTestFieldTrials();
+ LossBasedBwe loss_based_bwe(&field_trials);
+ loss_based_bwe.SetConfiguredMinMaxBitrate(DataRate::KilobitsPerSec(50),
+ DataRate::KilobitsPerSec(500));
+ loss_based_bwe.SetStartRate(DataRate::KilobitsPerSec(100));
+ ASSERT_EQ(loss_based_bwe.GetEstimate(), DataRate::KilobitsPerSec(100));
+
+ Timestamp now = Timestamp::Seconds(123);
+ for (int i = 0; i < 3; ++i) {
+ now += TimeDelta::Millis(30);
+ // 25% packet loss.
+ loss_based_bwe.OnPacketLossReport(
+ /*packets_lost=*/5,
+ /*packets_received=*/20,
+ /*round_trip_time=*/TimeDelta::Millis(10), now);
+ loss_based_bwe.OnPeriodicProcess(now);
+ }
+ ASSERT_LT(loss_based_bwe.GetEstimate(), DataRate::KilobitsPerSec(100));
+
+ TransportPacketsFeedback feedback;
+ feedback.feedback_time = now;
+ loss_based_bwe.OnTransportPacketsFeedback(
+ feedback, DataRate::KilobitsPerSec(200),
+ /*acknowledged_bitrate=*/std::nullopt,
+ /*is_probe_rate=*/true,
+ /*in_alr=*/false);
+ EXPECT_EQ(loss_based_bwe.GetEstimate(), DataRate::KilobitsPerSec(200));
+}
+
+TEST(LossBasedBweTest, DelayBasedBweDoesNotResetBweIfLossLimitedInStartPhase) {
+ FieldTrials field_trials = CreateTestFieldTrials();
+ LossBasedBwe loss_based_bwe(&field_trials);
+ loss_based_bwe.SetConfiguredMinMaxBitrate(DataRate::KilobitsPerSec(50),
+ DataRate::KilobitsPerSec(500));
+ loss_based_bwe.SetStartRate(DataRate::KilobitsPerSec(100));
+ ASSERT_EQ(loss_based_bwe.GetEstimate(), DataRate::KilobitsPerSec(100));
+
+ Timestamp now = Timestamp::Seconds(123);
+ for (int i = 0; i < 3; ++i) {
+ now += TimeDelta::Millis(30);
+ // 25% packet loss.
+ loss_based_bwe.OnPacketLossReport(
+ /*packets_lost=*/5,
+ /*packets_received=*/20,
+ /*round_trip_time=*/TimeDelta::Millis(10), now);
+ loss_based_bwe.OnPeriodicProcess(now);
+ }
+ ASSERT_LT(loss_based_bwe.GetEstimate(), DataRate::KilobitsPerSec(100));
+
+ TransportPacketsFeedback feedback;
+ feedback.feedback_time = now;
+ loss_based_bwe.OnTransportPacketsFeedback(
+ feedback, DataRate::KilobitsPerSec(200),
+ /*acknowledged_bitrate=*/std::nullopt,
+ /*is_probe_rate=*/false,
+ /*in_alr=*/false);
+ EXPECT_LT(loss_based_bwe.GetEstimate(), DataRate::KilobitsPerSec(100));
+}
+
+} // anonymous namespace
+} // namespace webrtc
diff --git a/modules/congestion_controller/goog_cc/send_side_bandwidth_estimation.cc b/modules/congestion_controller/goog_cc/send_side_bandwidth_estimation.cc
index 03c3f61..b4c6e1c 100644
--- a/modules/congestion_controller/goog_cc/send_side_bandwidth_estimation.cc
+++ b/modules/congestion_controller/goog_cc/send_side_bandwidth_estimation.cc
@@ -13,20 +13,17 @@
#include <algorithm>
#include <cstdint>
#include <cstdio>
-#include <limits>
#include <memory>
#include <optional>
-#include <string>
-#include <utility>
#include "api/field_trials_view.h"
#include "api/rtc_event_log/rtc_event_log.h"
-#include "api/transport/bandwidth_usage.h"
#include "api/transport/network_types.h"
#include "api/units/data_rate.h"
#include "api/units/time_delta.h"
#include "api/units/timestamp.h"
#include "logging/rtc_event_log/events/rtc_event_bwe_update_loss_based.h"
+#include "modules/congestion_controller/goog_cc/loss_based_bwe.h"
#include "modules/congestion_controller/goog_cc/loss_based_bwe_v2.h"
#include "modules/remote_bitrate_estimator/include/bwe_defines.h"
#include "rtc_base/checks.h"
@@ -36,20 +33,12 @@
namespace webrtc {
namespace {
-constexpr TimeDelta kBweIncreaseInterval = TimeDelta::Millis(1000);
-constexpr TimeDelta kBweDecreaseInterval = TimeDelta::Millis(300);
+
constexpr TimeDelta kStartPhase = TimeDelta::Millis(2000);
constexpr TimeDelta kBweConverganceTime = TimeDelta::Millis(20000);
-constexpr int kLimitNumPackets = 20;
constexpr DataRate kDefaultMaxBitrate = DataRate::BitsPerSec(1000000000);
constexpr TimeDelta kLowBitrateLogPeriod = TimeDelta::Millis(10000);
constexpr TimeDelta kRtcEventLogPeriod = TimeDelta::Millis(5000);
-// Expecting that RTCP feedback is sent uniformly within [0.5, 1.5]s intervals.
-constexpr TimeDelta kMaxRtcpFeedbackInterval = TimeDelta::Millis(5000);
-
-constexpr float kDefaultLowLossThreshold = 0.02f;
-constexpr float kDefaultHighLossThreshold = 0.1f;
-constexpr DataRate kDefaultBitrateThreshold = DataRate::Zero();
struct UmaRampUpMetric {
const char* metric_name;
@@ -63,49 +52,6 @@
const size_t kNumUmaRampupMetrics =
sizeof(kUmaRampupMetrics) / sizeof(kUmaRampupMetrics[0]);
-const char kBweLosExperiment[] = "WebRTC-BweLossExperiment";
-
-bool BweLossExperimentIsEnabled(const FieldTrialsView& field_trials) {
- return field_trials.IsEnabled(kBweLosExperiment);
-}
-
-bool ReadBweLossExperimentParameters(const FieldTrialsView& field_trials,
- float* low_loss_threshold,
- float* high_loss_threshold,
- uint32_t* bitrate_threshold_kbps) {
- RTC_DCHECK(low_loss_threshold);
- RTC_DCHECK(high_loss_threshold);
- RTC_DCHECK(bitrate_threshold_kbps);
- std::string experiment_string = field_trials.Lookup(kBweLosExperiment);
- int parsed_values =
- sscanf(experiment_string.c_str(), "Enabled-%f,%f,%u", low_loss_threshold,
- high_loss_threshold, bitrate_threshold_kbps);
- if (parsed_values == 3) {
- RTC_CHECK_GT(*low_loss_threshold, 0.0f)
- << "Loss threshold must be greater than 0.";
- RTC_CHECK_LE(*low_loss_threshold, 1.0f)
- << "Loss threshold must be less than or equal to 1.";
- RTC_CHECK_GT(*high_loss_threshold, 0.0f)
- << "Loss threshold must be greater than 0.";
- RTC_CHECK_LE(*high_loss_threshold, 1.0f)
- << "Loss threshold must be less than or equal to 1.";
- RTC_CHECK_LE(*low_loss_threshold, *high_loss_threshold)
- << "The low loss threshold must be less than or equal to the high loss "
- "threshold.";
- RTC_CHECK_GE(*bitrate_threshold_kbps, 0)
- << "Bitrate threshold can't be negative.";
- RTC_CHECK_LT(*bitrate_threshold_kbps,
- std::numeric_limits<int>::max() / 1000)
- << "Bitrate must be smaller enough to avoid overflows.";
- return true;
- }
- RTC_LOG(LS_WARNING) << "Failed to parse parameters for BweLossExperiment "
- "experiment from field trial string. Using default.";
- *low_loss_threshold = kDefaultLowLossThreshold;
- *high_loss_threshold = kDefaultHighLossThreshold;
- *bitrate_threshold_kbps = kDefaultBitrateThreshold.kbps();
- return false;
-}
} // namespace
RttBasedBackoff::RttBasedBackoff(const FieldTrialsView& key_value_config)
@@ -150,87 +96,54 @@
SendSideBandwidthEstimation::SendSideBandwidthEstimation(
const FieldTrialsView* key_value_config,
RtcEventLog* event_log)
- : key_value_config_(key_value_config),
- rtt_backoff_(*key_value_config),
- lost_packets_since_last_loss_update_(0),
- expected_packets_since_last_loss_update_(0),
- current_target_(DataRate::Zero()),
- last_logged_target_(DataRate::Zero()),
- min_bitrate_configured_(kCongestionControllerMinBitrate),
- max_bitrate_configured_(kDefaultMaxBitrate),
- last_low_bitrate_log_(Timestamp::MinusInfinity()),
- has_decreased_since_last_fraction_loss_(false),
- last_loss_feedback_(Timestamp::MinusInfinity()),
- last_loss_packet_report_(Timestamp::MinusInfinity()),
- last_fraction_loss_(0),
+ : rtt_backoff_(*key_value_config),
+ loss_based_bwe_(key_value_config),
last_logged_fraction_loss_(0),
last_round_trip_time_(TimeDelta::Zero()),
receiver_limit_(DataRate::PlusInfinity()),
delay_based_limit_(DataRate::PlusInfinity()),
- time_last_decrease_(Timestamp::MinusInfinity()),
- first_report_time_(Timestamp::MinusInfinity()),
+ loss_based_limit_(DataRate::PlusInfinity()),
+ current_target_(kCongestionControllerMinBitrate),
+ last_logged_target_(DataRate::Zero()),
+ min_bitrate_configured_(kCongestionControllerMinBitrate),
+ max_bitrate_configured_(kDefaultMaxBitrate),
+
+ last_low_bitrate_log_(Timestamp::MinusInfinity()),
+ time_last_decrease_due_to_rtt_(Timestamp::MinusInfinity()),
+ first_loss_report_time_(Timestamp::MinusInfinity()),
initially_lost_packets_(0),
bitrate_at_2_seconds_(DataRate::Zero()),
uma_update_state_(kNoUpdate),
uma_rtt_state_(kNoUpdate),
rampup_uma_stats_updated_(kNumUmaRampupMetrics, false),
event_log_(event_log),
- last_rtc_event_log_(Timestamp::MinusInfinity()),
- low_loss_threshold_(kDefaultLowLossThreshold),
- high_loss_threshold_(kDefaultHighLossThreshold),
- bitrate_threshold_(kDefaultBitrateThreshold),
- loss_based_bandwidth_estimator_v2_(new LossBasedBweV2(key_value_config)),
- loss_based_state_(LossBasedState::kDelayBasedEstimate),
- disable_receiver_limit_caps_only_("Disabled") {
+ last_rtc_event_log_(Timestamp::MinusInfinity()) {
RTC_DCHECK(event_log);
- if (BweLossExperimentIsEnabled(*key_value_config_)) {
- uint32_t bitrate_threshold_kbps;
- if (ReadBweLossExperimentParameters(
- *key_value_config_, &low_loss_threshold_, &high_loss_threshold_,
- &bitrate_threshold_kbps)) {
- RTC_LOG(LS_INFO) << "Enabled BweLossExperiment with parameters "
- << low_loss_threshold_ << ", " << high_loss_threshold_
- << ", " << bitrate_threshold_kbps;
- bitrate_threshold_ = DataRate::KilobitsPerSec(bitrate_threshold_kbps);
- }
- }
- ParseFieldTrial({&disable_receiver_limit_caps_only_},
- key_value_config->Lookup("WebRTC-Bwe-ReceiverLimitCapsOnly"));
- if (LossBasedBandwidthEstimatorV2Enabled()) {
- loss_based_bandwidth_estimator_v2_->SetMinMaxBitrate(
- min_bitrate_configured_, max_bitrate_configured_);
- }
+ loss_based_bwe_.SetConfiguredMinMaxBitrate(min_bitrate_configured_,
+ max_bitrate_configured_);
}
SendSideBandwidthEstimation::~SendSideBandwidthEstimation() {}
void SendSideBandwidthEstimation::OnRouteChange() {
- lost_packets_since_last_loss_update_ = 0;
- expected_packets_since_last_loss_update_ = 0;
- current_target_ = DataRate::Zero();
+ current_target_ = kCongestionControllerMinBitrate;
min_bitrate_configured_ = kCongestionControllerMinBitrate;
max_bitrate_configured_ = kDefaultMaxBitrate;
last_low_bitrate_log_ = Timestamp::MinusInfinity();
- has_decreased_since_last_fraction_loss_ = false;
- last_loss_feedback_ = Timestamp::MinusInfinity();
- last_loss_packet_report_ = Timestamp::MinusInfinity();
- last_fraction_loss_ = 0;
last_logged_fraction_loss_ = 0;
last_round_trip_time_ = TimeDelta::Zero();
receiver_limit_ = DataRate::PlusInfinity();
delay_based_limit_ = DataRate::PlusInfinity();
- time_last_decrease_ = Timestamp::MinusInfinity();
- first_report_time_ = Timestamp::MinusInfinity();
+ loss_based_limit_ = DataRate::PlusInfinity();
+ time_last_decrease_due_to_rtt_ = Timestamp::MinusInfinity();
+ first_loss_report_time_ = Timestamp::MinusInfinity();
initially_lost_packets_ = 0;
bitrate_at_2_seconds_ = DataRate::Zero();
uma_update_state_ = kNoUpdate;
uma_rtt_state_ = kNoUpdate;
last_rtc_event_log_ = Timestamp::MinusInfinity();
- if (LossBasedBandwidthEstimatorV2Enabled() &&
- loss_based_bandwidth_estimator_v2_->UseInStartPhase()) {
- loss_based_bandwidth_estimator_v2_.reset(
- new LossBasedBweV2(key_value_config_));
- }
+ rtt_back_off_rate_ = std::nullopt;
+ loss_based_bwe_.OnRouteChanged();
}
void SendSideBandwidthEstimation::SetBitrates(
@@ -240,21 +153,12 @@
Timestamp at_time) {
SetMinMaxBitrate(min_bitrate, max_bitrate);
if (send_bitrate) {
- SetSendBitrate(*send_bitrate, at_time);
+ delay_based_limit_ = DataRate::PlusInfinity();
+ current_target_ = *send_bitrate;
+ loss_based_bwe_.SetStartRate(*send_bitrate);
}
}
-void SendSideBandwidthEstimation::SetSendBitrate(DataRate bitrate,
- Timestamp at_time) {
- RTC_DCHECK_GT(bitrate, DataRate::Zero());
- // Reset to avoid being capped by the estimate.
- delay_based_limit_ = DataRate::PlusInfinity();
- UpdateTargetBitrate(bitrate, at_time);
- // Clear last sent bitrate history so the new value can be used directly
- // and not capped.
- min_bitrate_history_.clear();
-}
-
void SendSideBandwidthEstimation::SetMinMaxBitrate(DataRate min_bitrate,
DataRate max_bitrate) {
min_bitrate_configured_ =
@@ -264,8 +168,8 @@
} else {
max_bitrate_configured_ = kDefaultMaxBitrate;
}
- loss_based_bandwidth_estimator_v2_->SetMinMaxBitrate(min_bitrate_configured_,
- max_bitrate_configured_);
+ loss_based_bwe_.SetConfiguredMinMaxBitrate(min_bitrate_configured_,
+ max_bitrate_configured_);
}
int SendSideBandwidthEstimation::GetMinBitrate() const {
@@ -273,14 +177,11 @@
}
DataRate SendSideBandwidthEstimation::target_rate() const {
- DataRate target = current_target_;
- if (!disable_receiver_limit_caps_only_)
- target = std::min(target, receiver_limit_);
- return std::max(min_bitrate_configured_, target);
+ return current_target_;
}
LossBasedState SendSideBandwidthEstimation::loss_based_state() const {
- return loss_based_state_;
+ return loss_based_bwe_.state();
}
bool SendSideBandwidthEstimation::IsRttAboveLimit() const {
@@ -291,78 +192,59 @@
DataRate bandwidth) {
// TODO(srte): Ensure caller passes PlusInfinity, not zero, to represent no
// limitation.
- receiver_limit_ = bandwidth.IsZero() ? DataRate::PlusInfinity() : bandwidth;
- ApplyTargetLimits(at_time);
-}
+ DataRate estimate = bandwidth.IsZero() ? DataRate::PlusInfinity() : bandwidth;
+ if (estimate != receiver_limit_) {
+ receiver_limit_ = estimate;
-void SendSideBandwidthEstimation::UpdateDelayBasedEstimate(Timestamp at_time,
- DataRate bitrate) {
- // TODO(srte): Ensure caller passes PlusInfinity, not zero, to represent no
- // limitation.
- delay_based_limit_ = bitrate.IsZero() ? DataRate::PlusInfinity() : bitrate;
- ApplyTargetLimits(at_time);
-}
-
-void SendSideBandwidthEstimation::SetAcknowledgedRate(
- std::optional<DataRate> acknowledged_rate,
- Timestamp at_time) {
- acknowledged_rate_ = acknowledged_rate;
- if (!acknowledged_rate.has_value()) {
- return;
- }
- if (LossBasedBandwidthEstimatorV2Enabled()) {
- loss_based_bandwidth_estimator_v2_->SetAcknowledgedBitrate(
- *acknowledged_rate);
+ if (IsInStartPhase(at_time) && loss_based_bwe_.fraction_loss() == 0 &&
+ receiver_limit_ > current_target_ &&
+ delay_based_limit_ > receiver_limit_) {
+ // Reset the (fallback) loss based estimator and trust the remote estimate
+ // is a good starting rate.
+ loss_based_bwe_.SetStartRate(receiver_limit_);
+ loss_based_limit_ = loss_based_bwe_.GetEstimate();
+ }
+ ApplyTargetLimits(at_time);
}
}
-void SendSideBandwidthEstimation::UpdateLossBasedEstimator(
+void SendSideBandwidthEstimation::OnTransportPacketsFeedback(
const TransportPacketsFeedback& report,
- BandwidthUsage /* delay_detector_state */,
- std::optional<DataRate> /* probe_bitrate */,
+ DataRate delay_based_estimate,
+ std::optional<DataRate> acknowledged_rate,
+ bool is_probe_rate,
bool in_alr) {
- if (LossBasedBandwidthEstimatorV2Enabled()) {
- loss_based_bandwidth_estimator_v2_->UpdateBandwidthEstimate(
- report.packet_feedbacks, delay_based_limit_, in_alr);
- UpdateEstimate(report.feedback_time);
+ delay_based_estimate = delay_based_estimate.IsZero()
+ ? DataRate::PlusInfinity()
+ : delay_based_estimate;
+ acknowledged_rate_ = acknowledged_rate;
+
+ loss_based_bwe_.OnTransportPacketsFeedback(
+ report, delay_based_estimate, acknowledged_rate_, is_probe_rate, in_alr);
+
+ DataRate loss_based_estimate = loss_based_bwe_.GetEstimate();
+ if (loss_based_estimate != loss_based_limit_ ||
+ delay_based_limit_ != delay_based_estimate) {
+ delay_based_limit_ = delay_based_estimate;
+ loss_based_limit_ = loss_based_estimate;
+ ApplyTargetLimits(report.feedback_time);
}
}
void SendSideBandwidthEstimation::UpdatePacketsLost(int64_t packets_lost,
- int64_t number_of_packets,
+ int64_t packets_received,
Timestamp at_time) {
- last_loss_feedback_ = at_time;
- if (first_report_time_.IsInfinite())
- first_report_time_ = at_time;
-
- // Check sequence number diff and weight loss report
- if (number_of_packets > 0) {
- int64_t expected =
- expected_packets_since_last_loss_update_ + number_of_packets;
-
- // Don't generate a loss rate until it can be based on enough packets.
- if (expected < kLimitNumPackets) {
- // Accumulate reports.
- expected_packets_since_last_loss_update_ = expected;
- lost_packets_since_last_loss_update_ += packets_lost;
- return;
- }
-
- has_decreased_since_last_fraction_loss_ = false;
- int64_t lost_q8 =
- std::max<int64_t>(lost_packets_since_last_loss_update_ + packets_lost,
- 0)
- << 8;
- last_fraction_loss_ = std::min<int>(lost_q8 / expected, 255);
-
- // Reset accumulators.
- lost_packets_since_last_loss_update_ = 0;
- expected_packets_since_last_loss_update_ = 0;
- last_loss_packet_report_ = at_time;
- UpdateEstimate(at_time);
+ if (first_loss_report_time_.IsInfinite()) {
+ first_loss_report_time_ = at_time;
}
-
+ loss_based_bwe_.OnPacketLossReport(packets_lost, packets_received,
+ last_round_trip_time_, at_time);
UpdateUmaStatsPacketsLost(at_time, packets_lost);
+ DataRate estimate = loss_based_bwe_.GetEstimate();
+ if (estimate != loss_based_limit_) {
+ loss_based_limit_ = loss_based_bwe_.GetEstimate();
+ ApplyTargetLimits(at_time);
+ }
}
void SendSideBandwidthEstimation::UpdateUmaStatsPacketsLost(Timestamp at_time,
@@ -373,7 +255,7 @@
if (!rampup_uma_stats_updated_[i] &&
bitrate_kbps.kbps() >= kUmaRampupMetrics[i].bitrate_kbps) {
RTC_HISTOGRAMS_COUNTS_100000(i, kUmaRampupMetrics[i].metric_name,
- (at_time - first_report_time_).ms());
+ (at_time - first_loss_report_time_).ms());
rampup_uma_stats_updated_[i] = true;
}
}
@@ -387,7 +269,7 @@
RTC_HISTOGRAM_COUNTS("WebRTC.BWE.InitialBandwidthEstimate",
bitrate_at_2_seconds_.kbps(), 0, 2000, 50);
} else if (uma_update_state_ == kFirstDone &&
- at_time - first_report_time_ >= kBweConverganceTime) {
+ at_time - first_loss_report_time_ >= kBweConverganceTime) {
uma_update_state_ = kDone;
int bitrate_diff_kbps = std::max(
bitrate_at_2_seconds_.kbps<int>() - bitrate_kbps.kbps<int>(), 0);
@@ -408,111 +290,25 @@
}
}
-void SendSideBandwidthEstimation::UpdateEstimate(Timestamp at_time) {
+void SendSideBandwidthEstimation::OnPeriodicUpdate(Timestamp at_time) {
if (rtt_backoff_.IsRttAboveLimit()) {
- if (at_time - time_last_decrease_ >= rtt_backoff_.drop_interval_ &&
+ if (at_time - time_last_decrease_due_to_rtt_ >=
+ rtt_backoff_.drop_interval_ &&
current_target_ > rtt_backoff_.bandwidth_floor_) {
- time_last_decrease_ = at_time;
- DataRate new_bitrate =
+ time_last_decrease_due_to_rtt_ = at_time;
+ rtt_back_off_rate_ =
std::max(current_target_ * rtt_backoff_.drop_fraction_,
rtt_backoff_.bandwidth_floor_.Get());
- UpdateTargetBitrate(new_bitrate, at_time);
- return;
+ ApplyTargetLimits(at_time);
}
- // TODO(srte): This is likely redundant in most cases.
+ } else if (rtt_back_off_rate_.has_value()) {
+ rtt_back_off_rate_ = std::nullopt;
ApplyTargetLimits(at_time);
- return;
}
-
- // We trust the REMB and/or delay-based estimate during the first 2 seconds if
- // we haven't had any packet loss reported, to allow startup bitrate probing.
- if (last_fraction_loss_ == 0 && IsInStartPhase(at_time) &&
- !loss_based_bandwidth_estimator_v2_->ReadyToUseInStartPhase()) {
- DataRate new_bitrate = current_target_;
- // TODO(srte): We should not allow the new_bitrate to be larger than the
- // receiver limit here.
- if (receiver_limit_.IsFinite())
- new_bitrate = std::max(receiver_limit_, new_bitrate);
- if (delay_based_limit_.IsFinite()) {
- new_bitrate = std::max(delay_based_limit_, new_bitrate);
- }
- if (new_bitrate != current_target_) {
- min_bitrate_history_.clear();
- min_bitrate_history_.push_back(std::make_pair(at_time, current_target_));
- UpdateTargetBitrate(new_bitrate, at_time);
- return;
- }
- }
- UpdateMinHistory(at_time);
- if (last_loss_packet_report_.IsInfinite()) {
- // No feedback received.
- // TODO(srte): This is likely redundant in most cases.
+ if (loss_based_bwe_.OnPeriodicProcess(at_time)) {
+ loss_based_limit_ = loss_based_bwe_.GetEstimate();
ApplyTargetLimits(at_time);
- return;
}
-
- if (LossBasedBandwidthEstimatorV2ReadyForUse()) {
- LossBasedBweV2::Result result =
- loss_based_bandwidth_estimator_v2_->GetLossBasedResult();
- loss_based_state_ = result.state;
- UpdateTargetBitrate(result.bandwidth_estimate, at_time);
- return;
- }
-
- TimeDelta time_since_loss_packet_report = at_time - last_loss_packet_report_;
- if (time_since_loss_packet_report < 1.2 * kMaxRtcpFeedbackInterval) {
- // We only care about loss above a given bitrate threshold.
- float loss = last_fraction_loss_ / 256.0f;
- // We only make decisions based on loss when the bitrate is above a
- // threshold. This is a crude way of handling loss which is uncorrelated
- // to congestion.
- if (current_target_ < bitrate_threshold_ || loss <= low_loss_threshold_) {
- // Loss < 2%: Increase rate by 8% of the min bitrate in the last
- // kBweIncreaseInterval.
- // Note that by remembering the bitrate over the last second one can
- // rampup up one second faster than if only allowed to start ramping
- // at 8% per second rate now. E.g.:
- // If sending a constant 100kbps it can rampup immediately to 108kbps
- // whenever a receiver report is received with lower packet loss.
- // If instead one would do: current_bitrate_ *= 1.08^(delta time),
- // it would take over one second since the lower packet loss to achieve
- // 108kbps.
- DataRate new_bitrate = DataRate::BitsPerSec(
- min_bitrate_history_.front().second.bps() * 1.08 + 0.5);
-
- // Add 1 kbps extra, just to make sure that we do not get stuck
- // (gives a little extra increase at low rates, negligible at higher
- // rates).
- new_bitrate += DataRate::BitsPerSec(1000);
- UpdateTargetBitrate(new_bitrate, at_time);
- return;
- } else if (current_target_ > bitrate_threshold_) {
- if (loss <= high_loss_threshold_) {
- // Loss between 2% - 10%: Do nothing.
- } else {
- // Loss > 10%: Limit the rate decreases to once a kBweDecreaseInterval
- // + rtt.
- if (!has_decreased_since_last_fraction_loss_ &&
- (at_time - time_last_decrease_) >=
- (kBweDecreaseInterval + last_round_trip_time_)) {
- time_last_decrease_ = at_time;
-
- // Reduce rate:
- // newRate = rate * (1 - 0.5*lossRate);
- // where packetLoss = 256*lossRate;
- DataRate new_bitrate = DataRate::BitsPerSec(
- (current_target_.bps() *
- static_cast<double>(512 - last_fraction_loss_)) /
- 512.0);
- has_decreased_since_last_fraction_loss_ = true;
- UpdateTargetBitrate(new_bitrate, at_time);
- return;
- }
- }
- }
- }
- // TODO(srte): This is likely redundant in most cases.
- ApplyTargetLimits(at_time);
}
void SendSideBandwidthEstimation::UpdatePropagationRtt(
@@ -527,35 +323,8 @@
}
bool SendSideBandwidthEstimation::IsInStartPhase(Timestamp at_time) const {
- return first_report_time_.IsInfinite() ||
- at_time - first_report_time_ < kStartPhase;
-}
-
-void SendSideBandwidthEstimation::UpdateMinHistory(Timestamp at_time) {
- // Remove old data points from history.
- // Since history precision is in ms, add one so it is able to increase
- // bitrate if it is off by as little as 0.5ms.
- while (!min_bitrate_history_.empty() &&
- at_time - min_bitrate_history_.front().first + TimeDelta::Millis(1) >
- kBweIncreaseInterval) {
- min_bitrate_history_.pop_front();
- }
-
- // Typical minimum sliding-window algorithm: Pop values higher than current
- // bitrate before pushing it.
- while (!min_bitrate_history_.empty() &&
- current_target_ <= min_bitrate_history_.back().second) {
- min_bitrate_history_.pop_back();
- }
-
- min_bitrate_history_.push_back(std::make_pair(at_time, current_target_));
-}
-
-DataRate SendSideBandwidthEstimation::GetUpperLimit() const {
- DataRate upper_limit = delay_based_limit_;
- if (disable_receiver_limit_caps_only_)
- upper_limit = std::min(upper_limit, receiver_limit_);
- return std::min(upper_limit, max_bitrate_configured_);
+ return first_loss_report_time_.IsInfinite() ||
+ at_time - first_loss_report_time_ < kStartPhase;
}
void SendSideBandwidthEstimation::MaybeLogLowBitrateWarning(DataRate bitrate,
@@ -570,39 +339,28 @@
void SendSideBandwidthEstimation::MaybeLogLossBasedEvent(Timestamp at_time) {
if (current_target_ != last_logged_target_ ||
- last_fraction_loss_ != last_logged_fraction_loss_ ||
+ loss_based_bwe_.fraction_loss() != last_logged_fraction_loss_ ||
at_time - last_rtc_event_log_ > kRtcEventLogPeriod) {
event_log_->Log(std::make_unique<RtcEventBweUpdateLossBased>(
- current_target_.bps(), last_fraction_loss_,
- expected_packets_since_last_loss_update_));
- last_logged_fraction_loss_ = last_fraction_loss_;
+ current_target_.bps(), loss_based_bwe_.fraction_loss(),
+ /*total_packets_ =*/0));
+ last_logged_fraction_loss_ = loss_based_bwe_.fraction_loss();
last_logged_target_ = current_target_;
last_rtc_event_log_ = at_time;
}
}
-void SendSideBandwidthEstimation::UpdateTargetBitrate(DataRate new_bitrate,
- Timestamp at_time) {
- new_bitrate = std::min(new_bitrate, GetUpperLimit());
- if (new_bitrate < min_bitrate_configured_) {
- MaybeLogLowBitrateWarning(new_bitrate, at_time);
- new_bitrate = min_bitrate_configured_;
- }
- current_target_ = new_bitrate;
- MaybeLogLossBasedEvent(at_time);
-}
-
void SendSideBandwidthEstimation::ApplyTargetLimits(Timestamp at_time) {
- UpdateTargetBitrate(current_target_, at_time);
-}
+ current_target_ =
+ std::min({delay_based_limit_, receiver_limit_,
+ rtt_back_off_rate_.value_or(DataRate::PlusInfinity()),
+ loss_based_limit_, max_bitrate_configured_});
-bool SendSideBandwidthEstimation::LossBasedBandwidthEstimatorV2Enabled() const {
- return loss_based_bandwidth_estimator_v2_->IsEnabled();
-}
-
-bool SendSideBandwidthEstimation::LossBasedBandwidthEstimatorV2ReadyForUse()
- const {
- return loss_based_bandwidth_estimator_v2_->IsReady();
+ if (current_target_ < min_bitrate_configured_) {
+ MaybeLogLowBitrateWarning(current_target_, at_time);
+ current_target_ = min_bitrate_configured_;
+ }
+ MaybeLogLossBasedEvent(at_time);
}
} // namespace webrtc
diff --git a/modules/congestion_controller/goog_cc/send_side_bandwidth_estimation.h b/modules/congestion_controller/goog_cc/send_side_bandwidth_estimation.h
index 2795ba2..b68d984 100644
--- a/modules/congestion_controller/goog_cc/send_side_bandwidth_estimation.h
+++ b/modules/congestion_controller/goog_cc/send_side_bandwidth_estimation.h
@@ -15,18 +15,15 @@
#include <stdint.h>
-#include <deque>
-#include <memory>
#include <optional>
-#include <utility>
#include <vector>
#include "api/field_trials_view.h"
-#include "api/transport/bandwidth_usage.h"
#include "api/transport/network_types.h"
#include "api/units/data_rate.h"
#include "api/units/time_delta.h"
#include "api/units/timestamp.h"
+#include "modules/congestion_controller/goog_cc/loss_based_bwe.h"
#include "modules/congestion_controller/goog_cc/loss_based_bwe_v2.h"
#include "rtc_base/experiments/field_trial_parser.h"
@@ -71,23 +68,20 @@
// Return whether the current rtt is higher than the rtt limited configured in
// RttBasedBackoff.
bool IsRttAboveLimit() const;
- uint8_t fraction_loss() const { return last_fraction_loss_; }
+ uint8_t fraction_loss() const { return loss_based_bwe_.fraction_loss(); }
TimeDelta round_trip_time() const { return last_round_trip_time_; }
// Call periodically to update estimate.
- void UpdateEstimate(Timestamp at_time);
+ void OnPeriodicUpdate(Timestamp at_time);
void OnSentPacket(const SentPacket& sent_packet);
void UpdatePropagationRtt(Timestamp at_time, TimeDelta propagation_rtt);
// Call when we receive a RTCP message with TMMBR or REMB.
void UpdateReceiverEstimate(Timestamp at_time, DataRate bandwidth);
- // Call when a new delay-based estimate is available.
- void UpdateDelayBasedEstimate(Timestamp at_time, DataRate bitrate);
-
// Call when we receive a RTCP message with a ReceiveBlock.
void UpdatePacketsLost(int64_t packets_lost,
- int64_t number_of_packets,
+ int64_t packets_received,
Timestamp at_time);
// Call when we receive a RTCP message with a ReceiveBlock.
@@ -97,15 +91,14 @@
DataRate min_bitrate,
DataRate max_bitrate,
Timestamp at_time);
- void SetSendBitrate(DataRate bitrate, Timestamp at_time);
void SetMinMaxBitrate(DataRate min_bitrate, DataRate max_bitrate);
int GetMinBitrate() const;
- void SetAcknowledgedRate(std::optional<DataRate> acknowledged_rate,
- Timestamp at_time);
- void UpdateLossBasedEstimator(const TransportPacketsFeedback& report,
- BandwidthUsage delay_detector_state,
- std::optional<DataRate> probe_bitrate,
- bool in_alr);
+
+ void OnTransportPacketsFeedback(const TransportPacketsFeedback& report,
+ DataRate delay_based_estimate,
+ std::optional<DataRate> acknowledged_rate,
+ bool is_probe_rate,
+ bool in_alr);
private:
friend class GoogCcStatePrinter;
@@ -121,9 +114,6 @@
// min bitrate used during last kBweIncreaseIntervalMs.
void UpdateMinHistory(Timestamp at_time);
- // Gets the upper limit for the target bitrate. This is the minimum of the
- // delay based limit, the receiver limit and the loss based controller limit.
- DataRate GetUpperLimit() const;
// Prints a warning if `bitrate` if sufficiently long time has past since last
// warning.
void MaybeLogLowBitrateWarning(DataRate bitrate, Timestamp at_time);
@@ -131,47 +121,34 @@
// has changed, or sufficient time has passed since last stored event.
void MaybeLogLossBasedEvent(Timestamp at_time);
- // Cap `bitrate` to [min_bitrate_configured_, max_bitrate_configured_] and
- // set `current_bitrate_` to the capped value and updates the event log.
- void UpdateTargetBitrate(DataRate bitrate, Timestamp at_time);
- // Applies lower and upper bounds to the current target rate.
- // TODO(srte): This seems to be called even when limits haven't changed, that
- // should be cleaned up.
void ApplyTargetLimits(Timestamp at_time);
- bool LossBasedBandwidthEstimatorV2Enabled() const;
- bool LossBasedBandwidthEstimatorV2ReadyForUse() const;
-
const FieldTrialsView* key_value_config_;
RttBasedBackoff rtt_backoff_;
-
- std::deque<std::pair<Timestamp, DataRate> > min_bitrate_history_;
-
- // incoming filters
- int lost_packets_since_last_loss_update_;
- int expected_packets_since_last_loss_update_;
+ LossBasedBwe loss_based_bwe_;
std::optional<DataRate> acknowledged_rate_;
- DataRate current_target_;
- DataRate last_logged_target_;
- DataRate min_bitrate_configured_;
- DataRate max_bitrate_configured_;
- Timestamp last_low_bitrate_log_;
-
- bool has_decreased_since_last_fraction_loss_;
- Timestamp last_loss_feedback_;
- Timestamp last_loss_packet_report_;
- uint8_t last_fraction_loss_;
uint8_t last_logged_fraction_loss_;
TimeDelta last_round_trip_time_;
-
// The max bitrate as set by the receiver in the call. This is typically
// signalled using the REMB RTCP message and is used when we don't have any
// send side delay based estimate.
DataRate receiver_limit_;
DataRate delay_based_limit_;
- Timestamp time_last_decrease_;
- Timestamp first_report_time_;
+ DataRate loss_based_limit_;
+
+ // `rtt_back_off_rate_` is calculated in relation to a limit and can only be
+ // lower than the limit. If not, it is nullopt.
+ std::optional<DataRate> rtt_back_off_rate_;
+
+ DataRate current_target_; // Current combined target rate.
+ DataRate last_logged_target_;
+ DataRate min_bitrate_configured_;
+ DataRate max_bitrate_configured_;
+ Timestamp last_low_bitrate_log_;
+
+ Timestamp time_last_decrease_due_to_rtt_;
+ Timestamp first_loss_report_time_;
int initially_lost_packets_;
DataRate bitrate_at_2_seconds_;
UmaState uma_update_state_;
@@ -179,12 +156,6 @@
std::vector<bool> rampup_uma_stats_updated_;
RtcEventLog* const event_log_;
Timestamp last_rtc_event_log_;
- float low_loss_threshold_;
- float high_loss_threshold_;
- DataRate bitrate_threshold_;
- std::unique_ptr<LossBasedBweV2> loss_based_bandwidth_estimator_v2_;
- LossBasedState loss_based_state_;
- FieldTrialFlag disable_receiver_limit_caps_only_;
};
} // namespace webrtc
#endif // MODULES_CONGESTION_CONTROLLER_GOOG_CC_SEND_SIDE_BANDWIDTH_ESTIMATION_H_
diff --git a/modules/congestion_controller/goog_cc/send_side_bandwidth_estimation_unittest.cc b/modules/congestion_controller/goog_cc/send_side_bandwidth_estimation_unittest.cc
index 5efd337..93b76fc 100644
--- a/modules/congestion_controller/goog_cc/send_side_bandwidth_estimation_unittest.cc
+++ b/modules/congestion_controller/goog_cc/send_side_bandwidth_estimation_unittest.cc
@@ -11,10 +11,13 @@
#include "modules/congestion_controller/goog_cc/send_side_bandwidth_estimation.h"
#include <cstdint>
+#include <optional>
#include "api/field_trials.h"
#include "api/rtc_event_log/rtc_event.h"
+#include "api/transport/network_types.h"
#include "api/units/data_rate.h"
+#include "api/units/data_size.h"
#include "api/units/time_delta.h"
#include "api/units/timestamp.h"
#include "logging/rtc_event_log/events/rtc_event_bwe_update_loss_based.h"
@@ -41,70 +44,87 @@
return bwe_event->bitrate_bps() > 0 && bwe_event->fraction_loss() > 0;
}
-void TestProbing(bool use_delay_based) {
+TEST(SendSideBweTest, InitialRembAppliesImmediately) {
::testing::NiceMock<MockRtcEventLog> event_log;
FieldTrials key_value_config = CreateTestFieldTrials();
SendSideBandwidthEstimation bwe(&key_value_config, &event_log);
int64_t now_ms = 0;
- bwe.SetMinMaxBitrate(DataRate::BitsPerSec(100000),
- DataRate::BitsPerSec(1500000));
- bwe.SetSendBitrate(DataRate::BitsPerSec(200000), Timestamp::Millis(now_ms));
+ bwe.SetBitrates(DataRate::BitsPerSec(200000), DataRate::BitsPerSec(100000),
+ DataRate::BitsPerSec(1500000), Timestamp::Millis(now_ms));
const int kRembBps = 1000000;
const int kSecondRembBps = kRembBps + 500000;
- bwe.UpdatePacketsLost(/*packets_lost=*/0, /*number_of_packets=*/1,
+ bwe.UpdatePacketsLost(/*packets_lost=*/0, /*packets_received=*/1,
Timestamp::Millis(now_ms));
bwe.UpdateRtt(TimeDelta::Millis(50), Timestamp::Millis(now_ms));
// Initial REMB applies immediately.
- if (use_delay_based) {
- bwe.UpdateDelayBasedEstimate(Timestamp::Millis(now_ms),
- DataRate::BitsPerSec(kRembBps));
- } else {
- bwe.UpdateReceiverEstimate(Timestamp::Millis(now_ms),
- DataRate::BitsPerSec(kRembBps));
- }
- bwe.UpdateEstimate(Timestamp::Millis(now_ms));
- EXPECT_EQ(kRembBps, bwe.target_rate().bps());
+ bwe.UpdateReceiverEstimate(Timestamp::Millis(now_ms),
+ DataRate::BitsPerSec(kRembBps));
+ bwe.OnPeriodicUpdate(Timestamp::Millis(now_ms));
+ EXPECT_EQ(bwe.target_rate().bps(), kRembBps);
- // Second REMB doesn't apply immediately.
+ // Second REMB, after startphase doesn't apply immediately.
now_ms += 2001;
- if (use_delay_based) {
- bwe.UpdateDelayBasedEstimate(Timestamp::Millis(now_ms),
- DataRate::BitsPerSec(kSecondRembBps));
- } else {
- bwe.UpdateReceiverEstimate(Timestamp::Millis(now_ms),
- DataRate::BitsPerSec(kSecondRembBps));
+ bwe.UpdateReceiverEstimate(Timestamp::Millis(now_ms),
+ DataRate::BitsPerSec(kSecondRembBps));
+ bwe.OnPeriodicUpdate(Timestamp::Millis(now_ms));
+
+ EXPECT_EQ(bwe.target_rate().bps(), kRembBps);
+}
+
+TEST(SendSideBweTest, TargetFollowProbeRateIfNoLoss) {
+ ::testing::NiceMock<MockRtcEventLog> event_log;
+ FieldTrials key_value_config = CreateTestFieldTrials();
+ SendSideBandwidthEstimation bwe(&key_value_config, &event_log);
+ constexpr Timestamp kStartTime = Timestamp::Seconds(123);
+ constexpr DataRate kInitialBwe = DataRate::KilobitsPerSec(200);
+ bwe.SetBitrates(kInitialBwe, DataRate::KilobitsPerSec(100),
+ DataRate::KilobitsPerSec(15000), kStartTime);
+ bwe.UpdatePacketsLost(/*packets_lost=*/0, /*packets_received=*/1, kStartTime);
+
+ ASSERT_EQ(bwe.target_rate(), kInitialBwe);
+
+ DataRate delay_based_estimate = kInitialBwe;
+
+ int sequence_number = 0;
+ for (Timestamp now = kStartTime; now < kStartTime + TimeDelta::Seconds(5);
+ now = now + TimeDelta::Seconds(1)) {
+ TransportPacketsFeedback feedback;
+ feedback.feedback_time = now;
+ for (int i = 0; i < 100; ++i) {
+ PacketResult packet;
+ packet.sent_packet.sequence_number = ++sequence_number;
+ packet.sent_packet.send_time = now;
+ packet.sent_packet.size = DataSize::Bytes(1000);
+ packet.receive_time = now;
+ feedback.packet_feedbacks.push_back(packet);
+ }
+
+ bwe.OnTransportPacketsFeedback(
+ feedback, delay_based_estimate,
+ /*acknowledged_rate=*/delay_based_estimate / 2,
+ /*is_probe_rate=*/true,
+ /*in_alr=*/false);
+ EXPECT_EQ(bwe.target_rate(), delay_based_estimate);
+ delay_based_estimate = 2 * delay_based_estimate;
}
- bwe.UpdateEstimate(Timestamp::Millis(now_ms));
- EXPECT_EQ(kRembBps, bwe.target_rate().bps());
-}
-
-TEST(SendSideBweTest, InitialRembWithProbing) {
- TestProbing(false);
-}
-
-TEST(SendSideBweTest, InitialDelayBasedBweWithProbing) {
- TestProbing(true);
}
TEST(SendSideBweTest, DoesntReapplyBitrateDecreaseWithoutFollowingRemb) {
MockRtcEventLog event_log;
- EXPECT_CALL(event_log, LogProxy(LossBasedBweUpdateWithBitrateOnly()))
- .Times(1);
EXPECT_CALL(event_log,
LogProxy(LossBasedBweUpdateWithBitrateAndLossFraction()))
- .Times(1);
+ .Times(2);
FieldTrials key_value_config = CreateTestFieldTrials();
SendSideBandwidthEstimation bwe(&key_value_config, &event_log);
static const int kMinBitrateBps = 100000;
static const int kInitialBitrateBps = 1000000;
int64_t now_ms = 1000;
- bwe.SetMinMaxBitrate(DataRate::BitsPerSec(kMinBitrateBps),
- DataRate::BitsPerSec(1500000));
- bwe.SetSendBitrate(DataRate::BitsPerSec(kInitialBitrateBps),
- Timestamp::Millis(now_ms));
+ bwe.SetBitrates(DataRate::BitsPerSec(kInitialBitrateBps),
+ DataRate::BitsPerSec(kMinBitrateBps),
+ DataRate::BitsPerSec(1500000), Timestamp::Millis(now_ms));
static const uint8_t kFractionLoss = 128;
static const int64_t kRttMs = 50;
@@ -115,13 +135,15 @@
EXPECT_EQ(0, bwe.round_trip_time().ms());
// Signal heavy loss to go down in bitrate.
- bwe.UpdatePacketsLost(/*packets_lost=*/50, /*number_of_packets=*/100,
+ bwe.UpdatePacketsLost(/*packets_lost=*/50, /*packets_received=*/50,
Timestamp::Millis(now_ms));
bwe.UpdateRtt(TimeDelta::Millis(kRttMs), Timestamp::Millis(now_ms));
// Trigger an update 2 seconds later to not be rate limited.
now_ms += 1000;
- bwe.UpdateEstimate(Timestamp::Millis(now_ms));
+ bwe.UpdatePacketsLost(/*packets_lost=*/50, /*packets_received=*/50,
+ Timestamp::Millis(now_ms));
+ bwe.OnPeriodicUpdate(Timestamp::Millis(now_ms));
EXPECT_LT(bwe.target_rate().bps(), kInitialBitrateBps);
// Verify that the obtained bitrate isn't hitting the min bitrate, or this
// test doesn't make sense. If this ever happens, update the thresholds or
@@ -131,13 +153,13 @@
EXPECT_EQ(kRttMs, bwe.round_trip_time().ms());
// Triggering an update shouldn't apply further downgrade nor upgrade since
- // there's no intermediate receiver block received indicating whether this is
- // currently good or not.
+ // there's no intermediate receiver block received indicating whether this
+ // is currently good or not.
int last_bitrate_bps = bwe.target_rate().bps();
// Trigger an update 2 seconds later to not be rate limited (but it still
// shouldn't update).
now_ms += 1000;
- bwe.UpdateEstimate(Timestamp::Millis(now_ms));
+ bwe.OnPeriodicUpdate(Timestamp::Millis(now_ms));
EXPECT_EQ(last_bitrate_bps, bwe.target_rate().bps());
// The old loss rate should still be applied though.
@@ -145,34 +167,6 @@
EXPECT_EQ(kRttMs, bwe.round_trip_time().ms());
}
-TEST(SendSideBweTest, SettingSendBitrateOverridesDelayBasedEstimate) {
- ::testing::NiceMock<MockRtcEventLog> event_log;
- FieldTrials key_value_config = CreateTestFieldTrials();
- SendSideBandwidthEstimation bwe(&key_value_config, &event_log);
- static const int kMinBitrateBps = 10000;
- static const int kMaxBitrateBps = 10000000;
- static const int kInitialBitrateBps = 300000;
- static const int kDelayBasedBitrateBps = 350000;
- static const int kForcedHighBitrate = 2500000;
-
- int64_t now_ms = 0;
-
- bwe.SetMinMaxBitrate(DataRate::BitsPerSec(kMinBitrateBps),
- DataRate::BitsPerSec(kMaxBitrateBps));
- bwe.SetSendBitrate(DataRate::BitsPerSec(kInitialBitrateBps),
- Timestamp::Millis(now_ms));
-
- bwe.UpdateDelayBasedEstimate(Timestamp::Millis(now_ms),
- DataRate::BitsPerSec(kDelayBasedBitrateBps));
- bwe.UpdateEstimate(Timestamp::Millis(now_ms));
- EXPECT_GE(bwe.target_rate().bps(), kInitialBitrateBps);
- EXPECT_LE(bwe.target_rate().bps(), kDelayBasedBitrateBps);
-
- bwe.SetSendBitrate(DataRate::BitsPerSec(kForcedHighBitrate),
- Timestamp::Millis(now_ms));
- EXPECT_EQ(bwe.target_rate().bps(), kForcedHighBitrate);
-}
-
TEST(RttBasedBackoff, DefaultEnabled) {
RttBasedBackoff rtt_backoff(CreateTestFieldTrials());
EXPECT_TRUE(rtt_backoff.rtt_limit_.IsFinite());
@@ -192,10 +186,9 @@
static const int kMinBitrateBps = 100000;
static const int kInitialBitrateBps = 1000000;
int64_t now_ms = 1000;
- bwe.SetMinMaxBitrate(DataRate::BitsPerSec(kMinBitrateBps),
- DataRate::BitsPerSec(1500000));
- bwe.SetSendBitrate(DataRate::BitsPerSec(kInitialBitrateBps),
- Timestamp::Millis(now_ms));
+ bwe.SetBitrates(DataRate::BitsPerSec(kInitialBitrateBps),
+ DataRate::BitsPerSec(kMinBitrateBps),
+ DataRate::BitsPerSec(1500000), Timestamp::Millis(now_ms));
now_ms += 10000;
@@ -216,10 +209,10 @@
static const int kMaxBitrateBps = 10000000;
static const int kInitialBitrateBps = 300000;
int64_t now_ms = 0;
- bwe.SetMinMaxBitrate(DataRate::BitsPerSec(kMinBitrateBps),
- DataRate::BitsPerSec(kMaxBitrateBps));
- bwe.SetSendBitrate(DataRate::BitsPerSec(kInitialBitrateBps),
- Timestamp::Millis(now_ms));
+ bwe.SetBitrates(DataRate::BitsPerSec(kInitialBitrateBps),
+ DataRate::BitsPerSec(kMinBitrateBps),
+ DataRate::BitsPerSec(kMaxBitrateBps),
+ Timestamp::Millis(now_ms));
bwe.UpdatePropagationRtt(/*at_time=*/Timestamp::Millis(now_ms),
/*propagation_rtt=*/TimeDelta::Millis(5000));
EXPECT_TRUE(bwe.IsRttAboveLimit());
@@ -233,10 +226,10 @@
static const int kMaxBitrateBps = 10000000;
static const int kInitialBitrateBps = 300000;
int64_t now_ms = 0;
- bwe.SetMinMaxBitrate(DataRate::BitsPerSec(kMinBitrateBps),
- DataRate::BitsPerSec(kMaxBitrateBps));
- bwe.SetSendBitrate(DataRate::BitsPerSec(kInitialBitrateBps),
- Timestamp::Millis(now_ms));
+ bwe.SetBitrates(DataRate::BitsPerSec(kInitialBitrateBps),
+ DataRate::BitsPerSec(kMinBitrateBps),
+ DataRate::BitsPerSec(kMaxBitrateBps),
+ Timestamp::Millis(now_ms));
bwe.UpdatePropagationRtt(/*at_time=*/Timestamp::Millis(now_ms),
/*propagation_rtt=*/TimeDelta::Millis(1000));
EXPECT_FALSE(bwe.IsRttAboveLimit());