mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
HAL_ChibiOS: added disable() API for pulse input
This commit is contained in:
parent
258b8b71ea
commit
9c0cf0871b
@ -91,6 +91,12 @@ bool SoftSigReader::attach_capture_timer(ICUDriver* icu_drv, icuchannel_t chan,
|
||||
return true;
|
||||
}
|
||||
|
||||
void SoftSigReader::disable(void)
|
||||
{
|
||||
icuStopCapture(_icu_drv);
|
||||
dmaStreamDisable(dma);
|
||||
}
|
||||
|
||||
void SoftSigReader::_irq_handler(void* self, uint32_t flags)
|
||||
{
|
||||
SoftSigReader* sig_reader = (SoftSigReader*)self;
|
||||
|
@ -36,6 +36,7 @@ class ChibiOS::SoftSigReader {
|
||||
friend class ChibiOS::RCInput;
|
||||
public:
|
||||
bool attach_capture_timer(ICUDriver* icu_drv, icuchannel_t chan, uint8_t dma_stream, uint32_t dma_channel);
|
||||
void disable(void);
|
||||
|
||||
private:
|
||||
uint32_t *signal;
|
||||
|
@ -90,6 +90,11 @@ void SoftSigReaderInt::init(EICUDriver* icu_drv, eicuchannel_t chan)
|
||||
eicuEnable(_icu_drv);
|
||||
}
|
||||
|
||||
void SoftSigReaderInt::disable(void)
|
||||
{
|
||||
eicuDisable(_icu_drv);
|
||||
}
|
||||
|
||||
void SoftSigReaderInt::_irq_handler(EICUDriver *eicup, eicuchannel_t aux_channel)
|
||||
{
|
||||
eicuchannel_t channel = get_pair_channel(aux_channel);
|
||||
|
@ -42,6 +42,7 @@ public:
|
||||
|
||||
void init(EICUDriver* icu_drv, eicuchannel_t chan);
|
||||
bool read(uint32_t &widths0, uint32_t &widths1);
|
||||
void disable(void);
|
||||
private:
|
||||
// singleton
|
||||
static SoftSigReaderInt *_singleton;
|
||||
|
Loading…
Reference in New Issue
Block a user