diff --git a/libraries/AP_HAL/tests/test_prescaler.cpp b/libraries/AP_HAL/tests/test_prescaler.cpp index 1afaa9f1bf..6e9bfb6070 100644 --- a/libraries/AP_HAL/tests/test_prescaler.cpp +++ b/libraries/AP_HAL/tests/test_prescaler.cpp @@ -11,24 +11,24 @@ protected: const uint32_t prescaler = AP_HAL::RCOutput::calculate_bitrate_prescaler(clock, target_rate, is_dshot); // we would like at most a 1% discrepancy in target versus actual const float rate_delta = fabsf(float(clock / prescaler) - target_rate) / target_rate; - EXPECT_TRUE(rate_delta < 0.20f); + EXPECT_TRUE(rate_delta < 0.13f); } }; TEST_P(PrescalerParameterizedTestFixture, DShot150) { - test_prescaler(GetParam(), 150000 * 20, true); + test_prescaler(GetParam(), 150000 * 8, true); } TEST_P(PrescalerParameterizedTestFixture, DShot300) { - test_prescaler(GetParam(), 300000 * 20, true); + test_prescaler(GetParam(), 300000 * 8, true); } TEST_P(PrescalerParameterizedTestFixture, DShot600) { - test_prescaler(GetParam(), 600000 * 20, true); + test_prescaler(GetParam(), 600000 * 8, true); } TEST_P(PrescalerParameterizedTestFixture, DShot1200) { - test_prescaler(GetParam(), 1200000 * 20, true); + test_prescaler(GetParam(), 1200000 * 8, true); } TEST_P(PrescalerParameterizedTestFixture, Passthrough) { @@ -36,11 +36,11 @@ TEST_P(PrescalerParameterizedTestFixture, Passthrough) { } TEST_P(PrescalerParameterizedTestFixture, NeoPixel) { - test_prescaler(GetParam(), 800000 * 20, false); + test_prescaler(GetParam(), 800000 * 11, false); } TEST_P(PrescalerParameterizedTestFixture, ProfiLED) { - test_prescaler(GetParam(), 1500000 * 20, false); + test_prescaler(GetParam(), 1500000 * 11, false); } INSTANTIATE_TEST_CASE_P(