-
Notifications
You must be signed in to change notification settings - Fork 0
/
espRCPpm.cpp
90 lines (70 loc) · 2.12 KB
/
espRCPpm.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
/*
* This program is part an esp32 library to read and write RC protocols
* Copyright (C) 2021 Pierre-Loup Martin
*
* 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/>.
*/
#include "espRCPpm.h"
RCPpmIn* RCPpmIn::_pInstance = nullptr;
RCPpmIn::RCPpmIn(uint8_t pin, uint8_t timer, uint8_t numChannel, uint16_t neutral){
if(numChannel > 16) return;
if(timer > 3) return;
_data.channel = new int16_t[numChannel];
_tempCh = new int16_t[numChannel];
_data.numChannel = numChannel;
memset(_data.channel, 0, sizeof(int16_t) * numChannel);
memset(_tempCh, 0, sizeof(int16_t) * numChannel);
_neutral = neutral;
_resolution = 1024;
_currentCh = 0;
_pInstance = this;
_mux = portMUX_INITIALIZER_UNLOCKED;
pinMode(_pin, INPUT);
_timer = timerBegin(timer, 40, true);
attachInterrupt(pin, _isrStatic, RISING);
}
RCPpmIn::~RCPpmIn(){
delete[] _data.channel;
delete[] _tempCh;
}
bool RCPpmIn::update(){
if(!_hasNew) return false;
_hasNew = false;
for (uint8_t i = 0; i < _data.numChannel; ++i){
portENTER_CRITICAL_ISR(&_mux);
_data.channel[i] = _tempCh[i] - _neutral;
portEXIT_CRITICAL_ISR(&_mux);
}
return true;
}
// Protected methods
void RCPpmIn::_isrStatic(){
if(_pInstance == nullptr) return;
_pInstance->_isr();
}
void RCPpmIn::_isr(){
uint64_t time = timerRead(_timer);
timerRestart(_timer);
if(time > 6000){
_currentCh = 0;
_hasNew = true;
} else {
portENTER_CRITICAL_ISR(&_mux);
_tempCh[_currentCh] = (uint16_t)time;
portEXIT_CRITICAL_ISR(&_mux);
if(++_currentCh >= _data.numChannel){
_currentCh--;
}
}
}