mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_TemperatureSensor: add support for simulated TSYS01 temperature sensor
This commit is contained in:
parent
6433647d9e
commit
ecd21fbc4c
@ -15,9 +15,6 @@ static const uint8_t TSYS01_CMD_READ_ADC = 0x00;
|
||||
|
||||
bool TSYS01::init(uint8_t bus)
|
||||
{
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
return false;
|
||||
#endif
|
||||
_dev = std::move(hal.i2c_mgr->get_device(bus, TSYS01_ADDR));
|
||||
if (!_dev) {
|
||||
printf("TSYS01 device is null!");
|
||||
|
@ -16,20 +16,13 @@ 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?
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
return true;
|
||||
#endif
|
||||
return _healthy;
|
||||
}
|
||||
|
||||
AP_HAL::OwnPtr<AP_HAL::Device> _dev;
|
||||
|
||||
private:
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
float _temperature = 42.42; // degrees C
|
||||
#else
|
||||
float _temperature; // degrees C
|
||||
#endif
|
||||
bool _healthy; // we have a valid temperature reading to report
|
||||
uint16_t _k[5]; // internal calibration for temperature calculation
|
||||
bool _reset(void); // reset device
|
||||
|
Loading…
Reference in New Issue
Block a user