Skip to content

Commit

Permalink
Merge pull request #116 from rtlopez/develop
Browse files Browse the repository at this point in the history
pending release v0.2.0-RC5
  • Loading branch information
rtlopez authored May 10, 2024
2 parents 981b4e7 + 8ad0824 commit f7b76e1
Show file tree
Hide file tree
Showing 119 changed files with 6,993 additions and 5,845 deletions.
36 changes: 19 additions & 17 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,32 +2,34 @@
The mini, DIY, ~$5 cost, ESP8266/ESP32 based, high performance flight controller.

## Features
* Espressif targets (ESP32, ESP8266, ESP32-S3, ESP32-S2, ESP32-C3)
* ESC protocols (PWM, Oneshot125/42, Multishot, Brushed, Dshot150/300/600 bidirectional)
* PPM, SBUS and CRSF Receivers
* Builtin ESP-NOW receiver and WiFi configuration [read more...](/docs/wireless.md)
* SPI and I2C gyro modules support (MPU6050, MPU9250, ICM20602, BMI160)
* Flight modes (ACRO, ANGLE, AIRMODE)
* Frames (Quad X)
* Betaflight configuration tool compatible (v10.8 or v10.9)
* Receiver protocol (8 channel PPM)
* SBUS and CRSF Serial Rx protocols on ESP32 and RP2040
* ESC protocols (PWM, Oneshot125, Brushed, Dshot150, Dshot300, Dshot600)
* Configurable Gyro Filters (LPF, Notch, dTerm)
* Blackbox recording (OpenLog/Opelager serial)
* In flight PID Tuning
* Flight modes (ACRO, ANGLE, AIRMODE, ARM)
* Up to 8kHz gyro/loop on ESP32 with SPI gyro
* Betaflight configuration tool compatible (v10.8-v10.10)
* Configurable Gyro Filters (LPF, Notch, dTerm, RPM)
* Blackbox recording (OpenLog/OpenLager/Flash)
* Up to 4kHz gyro/loop on ESP32 with SPI gyro
* MSP protocol interface
* CLI Interface
* Resorce/Pin mapping
* In flight PID Tuning
* Buzzer
* Lipo voltage monitor
* Failsafe
* Failsafe mode

## Requirements
Hardware:
* ESP8266 Wemos D1 Mini or ESP32 mini board
* MPU6050 I2C gyro (GY-88, GY-91, GY-521 or similar) or MPU9250 SPI on ESP32
* ESP32 mini board or ESP8266 Wemos D1 mini or similar
* MPU9250 SPI or MPU6050 I2C gyro (GY-88, GY-91, GY-521 or similar)
* PDB with 5V BEC
* Buzzer and some electronic components (optional).

Software:
* [Betaflight Configurator](https://github.com/betaflight/betaflight-configurator/releases) (v10.8 or v10.9)
* [Betaflight Configurator](https://github.com/betaflight/betaflight-configurator/releases) (v10.10 or v10.9 or v10.8)
* [CH340 usb-serial converter driver](https://sparks.gogo.co.nz/ch340.html)

## Flashing
Expand All @@ -38,6 +40,8 @@ Software:
5. Click "Program"
6. After success power cycle board

Note: only ESP32 and ESP8266 can be flashed in this way.

![ESP-FC Flashing](/docs/images/esptool-js-flash-connect.png)

## Setup
Expand Down Expand Up @@ -75,9 +79,8 @@ Here are more details about [how to setup](/docs/setup.md).
| MSP | Yes | Yes | Yes |
| CLI | Yes | Yes | Yes |
| PPM (IN) | Yes | Yes | Yes |
| SBUS | - | Yes | Yes |
| IBUS | - | - | - |
| CRSF (ELRS) | - | Yes | Yes |
| SBUS | Yes | Yes | Yes |
| CRSF (ELRS) | Yes | Yes | Yes |
| BLACKBOX | Yes | Yes | Yes |
| PWM (OUT) | Yes | Yes | Yes |
| ONESHOT125 | Yes | Yes | Yes |
Expand Down Expand Up @@ -124,7 +127,6 @@ You can also join to our [Discord Channel](https://discord.gg/jhyPPM5UEH)
* Serial Rx (IBUS)
* ELRS telemetry
* ESP32-S2/S3/C3 targets
* BiDir Dshot
* Baro (MS5611)
* GPS navigation

Expand Down
Binary file modified docs/calculations.ods
Binary file not shown.
Binary file added docs/images/espfc_receiver.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added docs/images/espfc_wifi_ap_connect.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added docs/images/espfc_wifi_ap_enable.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
12 changes: 9 additions & 3 deletions docs/setup.md
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,13 @@ If you want to use Serial based receiver (SBUS,CRSF), you need to allocate UART

Then go to the `Receiver` tab, and select `Receiver mode` and `Serial Receiver Provider`.

To use Serial RX on ESP8266, you need to connect reciver to primary UART. In this case you lose ability to configure through UART.
To deal with it activate "SOFTSERIAL" feature. In this case if board stay in failsafe mode for 30 seconds (transmitter is turned off), then automatically WiFi access point will be started.
Default name is "ESP-FC". After connecting to this AP open configurator, select "manual" port and type port: `tcp://192.168.4.1:1111`.
You can also configure board to automatically connect existing wifi network. In this case set `wifi_ssid` and `wifi_pass` parameters in CLI.

To use ESP-NOW receiver, choose "SPI Rx (e.g. built-in Rx)" receiver mode in Receiver tab. You need compatible transmitter module. Read more about [ESP-FC Wireless Functions](/docs/wireless.md)

## Motor setup

In `Motors` tab you must configure
Expand Down Expand Up @@ -92,7 +99,7 @@ This option allows to separate PWM frequency. If your pid loop is set to 1k, but

## Flight modes

Flight modes can be configured in modes tab
Flight modes can be configured in `Modes` tab

### Arm

Expand Down Expand Up @@ -125,8 +132,7 @@ Logging using serial device is possible, like [D-ronin OpenLager](https://github
Recommended settings

- To log with 1k rate, you need device that is capable to receive data with 250kbps.
- To log with 1k rate with debug, baro and mag data, 500kbps is recommended.
- To log with 1k rate, you need device that is capable to receive data with 500kbps.
- To log with 2k rate, you need 1Mbps

OpenLager can handle it easily. If you plan to use OpenLog, you might need to flash [blackbox-firmware](https://github.com/cleanflight/blackbox-firmware) to be able to handle more than 115.2kbps. Either 250kbps and 500kbps works well with modern SD cards up to 32GB size.
Expand Down
44 changes: 44 additions & 0 deletions docs/wireless.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
# ESP-FC Wireless functions

Espressif modules have a built-in WiFi module that can be used for configuration and control.

## WiFi configuration

> [!NOTE] To be able to configure device using WiFi connection, you need to enable `SOFTSERIAL` function. WiFi function can only be used to configure device. Whilst WiFi is active, it is not possible to ARM controller and reboot is required.
![Enable WiFi](/docs/images/espfc_wifi_ap_enable.png)

WiFi will start its own Access-Point if board will not detect receiver signal for at least 30 seconds (stay in failsafe mode since boot). Name of this AP is `ESP-FC` and it is open network. If you connect to this AP, then choose `Manual Selection` and type `tcp://192.168.4.1:1111`

![Connect to ESP-FC AP](/docs/images/espfc_wifi_ap_connect.png)

You can also automatically connect ESP-FC to your home network. To achive that, go to the CLI tab, and enter your network name and secret.
```
set wifi_ssid MY-HOME-NET
set wifi_pass MY-HOME-PASS
```
> [!NOTE] Network name and pass cannot contains spaces.
then you can check status of connection by typing `wifi` in CLI tab.
```
wifi
ST IP4: tcp://0.0.0.0:1111
ST MAC: 30:30:F9:6E:10:74
AP IP4: tcp://192.168.4.1:1111
AP MAC: 32:30:F9:6E:10:74
```
In this mode you need to discover IP address granted by DHCP. In line `ST IP4` is the address that you need to use in configurator. If there is `0.0.0.0`, that means that FC was not able to connect to home network.

## ESP-NOW control

ESP-NOW is a proprietary wireless communication protocol defined by Espressif, which enables the direct, quick and low-power control of smart devices, without the need of a router.

As there are no real transmitters usng this protocol on the market, you have to build your own transmitting module first. If you alredy own RC transmitter with JR bay, you can use another ESP32 module. In this case follow [espnow-rclink-tx](https://github.com/rtlopez/espnow-rclink-tx) instructions.

In ESP-FC you have to choose `SPI Rx (e.g. built-in Rx)` as Receiver mode in Receiver tab.

![ESP-FC ESP-NOW Reciever](/docs/images/espfc_receiver.png)

Transmitter and receiver binds automatically after power up, you don't need to do anything. Recomended startup procedure is:
1. turn on transmitter first
2. next power up receiver/flight controller
9 changes: 8 additions & 1 deletion lib/AHRS/src/Mahony.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,13 @@
// Header files

#include "Mahony.h"
#include <Arduino.h>

#ifdef ESP32
#define FAST_CODE_IMU_ATTR IRAM_ATTR
#else
#define FAST_CODE_IMU_ATTR
#endif

//-------------------------------------------------------------------------------------------
// Definitions
Expand Down Expand Up @@ -165,7 +172,7 @@ void Mahony::update(float gx, float gy, float gz, float ax, float ay, float az,
//-------------------------------------------------------------------------------------------
// IMU algorithm update

void Mahony::update(float gx, float gy, float gz, float ax, float ay, float az)
void FAST_CODE_IMU_ATTR Mahony::update(float gx, float gy, float gz, float ax, float ay, float az)
{
float recipNorm;
float halfvx, halfvy, halfvz;
Expand Down
41 changes: 11 additions & 30 deletions lib/EscDriver/src/EscDriverEsp32.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,16 @@ static void IRAM_ATTR _rmt_zero_mem(rmt_channel_t channel, size_t len)
}
}

// using map() in isr cause crash
static long IRAM_ATTR _map(long x, long in_min, long in_max, long out_min, long out_max)
{
const long in_range = in_max - in_min;
if(in_range == 0) return out_min;
const long out_range = out_max - out_min;
const long delta = x - in_min;
return (delta * out_range) / in_range + out_min;
}

bool EscDriverEsp32::_tx_end_installed = false;

EscDriverEsp32 *EscDriverEsp32::instances[] = {NULL, NULL, NULL, NULL, NULL, NULL, NULL, NULL};
Expand Down Expand Up @@ -205,18 +215,14 @@ void EscDriverEsp32::initChannel(int i, gpio_num_t pin, int pulse)

void EscDriverEsp32::modeTx(rmt_channel_t channel)
{
//PIN_DEBUG(HIGH);
disableRx(channel);
enableTx(channel);
//PIN_DEBUG(LOW);
}

void EscDriverEsp32::modeRx(rmt_channel_t channel)
{
//PIN_DEBUG(HIGH);
disableTx(channel);
enableRx(channel);
//PIN_DEBUG(LOW);
}

void EscDriverEsp32::enableTx(rmt_channel_t channel)
Expand Down Expand Up @@ -266,7 +272,6 @@ void EscDriverEsp32::disableRx(rmt_channel_t channel)

void EscDriverEsp32::txDoneCallback(rmt_channel_t channel, void *arg)
{
//PIN_DEBUG(HIGH);
auto instance = instances[channel];
if(!instance) return;
if(instance->_async)
Expand All @@ -277,7 +282,6 @@ void EscDriverEsp32::txDoneCallback(rmt_channel_t channel, void *arg)
{
instance->modeRx(channel);
}
//PIN_DEBUG(LOW);
}

void EscDriverEsp32::transmitOne(uint8_t i)
Expand Down Expand Up @@ -318,48 +322,25 @@ void EscDriverEsp32::transmitAll()

void EscDriverEsp32::readTelemetry()
{
//PIN_DEBUG(HIGH);
for (size_t i = 0; i < ESC_CHANNEL_COUNT; i++)
{
if(!_digital || !_dshot_tlm) continue;
if(!_channel[i].attached()) continue;

//HardwareSerial* s = (i == 0 && _timer.check()) ? &Serial : nullptr;

RingbufHandle_t rb = NULL;
if(ESP_OK != rmt_get_ringbuf_handle((rmt_channel_t)i, &rb)) continue;

size_t rmt_len = 0;
rmt_item32_t* data = (rmt_item32_t*)xRingbufferReceive(rb, &rmt_len, 0);
//if(s) { s->print((uint8_t)rmt_len); }
if (data)
{
/*for(size_t j = 0; j < rmt_len >> 2; j++)
{
if(!data[j].duration0) break;
if(s) s->print(' ');
if(s) s->print(data[j].level0);
if(s) s->print(':');
if(s) s->print(data[j].duration0);
if(!data[j].duration1) break;
if(s) s->print(' ');
if(s) s->print(data[j].level1);
if(s) s->print(':');
if(s) s->print(data[j].duration1);
}*/
uint32_t value = extractTelemetryGcr((uint32_t*)data, rmt_len >> 2, _channel[i].dshot_tlm_bit_len);

//if(s) s->print(' ');
//if(s) s->print(value, HEX);

vRingbufferReturnItem(rb, (void *)data);

_channel[i].telemetryValue = value;
}
//if(s) s->print('\n');
}
//PIN_DEBUG(LOW);
}

void EscDriverEsp32::writeAnalogCommand(uint8_t channel, int32_t pulse)
Expand All @@ -373,7 +354,7 @@ void EscDriverEsp32::writeAnalogCommand(uint8_t channel, int32_t pulse)
maxPulse = 2000;
}
pulse = constrain(pulse, minPulse, maxPulse);
int duration = map(pulse, 1000, 2000, slot.pulse_min, slot.pulse_max);
int duration = _map(pulse, 1000, 2000, slot.pulse_min, slot.pulse_max);

int count = 2;
if (_async)
Expand Down
10 changes: 5 additions & 5 deletions lib/EscDriver/src/EscDriverEsp32.h
Original file line number Diff line number Diff line change
Expand Up @@ -82,10 +82,10 @@ class EscDriverEsp32: public EscDriverBase
int begin(const EscConfig& conf);
void end();
int attach(size_t channel, int pin, int pulse);
int write(size_t channel, int pulse);
void apply();
int write(size_t channel, int pulse) IRAM_ATTR;
void apply() IRAM_ATTR;
int pin(size_t channel) const;
uint32_t telemetry(size_t channel) const;
uint32_t telemetry(size_t channel) const IRAM_ATTR;

private:
void initChannel(int channel, gpio_num_t pin, int pulse);
Expand All @@ -97,8 +97,8 @@ class EscDriverEsp32: public EscDriverBase
void disableRx(rmt_channel_t channel) IRAM_ATTR;
static void txDoneCallback(rmt_channel_t channel, void *arg) IRAM_ATTR;
void transmitOne(uint8_t i) IRAM_ATTR;
void transmitAll();
void readTelemetry();
void transmitAll() IRAM_ATTR;
void readTelemetry() IRAM_ATTR;
void writeAnalogCommand(uint8_t channel, int32_t pulse) IRAM_ATTR;
void writeDshotCommand(uint8_t channel, int32_t pulse) IRAM_ATTR;
void transmitCommand(uint8_t channel) IRAM_ATTR;
Expand Down
3 changes: 0 additions & 3 deletions lib/EspGpio/library.json

This file was deleted.

65 changes: 0 additions & 65 deletions lib/EspGpio/src/EspGpio.h

This file was deleted.

3 changes: 0 additions & 3 deletions lib/EspSoftSerial/library.json

This file was deleted.

Loading

0 comments on commit f7b76e1

Please sign in to comment.