From 437e0e645984da937b9071a6c67c260919761740 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 13 Jul 2021 11:37:14 +1000 Subject: [PATCH] SITL: add simulated SPI devices --- libraries/SITL/SIM_SPI.cpp | 93 ++++++++++++++++++++++++++++++++++ libraries/SITL/SIM_SPI.h | 61 ++++++++++++++++++++++ libraries/SITL/SIM_SPIDevice.h | 18 +++++++ libraries/SITL/SITL.h | 7 ++- 4 files changed, 178 insertions(+), 1 deletion(-) create mode 100644 libraries/SITL/SIM_SPI.cpp create mode 100644 libraries/SITL/SIM_SPI.h create mode 100644 libraries/SITL/SIM_SPIDevice.h diff --git a/libraries/SITL/SIM_SPI.cpp b/libraries/SITL/SIM_SPI.cpp new file mode 100644 index 0000000000..c49201f678 --- /dev/null +++ b/libraries/SITL/SIM_SPI.cpp @@ -0,0 +1,93 @@ +/* + This program 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 program 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 . + */ +/* + Simulated spi buses and devices +*/ + + +#include +#include + +#include "SIM_SPI.h" + +#include + +using namespace SITL; + +struct spi_device_at_cs_pin { + uint8_t bus; + uint8_t cs_pin; + SPIDevice &device; +} spi_devices[] { +}; + +void SPI::init() +{ + for (auto &i : spi_devices) { + i.device.init(); + } + + // sanity check the spi_devices structure to ensure we don't have + // two devices at the same address on the same bus: + for (uint8_t i=0; i. + */ + +/* + Simulated spi buses and devices +*/ + +#pragma once + +#include + +#include "stdint.h" + +namespace SITL { + +class SPI { +public: + SPI() {} + + void init(); + + // update spi state + void update(const class Aircraft &aircraft); + + int ioctl(uint8_t bus, uint8_t cs_pin, uint8_t ioctl_type, void *data); + + // the following must be identical to AP_HAL_SITL/SPIDevice.h + struct spi_ioc_transfer { + uint64_t tx_buf; + uint64_t rx_buf; + + uint32_t len; + // uint32_t speed_hz; + + // uint16_t delay_usecs; + // uint8_t bits_per_word; + // uint8_t cs_change; + }; + +#define SPI_TRANSACTION_1LONG 17 +#define SPI_TRANSACTION_2LONG 18 + // end "the following" + +private: + int ioctl_transaction(uint8_t bus, uint8_t cs_pin, uint8_t count, spi_ioc_transfer *data); + +}; + +} diff --git a/libraries/SITL/SIM_SPIDevice.h b/libraries/SITL/SIM_SPIDevice.h new file mode 100644 index 0000000000..5a0e8fdf82 --- /dev/null +++ b/libraries/SITL/SIM_SPIDevice.h @@ -0,0 +1,18 @@ +#pragma once + +#include "SIM_SPI.h" + +#include + +namespace SITL { + +class SPIDevice { +public: + virtual void init() {} + + virtual void update(const class Aircraft &aircraft) { } + + virtual int rdwr(uint8_t count, SPI::spi_ioc_transfer *&data) = 0; +}; + +} // namespace SITL diff --git a/libraries/SITL/SITL.h b/libraries/SITL/SITL.h index 53715b5eee..03aa762da5 100644 --- a/libraries/SITL/SITL.h +++ b/libraries/SITL/SITL.h @@ -14,6 +14,7 @@ #include "SIM_Gripper_EPM.h" #include "SIM_Gripper_Servo.h" #include "SIM_I2C.h" +#include "SIM_SPI.h" #include "SIM_Parachute.h" #include "SIM_Precland.h" #include "SIM_Sprayer.h" @@ -404,6 +405,10 @@ public: return i2c_sim.ioctl(i2c_operation, data); } + int spi_ioctl(uint8_t bus, uint8_t cs_pin, uint8_t spi_operation, void *data) { + return spi_sim.ioctl(bus, cs_pin, spi_operation, data); + } + Sprayer sprayer_sim; // simulated ship takeoffs @@ -415,6 +420,7 @@ public: Parachute parachute_sim; Buzzer buzzer_sim; I2C i2c_sim; + SPI spi_sim; ToneAlarm tonealarm_sim; SIM_Precland precland_sim; RichenPower richenpower_sim; @@ -476,7 +482,6 @@ public: // Master instance to use servos from with slave instances AP_Int8 ride_along_master; - }; } // namespace SITL