Skip to content

Commit

Permalink
Merge remote-tracking branch 'upstream/development' into osd_temperature
Browse files Browse the repository at this point in the history
  • Loading branch information
nmaggioni committed Nov 5, 2018
2 parents 36efa70 + 138b6f6 commit a7e4e0f
Show file tree
Hide file tree
Showing 65 changed files with 2,139 additions and 1,700 deletions.
92 changes: 92 additions & 0 deletions docs/Board - MatekF722-SE.md
@@ -0,0 +1,92 @@
# Board - Matek F722-SE

Full details on the MATEKSYS F722-SE can be found on the Matek Website: [mateksys.com/?portfolio=f722-se](http://www.mateksys.com/?portfolio=f722-se). INAV Target: `MATEKF722SE`

## Hardware Specs

* *Mass:* ~10g
* *PCB Size:* 36x46mm
* 30x30mm Hole pattern (M4 size, M3 size with rubber isolators)

### FC Specs

* Processors and Sensors
* *MCU:* STM32F722RET6
* *IMU:* MPU6000(Gyro1) & ICM20602(Gyro2) connected via SPI1
* *Baro:* BMP280 (connected via I2C1)
* *OSD:* BetaFlight OSD (AT7456E connected via SPI2)
* *Blackbox:* MicroSD card slot (connected via SPI3)
* 5 UARTs
* 8 PWM/Dshot outputs
* 2 PINIO definition (VTX power switcher/user1 and 2 camera switcher/user2)

### Integrated PDB Specs

* *Input:* 6-36v (3-8S LiPo) w/TVS protection
* *ESC Pads:* Rated 4x30A per ESC pad set (4x46A burst)
* Voltage Regulators:
* *5v BEC:* 2A continuous load (3A burst)
* *3.3v LDO:* max load: 200mA
* Power Sense:
* *Current Sensor:* Rated for 184A (*Suggested scale value `179`*)
* *Voltage Sensor:* 1:10 signal output ratio (*Suggested scale value `110`*)

## Status LEDs

| LED | Color | Color Codes |
|---------------:|-------|:----------------------------------------------------------------------------------------------------------|
| FC Status | Blue | **Unlit:** USB disconnected and disarmed, <br> **Lit:** USB disconnected and armed, <br> **Flashing:** USB connected and disarmed, <br> **5x Rapid Flash then Flashing:** USB connected and arming command prevented |
| Accelerometer | Green | Accelerometer status (Lit: active, Unlit: inactive) |
| 3v3 Status | Red | Red: active, Unlit: inactive |

## Pinout

Pads are organised into two large banks of pads on left and right sides of board with a couple sets of pads on the underside of the board and ESC related connections near the board corners.

```
__________
/ U U \
/-----------------------------\
|oE Eo|
|SC SC|
| |
| P P |
| A A |
| D D |
| S S |
| |
|ES ES|
|oC Co|
\------------[USB]------------/
```


| Pad Silkscreen Label | Function | Notes |
|---------------------:|---------------|:-----------------------------------------------------------------------------------------------|
| `+ / -` | Battery In | 6-30vDC LiPo Power input (*Battery +/- and 4-in-1 ESC +/- pads*) |
| `S1-S8` | ESC Out | (*1-4 near ESC power connections, 5-8 on right side*) Supports PWM, Oneshot, Multishot, DSHOT |
| `GND, S1-S4` | ESC Out | (*Rear of board*) 4-in-1 ESC Out |
| `VBT, GND` | VBT Out | VBAT power pad (*marked for VTX*), power ON/OFF can be switched via PINIO1(PC8) |
| `CURR` | Current Sense | Current Sensor I/O pin (*output from onboard sensor or input from external sensor*) |
| `5V` | | Out from internal 5v BEC (*rated 2A continuous, 3A burst*) |
| `3V3` | | Out from 3v3 regulator (*rated 200mA*) |
| `4V5` | | Out from 4v4~4v8, 0.5A (*power is also supplied when connected via USB*) |
| `G` | GND | |
| `LED` | WS2812 Signal | |
| `Bz-, 5V` | Buzzer | |
| `CL, DA` | I2C | I2C connection marked for a magnetometer but could be used for whatever |
| `VTX` | VTX | VTX: Video out |
| `C1/C2` | Camera | C1: camera-1 IN, C1: camera-2 IN, 2 camera image can be switched via PINIO2(PC9) |
| `RX1, TX1` | UART1 | |
| `TX2` | UART2-TX | |
| `RX2` | UART2-RX | RX connection for Spektrum DSMX or DSM2, FlySky iBUS, or PPM (*Disable `UART2` for PPM*) |
| `RX3, TX3` | UART3 | TX3 can be used for VTX control |
| `RX4, TX4` | UART4 | RX4 pin `PA1` can be used for camera control(PWM) |
| `TX6` | UART6-TX | |
| `RX6` | UART6-RX | (*One per board corner*) Duplicates of RX6 pad for ESC Telemetry |
| `Rssi` | RSSI | FrSky RSSI input from RX (*Rear of board*) |
| `PA4 ` | ADC/DAC | Airspeed_ADC_PIN (*Rear of board*) |
| `D+, D-. VBus` | USB pins | (*Rear of board*) |



2 changes: 2 additions & 0 deletions make/source.mk
Expand Up @@ -145,6 +145,7 @@ COMMON_SRC = \
drivers/opflow/opflow_virtual.c \
drivers/vtx_common.c \
io/rangefinder_msp.c \
io/rangefinder_benewake.c \
io/opflow_cxof.c \
io/opflow_msp.c \
io/dashboard.c \
Expand Down Expand Up @@ -204,6 +205,7 @@ endif
ifneq ($(filter SDCARD,$(FEATURES)),)
TARGET_SRC += \
drivers/sdcard.c \
drivers/sdcard_spi.c \
drivers/sdcard_standard.c \
io/asyncfatfs/asyncfatfs.c \
io/asyncfatfs/fat_standard.c
Expand Down
51 changes: 41 additions & 10 deletions src/main/drivers/bus.c
Expand Up @@ -47,6 +47,7 @@ static void busDevPreInit_SPI(const busDeviceDescriptor_t * descriptor)
static void busDevPreInit(const busDeviceDescriptor_t * descriptor)
{
switch (descriptor->busType) {
default:
case BUSTYPE_NONE:
break;

Expand Down Expand Up @@ -121,6 +122,7 @@ busDevice_t * busDeviceInit(busType_e bus, devHardwareType_e hw, uint8_t tag, re

if (dev) {
switch (descriptor->busType) {
default:
case BUSTYPE_NONE:
return NULL;

Expand Down Expand Up @@ -180,6 +182,7 @@ void busSetSpeed(const busDevice_t * dev, busSpeed_e speed)
UNUSED(speed);

switch (dev->busType) {
default:
case BUSTYPE_NONE:
// Not available
break;
Expand Down Expand Up @@ -212,16 +215,7 @@ void * busDeviceGetScratchpadMemory(const busDevice_t * dev)
bool busTransfer(const busDevice_t * dev, uint8_t * rxBuf, const uint8_t * txBuf, int length)
{
#ifdef USE_SPI
// busTransfer function is only supported on SPI bus
if (dev->busType == BUSTYPE_SPI) {
busTransferDescriptor_t dsc = {
.rxBuf = rxBuf,
.txBuf = txBuf,
.length = length
};

return spiBusTransferMultiple(dev, &dsc, 1);
}
return spiBusTransfer(dev, rxBuf, txBuf, length);
#else
UNUSED(dev);
UNUSED(rxBuf);
Expand Down Expand Up @@ -355,3 +349,40 @@ bool busRead(const busDevice_t * dev, uint8_t reg, uint8_t * data)
return false;
}
}

void busSelectDevice(const busDevice_t * dev)
{
#ifdef USE_SPI
if (dev->busType == BUSTYPE_SPI && (dev->flags & DEVFLAGS_USE_MANUAL_DEVICE_SELECT)) {
spiBusSelectDevice(dev);
}
#endif
}

void busDeselectDevice(const busDevice_t * dev)
{
#ifdef USE_SPI
if (dev->busType == BUSTYPE_SPI && (dev->flags & DEVFLAGS_USE_MANUAL_DEVICE_SELECT)) {
spiBusDeselectDevice(dev);
}
#endif
}

bool busIsBusy(const busDevice_t * dev)
{
switch (dev->busType) {
case BUSTYPE_SPI:
#ifdef USE_SPI
return spiBusIsBusy(dev);
#else
return false;
#endif

case BUSTYPE_I2C:
// Not implemented for I2C, respond as always free
return false;

default:
return false;
}
}
26 changes: 23 additions & 3 deletions src/main/drivers/bus.h
Expand Up @@ -59,9 +59,17 @@ typedef enum {
BUSTYPE_ANY = 0,
BUSTYPE_NONE = 0,
BUSTYPE_I2C = 1,
BUSTYPE_SPI = 2
BUSTYPE_SPI = 2,
BUSTYPE_SDIO = 3,
} busType_e;

typedef enum {
BUSINDEX_1 = 0,
BUSINDEX_2 = 1,
BUSINDEX_3 = 2,
BUSINDEX_4 = 3
} busIndex_e;

/* Ultimately all hardware descriptors will go to target definition files.
* Driver code will merely query for it's HW descriptor and initialize it */
typedef enum {
Expand Down Expand Up @@ -118,11 +126,14 @@ typedef enum {
DEVHW_PCA9685, // PWM output device
DEVHW_M25P16, // SPI NOR flash
DEVHW_UG2864, // I2C OLED display
DEVHW_SDCARD, // Generic SD-Card
} devHardwareType_e;

typedef enum {
DEVFLAGS_NONE = 0,
DEVFLAGS_USE_RAW_REGISTERS = (1 << 0), // Don't manipulate MSB for R/W selection
DEVFLAGS_USE_RAW_REGISTERS = (1 << 0), // Don't manipulate MSB for R/W selection
DEVFLAGS_USE_MANUAL_DEVICE_SELECT = (1 << 1), // (SPI only) Don't automatically select/deselect device
DEVFLAGS_SPI_MODE_0 = (1 << 2), // (SPI only) Use CPOL=0/CPHA=0 (if unset MODE3 is used - CPOL=1/CPHA=1)
} deviceFlags_e;

typedef struct busDeviceDescriptor_s {
Expand Down Expand Up @@ -244,13 +255,16 @@ bool i2cBusWriteRegister(const busDevice_t * dev, uint8_t reg, uint8_t data);
bool i2cBusReadBuffer(const busDevice_t * dev, uint8_t reg, uint8_t * data, uint8_t length);
bool i2cBusReadRegister(const busDevice_t * dev, uint8_t reg, uint8_t * data);


bool spiBusIsBusy(const busDevice_t * dev);
void spiBusSetSpeed(const busDevice_t * dev, busSpeed_e speed);
bool spiBusTransfer(const busDevice_t * dev, uint8_t * rxBuf, const uint8_t * txBuf, int length);
bool spiBusTransferMultiple(const busDevice_t * dev, busTransferDescriptor_t * dsc, int count);
bool spiBusWriteBuffer(const busDevice_t * dev, uint8_t reg, const uint8_t * data, uint8_t length);
bool spiBusWriteRegister(const busDevice_t * dev, uint8_t reg, uint8_t data);
bool spiBusReadBuffer(const busDevice_t * dev, uint8_t reg, uint8_t * data, uint8_t length);
bool spiBusReadRegister(const busDevice_t * dev, uint8_t reg, uint8_t * data);
void spiBusSelectDevice(const busDevice_t * dev);
void spiBusDeselectDevice(const busDevice_t * dev);

/* Pre-initialize all known device descriptors to make sure hardware state is consistent and known
* Initialize bus hardware */
Expand All @@ -267,10 +281,16 @@ void * busDeviceGetScratchpadMemory(const busDevice_t * dev);

void busSetSpeed(const busDevice_t * dev, busSpeed_e speed);

/* Select/Deselect device will allow code to do something during device transfer or do transfer in chunks over some time */
void busSelectDevice(const busDevice_t * dev);
void busDeselectDevice(const busDevice_t * dev);

bool busWriteBuf(const busDevice_t * busdev, uint8_t reg, const uint8_t * data, uint8_t length);
bool busReadBuf(const busDevice_t * busdev, uint8_t reg, uint8_t * data, uint8_t length);
bool busRead(const busDevice_t * busdev, uint8_t reg, uint8_t * data);
bool busWrite(const busDevice_t * busdev, uint8_t reg, uint8_t data);

bool busTransfer(const busDevice_t * dev, uint8_t * rxBuf, const uint8_t * txBuf, int length);
bool busTransferMultiple(const busDevice_t * dev, busTransferDescriptor_t * buffers, int count);

bool busIsBusy(const busDevice_t * dev);

0 comments on commit a7e4e0f

Please sign in to comment.