Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

ESP32 / RP2040 Port #14

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
674 changes: 674 additions & 0 deletions Versions/dRehmFlight_ESP32_BETA_1.3/COPYING.txt

Large diffs are not rendered by default.

1,710 changes: 1,710 additions & 0 deletions Versions/dRehmFlight_ESP32_BETA_1.3/dRehmFlight_ESP32_BETA_1.3.ino

Large diffs are not rendered by default.

203 changes: 203 additions & 0 deletions Versions/dRehmFlight_ESP32_BETA_1.3/radioComm.ino
Original file line number Diff line number Diff line change
@@ -0,0 +1,203 @@
//Arduino/Teensy Flight Controller - dRehmFlight
//Author: Nicholas Rehm
//Project Start: 1/6/2020
//Last Updated: 7/29/2022
//Version: Beta 1.3

//========================================================================================================================//

//This file contains all necessary functions and code used for radio communication to avoid cluttering the main code

unsigned long rising_edge_start_1, rising_edge_start_2, rising_edge_start_3, rising_edge_start_4, rising_edge_start_5, rising_edge_start_6;
unsigned long channel_1_raw, channel_2_raw, channel_3_raw, channel_4_raw, channel_5_raw, channel_6_raw;
int ppm_counter = 0;
unsigned long time_ms = 0;

void radioSetup() {
//PPM Receiver
#if defined USE_PPM_RX
//Declare interrupt pin
pinMode(PPM_Pin, INPUT_PULLUP);
delay(20);
//Attach interrupt and point to corresponding ISR function
attachInterrupt(digitalPinToInterrupt(PPM_Pin), getPPM, CHANGE);

//PWM Receiver
#elif defined USE_PWM_RX
#error TODO USE_PWM_RX
//Declare interrupt pins
pinMode(ch1Pin, INPUT_PULLUP);
pinMode(ch2Pin, INPUT_PULLUP);
pinMode(ch3Pin, INPUT_PULLUP);
pinMode(ch4Pin, INPUT_PULLUP);
pinMode(ch5Pin, INPUT_PULLUP);
pinMode(ch6Pin, INPUT_PULLUP);
delay(20);
//Attach interrupt and point to corresponding ISR functions
attachInterrupt(digitalPinToInterrupt(ch1Pin), getCh1, CHANGE);
attachInterrupt(digitalPinToInterrupt(ch2Pin), getCh2, CHANGE);
attachInterrupt(digitalPinToInterrupt(ch3Pin), getCh3, CHANGE);
attachInterrupt(digitalPinToInterrupt(ch4Pin), getCh4, CHANGE);
attachInterrupt(digitalPinToInterrupt(ch5Pin), getCh5, CHANGE);
attachInterrupt(digitalPinToInterrupt(ch6Pin), getCh6, CHANGE);
delay(20);

//SBUS Recevier
#elif defined USE_SBUS_RX
#error TODO USE_SBUS_RX
sbus.begin();

//DSM receiver
#elif defined USE_DSM_RX
#error TODO USE_DSM_RX
Serial3.begin(115000);
#else
#error No RX type defined...
#endif
}

unsigned long getRadioPWM(int ch_num) {
//DESCRIPTION: Get current radio commands from interrupt routines
unsigned long returnPWM = 0;

if (ch_num == 1) {
returnPWM = channel_1_raw;
}
else if (ch_num == 2) {
returnPWM = channel_2_raw;
}
else if (ch_num == 3) {
returnPWM = channel_3_raw;
}
else if (ch_num == 4) {
returnPWM = channel_4_raw;
}
else if (ch_num == 5) {
returnPWM = channel_5_raw;
}
else if (ch_num == 6) {
returnPWM = channel_6_raw;
}

return returnPWM;
}

//For DSM type receivers
void serialEvent3(void)
{
#if defined USE_DSM_RX
while (Serial3.available()) {
DSM.handleSerialEvent(Serial3.read(), micros());
}
#endif
}



//========================================================================================================================//



//INTERRUPT SERVICE ROUTINES (for reading PWM and PPM)

void getPPM() {
unsigned long dt_ppm;
int trig = digitalRead(PPM_Pin);
if (trig==1) { //Only care about rising edge
dt_ppm = micros() - time_ms;
time_ms = micros();


if (dt_ppm > 5000) { //Waiting for long pulse to indicate a new pulse train has arrived
ppm_counter = 0;
}

if (ppm_counter == 1) { //First pulse
channel_1_raw = dt_ppm;
}

if (ppm_counter == 2) { //Second pulse
channel_2_raw = dt_ppm;
}

if (ppm_counter == 3) { //Third pulse
channel_3_raw = dt_ppm;
}

if (ppm_counter == 4) { //Fourth pulse
channel_4_raw = dt_ppm;
}

if (ppm_counter == 5) { //Fifth pulse
channel_5_raw = dt_ppm;
}

if (ppm_counter == 6) { //Sixth pulse
channel_6_raw = dt_ppm;
}

ppm_counter = ppm_counter + 1;
}
}

#ifdef USE_PWM_RX
void getCh1() {
int trigger = digitalRead(ch1Pin);
if(trigger == 1) {
rising_edge_start_1 = micros();
}
else if(trigger == 0) {
channel_1_raw = micros() - rising_edge_start_1;
}
}

void getCh2() {
int trigger = digitalRead(ch2Pin);
if(trigger == 1) {
rising_edge_start_2 = micros();
}
else if(trigger == 0) {
channel_2_raw = micros() - rising_edge_start_2;
}
}

void getCh3() {
int trigger = digitalRead(ch3Pin);
if(trigger == 1) {
rising_edge_start_3 = micros();
}
else if(trigger == 0) {
channel_3_raw = micros() - rising_edge_start_3;
}
}

void getCh4() {
int trigger = digitalRead(ch4Pin);
if(trigger == 1) {
rising_edge_start_4 = micros();
}
else if(trigger == 0) {
channel_4_raw = micros() - rising_edge_start_4;
}
}

void getCh5() {
int trigger = digitalRead(ch5Pin);
if(trigger == 1) {
rising_edge_start_5 = micros();
}
else if(trigger == 0) {
channel_5_raw = micros() - rising_edge_start_5;
}
}

void getCh6() {
int trigger = digitalRead(ch6Pin);
if(trigger == 1) {
rising_edge_start_6 = micros();
}
else if(trigger == 0) {
channel_6_raw = micros() - rising_edge_start_6;
}
}
#endif
116 changes: 116 additions & 0 deletions Versions/dRehmFlight_ESP32_BETA_1.3/src/DSMRX/DSMRX.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,116 @@
/*
Spektrum DSM receiver implementation

Copyright (C) Simon D. Levy 2017

This file is part of DSMRX.

DSMRX 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.

DSMRX 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 DSMRX. If not, see <http://www.gnu.org/licenses/>.
*/

#include "DSMRX.h"

DSMRX::DSMRX(uint8_t rcChans, uint8_t chanShift, uint8_t chanMask, uint8_t valShift)
{
_rcChans = rcChans;
_chanShift = chanShift;
_chanMask = chanMask;
_valShift = valShift;

_gotNewFrame = false;
_lastInterruptMicros = 0;
}

void DSMRX::handleSerialEvent(uint8_t value, uint32_t usec)
{
// Reset time
_lastInterruptMicros = usec;

// check for new frame, i.e. more than 2.5ms passed
static uint32_t spekTimeLast;
uint32_t spekTimeNow = usec;
uint32_t spekInterval = spekTimeNow - spekTimeLast;
spekTimeLast = spekTimeNow;
if (spekInterval > 2500) {
_rxBufPos = 0;
}

// put the data in buffer
if (_rxBufPos < BUFFER_SIZE) {
_rxBuf[_rxBufPos++] = value;
}

// parse frame if done
if (_rxBufPos == BUFFER_SIZE) {

// grab fade count
_fadeCount = _rxBuf[0];

// convert to channel data in [0,1024]
for (int b = 2; b < BUFFER_SIZE; b += 2) {
uint8_t bh = _rxBuf[b];
uint8_t bl = _rxBuf[b+1];
uint8_t spekChannel = 0x0F & (bh >> _chanShift);
if (spekChannel < _rcChans) {
_rcValue[spekChannel] = ((((uint16_t)(bh & _chanMask) << 8) + bl) >> _valShift);
}
}

// we have a new frame
_gotNewFrame = true;
}
}


bool DSMRX::gotNewFrame(void)
{
bool retval = _gotNewFrame;
if (_gotNewFrame) {
_gotNewFrame = false;
}
return retval;
}

void DSMRX::getChannelValues(uint16_t values[], uint8_t count)
{
for (uint8_t k=0; k<count; ++k) {
values[k] = _rcValue[k] + 988;
}
}

void DSMRX::getChannelValuesNormalized(float values[], uint8_t count)
{
for (uint8_t k=0; k<count; ++k) {
values[k] = (_rcValue[k] - 512) / 512.f;
}
}

uint8_t DSMRX::getFadeCount(void)
{
return _fadeCount;
}

bool DSMRX::timedOut(uint32_t usec, uint32_t maxMicros)
{

uint32_t lag = usec - _lastInterruptMicros;
return lag > maxMicros;
}

DSM1024::DSM1024(void) : DSMRX(7, 2, 0x03, 0)
{
}

DSM2048::DSM2048(void) : DSMRX(8, 3, 0x07, 1)
{
}
Loading