Skip to content
Snippets Groups Projects
Commit 17834afc authored by Federico Mandelli's avatar Federico Mandelli
Browse files

[SensorConfig] Update BMX160_WITH_CORRECTION_SAMPLE_PERIOD to 100ms

parent 35392945
No related branches found
No related tags found
No related merge requests found
Pipeline #8753 passed
...@@ -119,6 +119,10 @@ constexpr float BATTERY_VOLTAGE_COEFF = (150 + 40.2) / 40.2; ...@@ -119,6 +119,10 @@ constexpr float BATTERY_VOLTAGE_COEFF = (150 + 40.2) / 40.2;
// imprecision, avoid clearing the fifo before the interrupt // imprecision, avoid clearing the fifo before the interrupt
constexpr unsigned int BMX160_SAMPLE_PERIOD = constexpr unsigned int BMX160_SAMPLE_PERIOD =
BMX160_FIFO_FILL_TIME * (BMX160_FIFO_WATERMARK + 30) * 4 / 1024; // [ms] BMX160_FIFO_FILL_TIME * (BMX160_FIFO_WATERMARK + 30) * 4 / 1024; // [ms]
// BMX160_WITH_CORRECTION_SAMPLE_PERIOD should be lower than the
// BMX160_SAMPLE_PERIOD and faster then the NAS
constexpr unsigned int BMX160_WITH_CORRECTION_SAMPLE_PERIOD = 100; // [ms]
constexpr unsigned int LIS3MDL_SAMPLE_PERIOD = 15; constexpr unsigned int LIS3MDL_SAMPLE_PERIOD = 15;
constexpr unsigned int INTERNAL_ADC_SAMPLE_PERIOD = 1000; // [ms] constexpr unsigned int INTERNAL_ADC_SAMPLE_PERIOD = 1000; // [ms]
constexpr unsigned int INTERNAL_TEMP_SAMPLE_PERIOD = 2000; // [ms] constexpr unsigned int INTERNAL_TEMP_SAMPLE_PERIOD = 2000; // [ms]
......
...@@ -244,7 +244,8 @@ void Sensors::bmx160WithCorrectionInit() ...@@ -244,7 +244,8 @@ void Sensors::bmx160WithCorrectionInit()
bmx160WithCorrection = bmx160WithCorrection =
new BMX160WithCorrection(bmx160, BMX160_AXIS_ROTATION); new BMX160WithCorrection(bmx160, BMX160_AXIS_ROTATION);
SensorInfo info("BMX160WithCorrection", BMX160_SAMPLE_PERIOD, SensorInfo info("BMX160WithCorrection",
BMX160_WITH_CORRECTION_SAMPLE_PERIOD,
bind(&Sensors::bmx160WithCorrectionCallback, this)); bind(&Sensors::bmx160WithCorrectionCallback, this));
sensorMap.emplace(make_pair(bmx160WithCorrection, info)); sensorMap.emplace(make_pair(bmx160WithCorrection, info));
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment