HAL_SITL: allow for I2C simulated devices in SITL AP_Periph

this allows for SMBbus batteries and other I2C simulated devices
This commit is contained in:
Andrew Tridgell 2023-09-28 09:34:22 +10:00
parent 5f5de52984
commit 18f3ab98e4
8 changed files with 18 additions and 11 deletions

View File

@ -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);

View File

@ -17,7 +17,7 @@
#include "I2CDevice.h"
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(HAL_BUILD_AP_PERIPH)
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <SITL/SITL.h>
@ -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

View File

@ -19,7 +19,7 @@
#include <inttypes.h>
#include <AP_HAL/HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(HAL_BUILD_AP_PERIPH)
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <AP_HAL/I2CDevice.h>
#include <AP_HAL/utility/OwnPtr.h>
@ -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

View File

@ -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)

View File

@ -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;

View File

@ -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 {

View File

@ -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,

View File

@ -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();