mirror of https://github.com/ArduPilot/ardupilot
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:
parent
5f5de52984
commit
18f3ab98e4
|
@ -64,11 +64,11 @@ static UARTDriver sitlUart7Driver(7, &sitlState);
|
||||||
static UARTDriver sitlUart8Driver(8, &sitlState);
|
static UARTDriver sitlUart8Driver(8, &sitlState);
|
||||||
static UARTDriver sitlUart9Driver(9, &sitlState);
|
static UARTDriver sitlUart9Driver(9, &sitlState);
|
||||||
|
|
||||||
|
static I2CDeviceManager i2c_mgr_instance;
|
||||||
|
|
||||||
#if defined(HAL_BUILD_AP_PERIPH)
|
#if defined(HAL_BUILD_AP_PERIPH)
|
||||||
static Empty::I2CDeviceManager i2c_mgr_instance;
|
|
||||||
static Empty::SPIDeviceManager spi_mgr_instance;
|
static Empty::SPIDeviceManager spi_mgr_instance;
|
||||||
#else
|
#else
|
||||||
static I2CDeviceManager i2c_mgr_instance;
|
|
||||||
static SPIDeviceManager spi_mgr_instance;
|
static SPIDeviceManager spi_mgr_instance;
|
||||||
#endif
|
#endif
|
||||||
static Util utilInstance(&sitlState);
|
static Util utilInstance(&sitlState);
|
||||||
|
|
|
@ -17,7 +17,7 @@
|
||||||
#include "I2CDevice.h"
|
#include "I2CDevice.h"
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.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>
|
#include <SITL/SITL.h>
|
||||||
|
|
||||||
|
@ -217,4 +217,4 @@ bool I2CDevice::adjust_periodic_callback(Device::PeriodicHandle h, uint32_t peri
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif //#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(HAL_BUILD_AP_PERIPH)
|
#endif //#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
|
|
|
@ -19,7 +19,7 @@
|
||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
|
|
||||||
#include <AP_HAL/HAL.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/I2CDevice.h>
|
||||||
#include <AP_HAL/utility/OwnPtr.h>
|
#include <AP_HAL/utility/OwnPtr.h>
|
||||||
|
@ -128,4 +128,4 @@ protected:
|
||||||
#define NUM_SITL_I2C_BUSES 4
|
#define NUM_SITL_I2C_BUSES 4
|
||||||
static I2CBus buses[];
|
static I2CBus buses[];
|
||||||
};
|
};
|
||||||
#endif //#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(HAL_BUILD_AP_PERIPH)
|
#endif //#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
|
|
|
@ -117,6 +117,9 @@ void SITL_State::init(int argc, char * const argv[]) {
|
||||||
sitl_model = new SimMCast("");
|
sitl_model = new SimMCast("");
|
||||||
|
|
||||||
_sitl = AP::sitl();
|
_sitl = AP::sitl();
|
||||||
|
|
||||||
|
_sitl->i2c_sim.init();
|
||||||
|
sitl_model->set_i2c(&_sitl->i2c_sim);
|
||||||
}
|
}
|
||||||
|
|
||||||
void SITL_State::wait_clock(uint64_t wait_time_usec)
|
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)
|
void SimMCast::update(const struct sitl_input &input)
|
||||||
{
|
{
|
||||||
multicast_read();
|
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)
|
#endif //CONFIG_HAL_BOARD == HAL_BOARD_SITL && defined(HAL_BUILD_AP_PERIPH)
|
||||||
|
|
|
@ -51,7 +51,7 @@ class HALSITL::SITL_State : public SITL_State_Common {
|
||||||
friend class HALSITL::Util;
|
friend class HALSITL::Util;
|
||||||
friend class HALSITL::GPIO;
|
friend class HALSITL::GPIO;
|
||||||
public:
|
public:
|
||||||
void init(int argc, char * const argv[]);
|
void init(int argc, char * const argv[]) override;
|
||||||
|
|
||||||
bool use_rtscts(void) const {
|
bool use_rtscts(void) const {
|
||||||
return _use_rtscts;
|
return _use_rtscts;
|
||||||
|
|
|
@ -17,7 +17,7 @@ class HALSITL::SITL_State : public SITL_State_Common {
|
||||||
friend class HALSITL::Util;
|
friend class HALSITL::Util;
|
||||||
friend class HALSITL::GPIO;
|
friend class HALSITL::GPIO;
|
||||||
public:
|
public:
|
||||||
void init(int argc, char * const argv[]);
|
void init(int argc, char * const argv[]) override;
|
||||||
|
|
||||||
void loop_hook(void);
|
void loop_hook(void);
|
||||||
uint16_t base_port(void) const {
|
uint16_t base_port(void) const {
|
||||||
|
|
|
@ -73,7 +73,7 @@ class HALSITL::SITL_State_Common {
|
||||||
friend class HALSITL::Util;
|
friend class HALSITL::Util;
|
||||||
friend class HALSITL::GPIO;
|
friend class HALSITL::GPIO;
|
||||||
public:
|
public:
|
||||||
void init(int argc, char * const argv[]);
|
virtual void init(int argc, char * const argv[]) = 0;
|
||||||
|
|
||||||
enum vehicle_type {
|
enum vehicle_type {
|
||||||
NONE,
|
NONE,
|
||||||
|
|
|
@ -276,10 +276,8 @@ void Scheduler::_run_io_procs()
|
||||||
}
|
}
|
||||||
hal.storage->_timer_tick();
|
hal.storage->_timer_tick();
|
||||||
|
|
||||||
#ifndef HAL_BUILD_AP_PERIPH
|
|
||||||
// in lieu of a thread-per-bus:
|
// in lieu of a thread-per-bus:
|
||||||
((HALSITL::I2CDeviceManager*)(hal.i2c_mgr))->_timer_tick();
|
((HALSITL::I2CDeviceManager*)(hal.i2c_mgr))->_timer_tick();
|
||||||
#endif
|
|
||||||
|
|
||||||
#if SITL_STACK_CHECKING_ENABLED
|
#if SITL_STACK_CHECKING_ENABLED
|
||||||
check_thread_stacks();
|
check_thread_stacks();
|
||||||
|
|
Loading…
Reference in New Issue