From a1bce2b54d7d6a0c6ee33930031f77c2c0c7ab17 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 17 Nov 2016 16:23:22 +1100 Subject: [PATCH] AP_Compass: use get_random16() --- libraries/AP_Compass/CompassCalibrator.cpp | 11 +---------- libraries/AP_Compass/CompassCalibrator.h | 2 -- 2 files changed, 1 insertion(+), 12 deletions(-) diff --git a/libraries/AP_Compass/CompassCalibrator.cpp b/libraries/AP_Compass/CompassCalibrator.cpp index 0f7039c3c1..b07f4df2ec 100644 --- a/libraries/AP_Compass/CompassCalibrator.cpp +++ b/libraries/AP_Compass/CompassCalibrator.cpp @@ -371,7 +371,7 @@ void CompassCalibrator::thin_samples() { // shuffle the samples http://en.wikipedia.org/wiki/Fisher%E2%80%93Yates_shuffle // this is so that adjacent samples don't get sequentially eliminated for(uint16_t i=_samples_collected-1; i>=1; i--) { - uint16_t j = get_random() % (i+1); + uint16_t j = get_random16() % (i+1); CompassSample temp = _sample_buffer[i]; _sample_buffer[i] = _sample_buffer[j]; _sample_buffer[j] = temp; @@ -686,15 +686,6 @@ void CompassCalibrator::run_ellipsoid_fit() } -uint16_t CompassCalibrator::get_random(void) -{ - static uint32_t m_z = 1234; - static uint32_t m_w = 76542; - m_z = 36969 * (m_z & 65535) + (m_z >> 16); - m_w = 18000 * (m_w & 65535) + (m_w >> 16); - return ((m_z << 16) + m_w) & 0xFFFF; -} - ////////////////////////////////////////////////////////// //////////// CompassSample public interface ////////////// ////////////////////////////////////////////////////////// diff --git a/libraries/AP_Compass/CompassCalibrator.h b/libraries/AP_Compass/CompassCalibrator.h index 16c1ef14aa..ed814afbea 100644 --- a/libraries/AP_Compass/CompassCalibrator.h +++ b/libraries/AP_Compass/CompassCalibrator.h @@ -135,6 +135,4 @@ private: * Reset and update #_completion_mask with the current samples. */ void update_completion_mask(); - - uint16_t get_random(); };