APM:Libraries
SoftSigReaderInt.h
Go to the documentation of this file.
1 /*
2  * This file is free software: you can redistribute it and/or modify it
3  * under the terms of the GNU General Public License as published by the
4  * Free Software Foundation, either version 3 of the License, or
5  * (at your option) any later version.
6  *
7  * This file is distributed in the hope that it will be useful, but
8  * WITHOUT ANY WARRANTY; without even the implied warranty of
9  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
10  * See the GNU General Public License for more details.
11  *
12  * You should have received a copy of the GNU General Public License along
13  * with this program. If not, see <http://www.gnu.org/licenses/>.
14  *
15  */
16 #pragma once
18 #include <AP_HAL/AP_HAL_Boards.h>
19 
20 #include "AP_HAL_ChibiOS.h"
21 
22 #if HAL_USE_EICU == TRUE
23 
24 #define INPUT_CAPTURE_FREQUENCY 1000000 //capture unit in microseconds
25 #define MAX_SIGNAL_TRANSITIONS 256
26 
27 
29 public:
31  /* Do not allow copies */
32  SoftSigReaderInt(const SoftSigReaderInt &other) = delete;
34 
35  // get singleton
37  {
38  return _instance;
39  }
40 
41  void init(EICUDriver* icu_drv, eicuchannel_t chan);
42  bool read(uint32_t &widths0, uint32_t &widths1);
43 private:
44  // singleton
46 
47  static void _irq_handler(EICUDriver *eicup, eicuchannel_t channel);
48 
50  EICUConfig icucfg;
51  EICUChannelConfig channel_config;
52  EICUDriver* _icu_drv = nullptr;
53  uint16_t last_value;
54 };
55 
56 #endif // HAL_USE_EICU
57 
static void _irq_handler(EICUDriver *eicup, eicuchannel_t channel)
#define MAX_SIGNAL_TRANSITIONS
static SoftSigReaderInt * get_instance(void)
void init(EICUDriver *icu_drv, eicuchannel_t chan)
ObjectBuffer< uint16_t > sigbuf
SoftSigReaderInt & operator=(const SoftSigReaderInt &)=delete
EICUChannelConfig channel_config
bool read(uint32_t &widths0, uint32_t &widths1)
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
static SoftSigReaderInt * _instance