mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-04 23:18:28 -04:00
8da5275b03
The temperature readings is not subject to white noise so there's no point in averaging its reading. Moreover since for a normal 50Hz accumulate() / 10Hz update() it would read temperature only once per update(), it's pointless to keep averaging and introducing rounding error. The temperature doesn't need to be checked as frequent as pressure, too. The datasheet even suggests on section 3.3, page 10 to enable standard mode and read the temperature at 1Hz. Here we reduce it to 2Hz (considering the accumulate() function being called at 50Hz).
50 lines
1.1 KiB
C++
50 lines
1.1 KiB
C++
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
#pragma once
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
#include <AP_HAL/I2CDevice.h>
|
|
#include <AP_HAL/utility/OwnPtr.h>
|
|
|
|
#include "AP_Baro_Backend.h"
|
|
|
|
class AP_Baro_BMP085 : public AP_Baro_Backend
|
|
{
|
|
public:
|
|
AP_Baro_BMP085(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
|
|
|
|
/* AP_Baro public interface: */
|
|
void update();
|
|
void accumulate(void);
|
|
|
|
private:
|
|
void _cmd_read_pressure();
|
|
void _cmd_read_temp();
|
|
bool _read_pressure();
|
|
void _read_temp();
|
|
void _calculate();
|
|
bool _data_ready();
|
|
|
|
AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
|
|
AP_HAL::DigitalSource *_eoc;
|
|
|
|
uint8_t _instance;
|
|
uint8_t _count;
|
|
|
|
// Boards with no EOC pin: use times instead
|
|
uint32_t _last_press_read_command_time;
|
|
uint32_t _last_temp_read_command_time;
|
|
|
|
// State machine
|
|
uint8_t _state;
|
|
|
|
// Internal calibration registers
|
|
int16_t ac1, ac2, ac3, b1, b2, mb, mc, md;
|
|
uint16_t ac4, ac5, ac6;
|
|
|
|
uint32_t _retry_time;
|
|
int32_t _raw_pressure;
|
|
int32_t _raw_temp;
|
|
int32_t _temp;
|
|
float _press_sum;
|
|
};
|