mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL_SITL: simulated i2c support
This commit is contained in:
parent
0303c5c4a8
commit
2319638dd2
@ -6,6 +6,8 @@ class Scheduler;
|
||||
class SITL_State;
|
||||
class Storage;
|
||||
class AnalogIn;
|
||||
class I2CDevice;
|
||||
class I2CDeviceManager;
|
||||
class RCInput;
|
||||
class RCOutput;
|
||||
class ADCSource;
|
||||
|
@ -13,6 +13,7 @@
|
||||
#include "Scheduler.h"
|
||||
#include "AnalogIn.h"
|
||||
#include "UARTDriver.h"
|
||||
#include "I2CDevice.h"
|
||||
#include "Storage.h"
|
||||
#include "RCInput.h"
|
||||
#include "RCOutput.h"
|
||||
@ -40,7 +41,6 @@ static DSP dspDriver;
|
||||
|
||||
|
||||
// use the Empty HAL for hardware we don't emulate
|
||||
static Empty::I2CDeviceManager i2c_mgr_instance;
|
||||
static Empty::SPIDeviceManager emptySPI;
|
||||
static Empty::OpticalFlow emptyOpticalFlow;
|
||||
static Empty::Flash emptyFlash;
|
||||
@ -54,6 +54,8 @@ static UARTDriver sitlUart5Driver(5, &sitlState);
|
||||
static UARTDriver sitlUart6Driver(6, &sitlState);
|
||||
static UARTDriver sitlUart7Driver(7, &sitlState);
|
||||
|
||||
static I2CDeviceManager i2c_mgr_instance;
|
||||
|
||||
static Util utilInstance(&sitlState);
|
||||
|
||||
HAL_SITL::HAL_SITL() :
|
||||
|
204
libraries/AP_HAL_SITL/I2CDevice.cpp
Normal file
204
libraries/AP_HAL_SITL/I2CDevice.cpp
Normal file
@ -0,0 +1,204 @@
|
||||
/*
|
||||
* Copyright (C) 2020 Peter Barker. All rights reserved.
|
||||
*
|
||||
* This file is free software: you can redistribute it and/or modify it
|
||||
* under the terms of the GNU General Public License as published by the
|
||||
* Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This file is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#include "I2CDevice.h"
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <SITL/SITL.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
using namespace HALSITL;
|
||||
|
||||
/*
|
||||
* I2CBus
|
||||
*/
|
||||
class I2CBus {
|
||||
friend class I2CDeviceManager;
|
||||
public:
|
||||
uint8_t bus;
|
||||
Semaphore sem;
|
||||
int ioctl(uint8_t ioctl_number, void *data) {
|
||||
return _ioctl(ioctl_number, data);
|
||||
}
|
||||
void _timer_tick(); // in lieu of a thread-per-bus
|
||||
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb);
|
||||
|
||||
private:
|
||||
int _ioctl(uint8_t ioctl_number, void *data);
|
||||
|
||||
struct callback_info {
|
||||
struct callback_info *next;
|
||||
AP_HAL::Device::PeriodicCb cb;
|
||||
uint32_t period_usec;
|
||||
uint64_t next_usec;
|
||||
} *callbacks;
|
||||
};
|
||||
|
||||
int I2CBus::_ioctl(uint8_t ioctl_number, void *data)
|
||||
{
|
||||
SITL::SITL *sitl = AP::sitl();
|
||||
return sitl->i2c_ioctl(ioctl_number, data);
|
||||
}
|
||||
|
||||
AP_HAL::Device::PeriodicHandle I2CBus::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
|
||||
{
|
||||
// mostly swiped from ChibiOS:
|
||||
I2CBus::callback_info *callback = new I2CBus::callback_info;
|
||||
if (callback == nullptr) {
|
||||
return nullptr;
|
||||
}
|
||||
callback->cb = cb;
|
||||
callback->period_usec = period_usec;
|
||||
callback->next_usec = AP_HAL::micros64() + period_usec;
|
||||
|
||||
// add to linked list of callbacks on thread
|
||||
callback->next = callbacks;
|
||||
callbacks = callback;
|
||||
return callback;
|
||||
}
|
||||
|
||||
void I2CBus::_timer_tick()
|
||||
{
|
||||
const uint64_t now = AP_HAL::micros64();
|
||||
for (struct callback_info *ci = callbacks; ci != nullptr; ci = ci->next) {
|
||||
if (ci->next_usec >= now) {
|
||||
ci->cb();
|
||||
ci->next_usec += ci->period_usec;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* I2CDeviceManager
|
||||
*/
|
||||
|
||||
I2CBus I2CDeviceManager::buses[NUM_SITL_I2C_BUSES];
|
||||
|
||||
I2CDeviceManager::I2CDeviceManager()
|
||||
{
|
||||
}
|
||||
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice>
|
||||
I2CDeviceManager::get_device(uint8_t bus,
|
||||
uint8_t address,
|
||||
uint32_t bus_clock,
|
||||
bool use_smbus,
|
||||
uint32_t timeout_ms)
|
||||
{
|
||||
if (bus >= ARRAY_SIZE(buses)) {
|
||||
return AP_HAL::OwnPtr<AP_HAL::I2CDevice>(nullptr);
|
||||
}
|
||||
auto dev = AP_HAL::OwnPtr<AP_HAL::I2CDevice>(new I2CDevice(buses[bus], address));
|
||||
return dev;
|
||||
}
|
||||
|
||||
void I2CDeviceManager::_timer_tick()
|
||||
{
|
||||
for (auto bus : buses) {
|
||||
bus._timer_tick();
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* I2CDevice
|
||||
*/
|
||||
|
||||
I2CDevice::I2CDevice(I2CBus &bus, uint8_t address)
|
||||
: _bus(bus)
|
||||
, _address(address)
|
||||
{
|
||||
set_device_bus(bus.bus);
|
||||
set_device_address(address);
|
||||
}
|
||||
|
||||
#include <stdio.h>
|
||||
|
||||
#include <signal.h>
|
||||
|
||||
bool I2CDevice::transfer(const uint8_t *send, uint32_t send_len,
|
||||
uint8_t *recv, uint32_t recv_len)
|
||||
{
|
||||
// kill(0, SIGTRAP);
|
||||
// combined transfer
|
||||
if (!_transfer(send, send_len, recv, recv_len)) {
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
bool I2CDevice::_transfer(const uint8_t *send, uint32_t send_len,
|
||||
uint8_t *recv, uint32_t recv_len)
|
||||
{
|
||||
struct i2c_msg msgs[2] = { };
|
||||
unsigned nmsgs = 0;
|
||||
|
||||
if (send && send_len != 0) {
|
||||
msgs[nmsgs].addr = _address;
|
||||
msgs[nmsgs].flags = 0;
|
||||
msgs[nmsgs].buf = const_cast<uint8_t*>(send);
|
||||
msgs[nmsgs].len = send_len;
|
||||
nmsgs++;
|
||||
}
|
||||
|
||||
if (recv && recv_len != 0) {
|
||||
msgs[nmsgs].addr = _address;
|
||||
msgs[nmsgs].flags = I2C_M_RD;
|
||||
msgs[nmsgs].buf = recv;
|
||||
msgs[nmsgs].len = recv_len;
|
||||
nmsgs++;
|
||||
}
|
||||
|
||||
/* interpret it as an input error if nothing has to be done */
|
||||
if (!nmsgs) {
|
||||
return false;
|
||||
}
|
||||
|
||||
struct i2c_rdwr_ioctl_data i2c_data = { };
|
||||
|
||||
i2c_data.msgs = msgs;
|
||||
i2c_data.nmsgs = nmsgs;
|
||||
|
||||
int r;
|
||||
unsigned retries = _retries;
|
||||
do {
|
||||
r = _bus.ioctl(I2C_RDWR, &i2c_data);
|
||||
} while (r == -1 && retries-- > 0);
|
||||
|
||||
return r != -1;
|
||||
}
|
||||
|
||||
bool I2CDevice::read_registers_multiple(uint8_t first_reg, uint8_t *recv,
|
||||
uint32_t recv_len, uint8_t times)
|
||||
{
|
||||
::fprintf(stderr, "read_registers_multiple called\n");
|
||||
return false;
|
||||
}
|
||||
|
||||
AP_HAL::Semaphore *I2CDevice::get_semaphore() {
|
||||
return &_bus.sem;
|
||||
}
|
||||
|
||||
AP_HAL::Device::PeriodicHandle I2CDevice::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
|
||||
{
|
||||
return _bus.register_periodic_callback(period_usec, cb);
|
||||
}
|
||||
|
||||
bool I2CDevice::adjust_periodic_callback(Device::PeriodicHandle h, uint32_t period_usec)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
127
libraries/AP_HAL_SITL/I2CDevice.h
Normal file
127
libraries/AP_HAL_SITL/I2CDevice.h
Normal file
@ -0,0 +1,127 @@
|
||||
/*
|
||||
* Copyright (C) 2020 Peter Barker. All rights reserved.
|
||||
*
|
||||
* This file is free software: you can redistribute it and/or modify it
|
||||
* under the terms of the GNU General Public License as published by the
|
||||
* Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This file is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <inttypes.h>
|
||||
|
||||
#include <AP_HAL/HAL.h>
|
||||
#include <AP_HAL/I2CDevice.h>
|
||||
#include <AP_HAL/utility/OwnPtr.h>
|
||||
|
||||
#include "AP_HAL_SITL_Namespace.h"
|
||||
#include "Semaphores.h"
|
||||
|
||||
class I2CBus;
|
||||
|
||||
class HALSITL::I2CDevice : public AP_HAL::I2CDevice {
|
||||
public:
|
||||
static I2CDevice *from(AP_HAL::I2CDevice *dev) {
|
||||
return static_cast<I2CDevice*>(dev);
|
||||
}
|
||||
|
||||
/* AP_HAL::I2CDevice implementation */
|
||||
|
||||
I2CDevice(I2CBus &bus, uint8_t address);
|
||||
|
||||
~I2CDevice() {}
|
||||
|
||||
/* See AP_HAL::I2CDevice::set_address() */
|
||||
void set_address(uint8_t address) override { _address = address; }
|
||||
|
||||
/* See AP_HAL::I2CDevice::set_retries() */
|
||||
void set_retries(uint8_t retries) override { _retries = retries; }
|
||||
|
||||
/* AP_HAL::Device implementation */
|
||||
|
||||
/* See AP_HAL::Device::set_speed(): Empty implementation, not supported. */
|
||||
bool set_speed(enum Device::Speed speed) override { return true; }
|
||||
|
||||
/* See AP_HAL::Device::transfer() */
|
||||
bool transfer(const uint8_t *send, uint32_t send_len,
|
||||
uint8_t *recv, uint32_t recv_len) override;
|
||||
|
||||
bool read_registers_multiple(uint8_t first_reg, uint8_t *recv,
|
||||
uint32_t recv_len, uint8_t times) override;
|
||||
|
||||
/* See AP_HAL::Device::get_semaphore() */
|
||||
AP_HAL::Semaphore *get_semaphore() override;
|
||||
|
||||
/* See AP_HAL::Device::register_periodic_callback() */
|
||||
AP_HAL::Device::PeriodicHandle register_periodic_callback(
|
||||
uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;
|
||||
|
||||
/* See AP_HAL::Device::adjust_periodic_callback() */
|
||||
bool adjust_periodic_callback(
|
||||
AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) override;
|
||||
|
||||
/* set split transfers flag */
|
||||
void set_split_transfers(bool set) override {
|
||||
_split_transfers = set;
|
||||
}
|
||||
|
||||
static void sitl_update();
|
||||
|
||||
// the following must be identical to the structure in SITL/SIM_I2C.h!
|
||||
#define I2C_M_RD 1
|
||||
#define I2C_RDWR 0
|
||||
struct i2c_msg {
|
||||
uint8_t addr;
|
||||
uint8_t flags;
|
||||
uint8_t *buf;
|
||||
uint16_t len; // FIXME: what type should this be?
|
||||
};
|
||||
struct i2c_rdwr_ioctl_data {
|
||||
i2c_msg *msgs;
|
||||
uint8_t nmsgs;
|
||||
};
|
||||
// end "the following"
|
||||
|
||||
protected:
|
||||
I2CBus &_bus;
|
||||
uint8_t _address;
|
||||
uint8_t _retries;
|
||||
bool _split_transfers = false;
|
||||
|
||||
bool _transfer(const uint8_t *send, uint32_t send_len,
|
||||
uint8_t *recv, uint32_t recv_len);
|
||||
};
|
||||
|
||||
class HALSITL::I2CDeviceManager : public AP_HAL::I2CDeviceManager {
|
||||
public:
|
||||
friend class I2CDevice;
|
||||
|
||||
static I2CDeviceManager *from(AP_HAL::I2CDeviceManager *i2c_mgr)
|
||||
{
|
||||
return static_cast<I2CDeviceManager*>(i2c_mgr);
|
||||
}
|
||||
|
||||
I2CDeviceManager();
|
||||
~I2CDeviceManager() {};
|
||||
|
||||
void _timer_tick(); // in lieu of a thread-per-bus
|
||||
|
||||
/* AP_HAL::I2CDeviceManager implementation */
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> get_device(uint8_t bus, uint8_t address,
|
||||
uint32_t bus_clock=400000,
|
||||
bool use_smbus = false,
|
||||
uint32_t timeout_ms=4) override;
|
||||
|
||||
protected:
|
||||
|
||||
#define NUM_SITL_I2C_BUSES 4
|
||||
static I2CBus buses[];
|
||||
};
|
@ -95,6 +95,7 @@ void SITL_State::_sitl_setup(const char *home_str)
|
||||
sitl_model->set_gripper_epm(&_sitl->gripper_epm_sim);
|
||||
sitl_model->set_parachute(&_sitl->parachute_sim);
|
||||
sitl_model->set_precland(&_sitl->precland_sim);
|
||||
sitl_model->set_i2c(&_sitl->i2c_sim);
|
||||
|
||||
if (_use_fg_view) {
|
||||
fg_socket.connect(_fg_address, _fg_view_port);
|
||||
|
@ -1,6 +1,7 @@
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#include "AP_HAL_SITL.h"
|
||||
#include <AP_HAL_SITL/I2CDevice.h>
|
||||
#include "Scheduler.h"
|
||||
#include "UARTDriver.h"
|
||||
#include <sys/time.h>
|
||||
@ -240,6 +241,9 @@ void Scheduler::_run_io_procs()
|
||||
hal.uartH->_timer_tick();
|
||||
hal.storage->_timer_tick();
|
||||
|
||||
// in lieu of a thread-per-bus:
|
||||
((HALSITL::I2CDeviceManager*)(hal.i2c_mgr))->_timer_tick();
|
||||
|
||||
#if SITL_STACK_CHECKING_ENABLED
|
||||
check_thread_stacks();
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user