mirror of https://github.com/ArduPilot/ardupilot
SITL: add simulated SPI devices
This commit is contained in:
parent
58a7f022fd
commit
437e0e6459
|
@ -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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
/*
|
||||
Simulated spi buses and devices
|
||||
*/
|
||||
|
||||
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#include <SITL/SITL.h>
|
||||
|
||||
#include "SIM_SPI.h"
|
||||
|
||||
#include <signal.h>
|
||||
|
||||
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<ARRAY_SIZE(spi_devices)-1; i++) {
|
||||
const auto &dev_i = spi_devices[i];
|
||||
for (uint8_t j=i+1; j<ARRAY_SIZE(spi_devices); j++) {
|
||||
const auto &dev_j = spi_devices[j];
|
||||
if (dev_i.bus == dev_j.bus &&
|
||||
dev_i.cs_pin == dev_j.cs_pin) {
|
||||
AP_HAL::panic("Two devices on the same cs_pin on the same bus");
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void SPI::update(const class Aircraft &aircraft)
|
||||
{
|
||||
for (auto daa : spi_devices) {
|
||||
daa.device.update(aircraft);
|
||||
}
|
||||
}
|
||||
|
||||
int SPI::ioctl_transaction(uint8_t bus, uint8_t cs_pin, uint8_t count, spi_ioc_transfer *data)
|
||||
{
|
||||
for (auto &dev_at_cs_pin : spi_devices) {
|
||||
if (dev_at_cs_pin.cs_pin != cs_pin) {
|
||||
continue;
|
||||
}
|
||||
if (dev_at_cs_pin.bus != bus) {
|
||||
continue;
|
||||
}
|
||||
return dev_at_cs_pin.device.rdwr(count, data);
|
||||
}
|
||||
::fprintf(stderr, "Unhandled spi message: bus=%u cs_pin=%u\n", bus, cs_pin);
|
||||
return -1;
|
||||
}
|
||||
|
||||
int SPI::ioctl(uint8_t bus, uint8_t cs_pin, uint8_t ioctl_type, void *data)
|
||||
{
|
||||
uint8_t count;
|
||||
switch (ioctl_type) {
|
||||
case SPI_TRANSACTION_1LONG:
|
||||
count = 1;
|
||||
break;
|
||||
case SPI_TRANSACTION_2LONG:
|
||||
count = 2;
|
||||
break;
|
||||
default:
|
||||
AP_HAL::panic("Bad transaction type");
|
||||
}
|
||||
|
||||
return ioctl_transaction(bus, cs_pin, count, (spi_ioc_transfer*)data);
|
||||
}
|
|
@ -0,0 +1,61 @@
|
|||
/*
|
||||
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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
/*
|
||||
Simulated spi buses and devices
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <AP_Param/AP_Param.h>
|
||||
|
||||
#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);
|
||||
|
||||
};
|
||||
|
||||
}
|
|
@ -0,0 +1,18 @@
|
|||
#pragma once
|
||||
|
||||
#include "SIM_SPI.h"
|
||||
|
||||
#include <SITL/SIM_Aircraft.h>
|
||||
|
||||
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
|
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue