diff --git a/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp b/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp index c157472f8c..8a7537ab97 100644 --- a/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp +++ b/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp @@ -64,11 +64,11 @@ static UARTDriver sitlUart7Driver(7, &sitlState); static UARTDriver sitlUart8Driver(8, &sitlState); static UARTDriver sitlUart9Driver(9, &sitlState); +static I2CDeviceManager i2c_mgr_instance; + #if defined(HAL_BUILD_AP_PERIPH) -static Empty::I2CDeviceManager i2c_mgr_instance; static Empty::SPIDeviceManager spi_mgr_instance; #else -static I2CDeviceManager i2c_mgr_instance; static SPIDeviceManager spi_mgr_instance; #endif static Util utilInstance(&sitlState); diff --git a/libraries/AP_HAL_SITL/I2CDevice.cpp b/libraries/AP_HAL_SITL/I2CDevice.cpp index e4f789ffe0..7b7b2d5914 100644 --- a/libraries/AP_HAL_SITL/I2CDevice.cpp +++ b/libraries/AP_HAL_SITL/I2CDevice.cpp @@ -17,7 +17,7 @@ #include "I2CDevice.h" #include -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(HAL_BUILD_AP_PERIPH) +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include @@ -217,4 +217,4 @@ bool I2CDevice::adjust_periodic_callback(Device::PeriodicHandle h, uint32_t peri return false; } -#endif //#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(HAL_BUILD_AP_PERIPH) +#endif //#if CONFIG_HAL_BOARD == HAL_BOARD_SITL diff --git a/libraries/AP_HAL_SITL/I2CDevice.h b/libraries/AP_HAL_SITL/I2CDevice.h index 2a414bcf69..828fd3efd4 100644 --- a/libraries/AP_HAL_SITL/I2CDevice.h +++ b/libraries/AP_HAL_SITL/I2CDevice.h @@ -19,7 +19,7 @@ #include #include -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(HAL_BUILD_AP_PERIPH) +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include #include @@ -128,4 +128,4 @@ protected: #define NUM_SITL_I2C_BUSES 4 static I2CBus buses[]; }; -#endif //#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(HAL_BUILD_AP_PERIPH) +#endif //#if CONFIG_HAL_BOARD == HAL_BOARD_SITL diff --git a/libraries/AP_HAL_SITL/SITL_Periph_State.cpp b/libraries/AP_HAL_SITL/SITL_Periph_State.cpp index c53f84623f..a4bf8cfa1c 100644 --- a/libraries/AP_HAL_SITL/SITL_Periph_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_Periph_State.cpp @@ -117,6 +117,9 @@ void SITL_State::init(int argc, char * const argv[]) { sitl_model = new SimMCast(""); _sitl = AP::sitl(); + + _sitl->i2c_sim.init(); + sitl_model->set_i2c(&_sitl->i2c_sim); } void SITL_State::wait_clock(uint64_t wait_time_usec) @@ -285,6 +288,12 @@ SimMCast::SimMCast(const char *frame_str) : void SimMCast::update(const struct sitl_input &input) { multicast_read(); + update_external_payload(input); + + auto *_sitl = AP::sitl(); + if (_sitl != nullptr) { + battery_voltage = _sitl->batt_voltage; + } } #endif //CONFIG_HAL_BOARD == HAL_BOARD_SITL && defined(HAL_BUILD_AP_PERIPH) diff --git a/libraries/AP_HAL_SITL/SITL_Periph_State.h b/libraries/AP_HAL_SITL/SITL_Periph_State.h index 17bf1c8615..e519c84c53 100644 --- a/libraries/AP_HAL_SITL/SITL_Periph_State.h +++ b/libraries/AP_HAL_SITL/SITL_Periph_State.h @@ -51,7 +51,7 @@ class HALSITL::SITL_State : public SITL_State_Common { friend class HALSITL::Util; friend class HALSITL::GPIO; public: - void init(int argc, char * const argv[]); + void init(int argc, char * const argv[]) override; bool use_rtscts(void) const { return _use_rtscts; diff --git a/libraries/AP_HAL_SITL/SITL_State.h b/libraries/AP_HAL_SITL/SITL_State.h index 1bb57e161b..8ca5afd452 100644 --- a/libraries/AP_HAL_SITL/SITL_State.h +++ b/libraries/AP_HAL_SITL/SITL_State.h @@ -17,7 +17,7 @@ class HALSITL::SITL_State : public SITL_State_Common { friend class HALSITL::Util; friend class HALSITL::GPIO; public: - void init(int argc, char * const argv[]); + void init(int argc, char * const argv[]) override; void loop_hook(void); uint16_t base_port(void) const { diff --git a/libraries/AP_HAL_SITL/SITL_State_common.h b/libraries/AP_HAL_SITL/SITL_State_common.h index 1d4555ccd9..b1105ecc35 100644 --- a/libraries/AP_HAL_SITL/SITL_State_common.h +++ b/libraries/AP_HAL_SITL/SITL_State_common.h @@ -73,7 +73,7 @@ class HALSITL::SITL_State_Common { friend class HALSITL::Util; friend class HALSITL::GPIO; public: - void init(int argc, char * const argv[]); + virtual void init(int argc, char * const argv[]) = 0; enum vehicle_type { NONE, diff --git a/libraries/AP_HAL_SITL/Scheduler.cpp b/libraries/AP_HAL_SITL/Scheduler.cpp index ba04d6af2d..2531722d71 100644 --- a/libraries/AP_HAL_SITL/Scheduler.cpp +++ b/libraries/AP_HAL_SITL/Scheduler.cpp @@ -276,10 +276,8 @@ void Scheduler::_run_io_procs() } hal.storage->_timer_tick(); -#ifndef HAL_BUILD_AP_PERIPH // in lieu of a thread-per-bus: ((HALSITL::I2CDeviceManager*)(hal.i2c_mgr))->_timer_tick(); -#endif #if SITL_STACK_CHECKING_ENABLED check_thread_stacks();