RSeries astromech firmware
PPMReader.h
Go to the documentation of this file.
1 /*
2 Copyright 2016 Aapo Nikkilä
3 Copyright 2021 Dmitry Grigoryev
4 
5 This file is part of PPM Reader.
6 
7 PPM Reader is free software: you can redistribute it and/or modify
8 it under the terms of the GNU General Public License as published by
9 the Free Software Foundation, either version 3 of the License, or
10 (at your option) any later version.
11 
12 PPM Reader is distributed in the hope that it will be useful,
13 but WITHOUT ANY WARRANTY; without even the implied warranty of
14 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 GNU General Public License for more details.
16 
17 You should have received a copy of the GNU General Public License
18 along with PPM Reader. If not, see <http://www.gnu.org/licenses/>.
19 */
20 
21 #ifndef PPM_READER
22 #define PPM_READER
23 
24 #include "ReelTwo.h"
25 
26 #ifdef ESP32
27 class PPMReader {
28 public:
29  PPMReader(byte interruptPin, byte channelAmount);
30  ~PPMReader(void);
31 
32  void begin();
33  void end();
34 
35  // Returns the latest raw (not necessarily valid) value for the channel (starting from 1)
36  unsigned rawChannelValue(byte channel);
37 
38  // Returns the latest received value that was considered valid for the channel (starting from 1)
39  // Returns defaultValue if the channel hasn't received any valid values yet, or the PPM signal was absent for more than failsafeTimeout
40  unsigned latestValidChannelValue(byte channel, unsigned defaultValue);
41 
42  // The range of a channel's possible values (microseconds)
43  static constexpr unsigned minChannelValue = 1000;
44  static constexpr unsigned maxChannelValue = 2000;
45 
46  // The maximum error (in either direction) in channel value with which the channel value is still considered valid
47  static constexpr unsigned channelValueMaxError = 10;
48 
49  // The minimum blanking time (microseconds) after which the frame current is considered to be finished
50  // Should be bigger than maxChannelValue + channelValueMaxError
51  static constexpr unsigned blankTime = 2100;
52 
53  // The timeout (microseconds) after which the channels which were not updated are considered invalid
54  static constexpr unsigned long failsafeTimeout = 500000L;
55 
56 private:
57 
58  // An interrupt service routine for handling the interrupts activated by PPM pulses
59  void handleInterrupt(void);
60 
61  // Interrupt service routine function compatible with attachInterrupt. Add more funcitons if multiple PPM reader instances are needed
62  static void PPM_ISR(void);
63 
64  // The pin from which to listen for interrupts
65  byte interruptPin = 0;
66 
67  // The number of channels to be expected in the PPM signal
68  byte channelAmount = 0;
69 
70  // Arrays for keeping track of channel values
71  volatile unsigned *rawValues = NULL;
72 
73  // A counter variable for determining which channel is being read next
74  volatile byte pulseCounter = 0;
75 
76  // A time variable to remember when the last pulse was read
77  volatile unsigned long microsAtLastPulse = 0;
78 
79  // Pointer to PPMReader object used by ISR. Replace by an array if multiple PPM reader instances are needed
80  static PPMReader *ppm;
81 };
82 #endif
83 
84 #endif
ReelTwo.h