diff --git a/ArduSub/system.cpp b/ArduSub/system.cpp index 2f05066c31..84293f5574 100644 --- a/ArduSub/system.cpp +++ b/ArduSub/system.cpp @@ -40,13 +40,16 @@ void Sub::init_ardupilot() switch (AP_BoardConfig::get_board_type()) { case AP_BoardConfig::PX4_BOARD_PIXHAWK2: AP_Param::set_by_name("GND_EXT_BUS", 0); + celsius.init(0); break; default: AP_Param::set_by_name("GND_EXT_BUS", 1); + celsius.init(1); break; } #else AP_Param::set_default_by_name("GND_EXT_BUS", 1); + celsius.init(1); #endif // identify ourselves correctly with the ground station @@ -71,8 +74,6 @@ void Sub::init_ardupilot() barometer.init(); - celsius.init(); - // Register the mavlink service callback. This will run // anytime there are more than 5ms remaining in a call to // hal.scheduler->delay. diff --git a/libraries/AP_TemperatureSensor/TSYS01.cpp b/libraries/AP_TemperatureSensor/TSYS01.cpp index ed0bf3a6d7..a11c13740d 100644 --- a/libraries/AP_TemperatureSensor/TSYS01.cpp +++ b/libraries/AP_TemperatureSensor/TSYS01.cpp @@ -13,9 +13,9 @@ static const uint8_t TSYS01_CMD_READ_PROM = 0xA0; static const uint8_t TSYS01_CMD_CONVERT = 0x40; static const uint8_t TSYS01_CMD_READ_ADC = 0x00; -bool TSYS01::init() +bool TSYS01::init(uint8_t bus) { - _dev = std::move(hal.i2c_mgr->get_device(1, TSYS01_ADDR)); + _dev = std::move(hal.i2c_mgr->get_device(bus, TSYS01_ADDR)); if (!_dev) { printf("TSYS01 device is null!"); return false; diff --git a/libraries/AP_TemperatureSensor/TSYS01.h b/libraries/AP_TemperatureSensor/TSYS01.h index 2d1556adf2..5c19234f8a 100644 --- a/libraries/AP_TemperatureSensor/TSYS01.h +++ b/libraries/AP_TemperatureSensor/TSYS01.h @@ -13,7 +13,7 @@ class TSYS01 { public: - bool init(void); + 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