2018-01-17 15:29:06 -04:00
|
|
|
/*
|
|
|
|
* This file 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 file 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/>.
|
|
|
|
*
|
|
|
|
* Code by Andrew Tridgell and Siddharth Bharat Purohit
|
|
|
|
*/
|
|
|
|
#pragma once
|
|
|
|
#include <AP_HAL/utility/RingBuffer.h>
|
|
|
|
#include <AP_HAL/AP_HAL_Boards.h>
|
|
|
|
|
|
|
|
#include "AP_HAL_ChibiOS.h"
|
|
|
|
|
2018-01-17 19:54:37 -04:00
|
|
|
#if HAL_USE_ICU == TRUE
|
|
|
|
|
2018-01-17 15:29:06 -04:00
|
|
|
#define INPUT_CAPTURE_FREQUENCY 1000000 //capture unit in microseconds
|
2018-11-03 02:46:02 -03:00
|
|
|
|
2018-10-03 23:45:40 -03:00
|
|
|
#ifndef SOFTSIG_MAX_SIGNAL_TRANSITIONS
|
2018-11-05 07:02:06 -04:00
|
|
|
#define SOFTSIG_MAX_SIGNAL_TRANSITIONS 128
|
2018-10-03 23:45:40 -03:00
|
|
|
#endif
|
2018-11-03 02:46:02 -03:00
|
|
|
|
|
|
|
// we use a small bounce buffer size to minimise time in the DMA
|
|
|
|
// callback IRQ
|
|
|
|
#define SOFTSIG_BOUNCE_BUF_SIZE 8
|
2018-01-17 18:04:42 -04:00
|
|
|
|
2018-01-17 15:29:06 -04:00
|
|
|
class ChibiOS::SoftSigReader {
|
2018-11-03 02:46:02 -03:00
|
|
|
friend class ChibiOS::RCInput;
|
2018-01-17 15:29:06 -04:00
|
|
|
public:
|
|
|
|
bool attach_capture_timer(ICUDriver* icu_drv, icuchannel_t chan, uint8_t dma_stream, uint32_t dma_channel);
|
2018-11-03 02:46:02 -03:00
|
|
|
|
2018-01-17 15:29:06 -04:00
|
|
|
private:
|
|
|
|
uint32_t *signal;
|
2018-11-05 06:39:47 -04:00
|
|
|
uint32_t signal2[SOFTSIG_BOUNCE_BUF_SIZE];
|
2018-01-17 15:29:06 -04:00
|
|
|
static void _irq_handler(void* self, uint32_t flags);
|
|
|
|
uint8_t num_timer_channels;
|
|
|
|
uint8_t enable_chan_mask;
|
|
|
|
uint8_t max_pulse_width;
|
|
|
|
const stm32_dma_stream_t* dma;
|
2018-10-05 21:32:54 -03:00
|
|
|
uint32_t dmamode;
|
2018-01-17 15:29:06 -04:00
|
|
|
ICUConfig icucfg;
|
2018-01-18 15:13:52 -04:00
|
|
|
ICUDriver* _icu_drv = nullptr;
|
2018-11-05 07:02:06 -04:00
|
|
|
typedef struct PACKED {
|
|
|
|
uint32_t w0;
|
|
|
|
uint32_t w1;
|
|
|
|
} pulse_t;
|
|
|
|
ObjectBuffer<pulse_t> sigbuf{SOFTSIG_MAX_SIGNAL_TRANSITIONS};
|
2018-01-18 15:13:52 -04:00
|
|
|
bool need_swap;
|
2018-01-17 15:29:06 -04:00
|
|
|
};
|
2018-01-17 19:54:37 -04:00
|
|
|
|
|
|
|
#endif // HAL_USE_ICU
|
|
|
|
|