AP_TemperatureSensor: Add missing const in member functions

Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
Patrick José Pereira 2021-02-01 13:26:35 -03:00 committed by Andrew Tridgell
parent e146483e72
commit 6b2e4296db
2 changed files with 10 additions and 10 deletions

View File

@ -53,7 +53,7 @@ bool TSYS01::init(uint8_t bus)
return true;
}
bool TSYS01::_reset()
bool TSYS01::_reset() const
{
return _dev->transfer(&TSYS01_CMD_RESET, 1, nullptr, 0);
}
@ -80,7 +80,7 @@ bool TSYS01::_read_prom()
}
// Borrowed from MS Baro driver
uint16_t TSYS01::_read_prom_word(uint8_t word)
uint16_t TSYS01::_read_prom_word(uint8_t word) const
{
const uint8_t reg = TSYS01_CMD_READ_PROM + (word << 1);
uint8_t val[2];
@ -90,12 +90,12 @@ uint16_t TSYS01::_read_prom_word(uint8_t word)
return (val[0] << 8) | val[1];
}
bool TSYS01::_convert()
bool TSYS01::_convert() const
{
return _dev->transfer(&TSYS01_CMD_CONVERT, 1, nullptr, 0);
}
uint32_t TSYS01::_read_adc()
uint32_t TSYS01::_read_adc() const
{
uint8_t val[3];
if (!_dev->transfer(&TSYS01_CMD_READ_ADC, 1, val, 3)) {

View File

@ -14,8 +14,8 @@ class TSYS01 {
public:
bool init(uint8_t bus);
float temperature(void) { return _temperature; } // temperature in degrees C
bool healthy(void) { // do we have a valid temperature reading?
float temperature(void) const { return _temperature; } // temperature in degrees C
bool healthy(void) const { // do we have a valid temperature reading?
return _healthy;
}
@ -25,11 +25,11 @@ private:
float _temperature; // degrees C
bool _healthy; // we have a valid temperature reading to report
uint16_t _k[5]; // internal calibration for temperature calculation
bool _reset(void); // reset device
bool _reset(void) const; // reset device
bool _read_prom(void); // read (relevant) internal calibration registers into _k
bool _convert(void); // begin an ADC conversion (min:7.40ms typ:8.22ms max:9.04ms)
uint32_t _read_adc(void);
uint16_t _read_prom_word(uint8_t word);
bool _convert(void) const; // begin an ADC conversion (min:7.40ms typ:8.22ms max:9.04ms)
uint32_t _read_adc(void) const;
uint16_t _read_prom_word(uint8_t word) const;
void _timer(void); // update the temperature, called at 20Hz
void _calculate(uint32_t adc); // calculate temperature using adc reading and internal calibration
};