Browse Source

HAL_ChibiOS: allow reduction of memory for SoftSigReader

for IOMCU
mission-4.1.18
Andrew Tridgell 6 years ago
parent
commit
298a91ac7c
  1. 6
      libraries/AP_HAL_ChibiOS/SoftSigReader.h
  2. 6
      libraries/AP_HAL_ChibiOS/SoftSigReaderInt.h

6
libraries/AP_HAL_ChibiOS/SoftSigReader.h

@ -23,7 +23,9 @@ @@ -23,7 +23,9 @@
#if HAL_USE_ICU == TRUE
#define INPUT_CAPTURE_FREQUENCY 1000000 //capture unit in microseconds
#define MAX_SIGNAL_TRANSITIONS 256
#ifndef SOFTSIG_MAX_SIGNAL_TRANSITIONS
#define SOFTSIG_MAX_SIGNAL_TRANSITIONS 256
#endif
#define DEFAULT_BOUNCE_BUF_SIZE 32
class ChibiOS::SoftSigReader {
@ -36,7 +38,7 @@ private: @@ -36,7 +38,7 @@ private:
uint32_t *signal;
static void _irq_handler(void* self, uint32_t flags);
uint8_t num_timer_channels;
ObjectBuffer<uint32_t> sigbuf{MAX_SIGNAL_TRANSITIONS};
ObjectBuffer<uint32_t> sigbuf{SOFTSIG_MAX_SIGNAL_TRANSITIONS};
uint8_t enable_chan_mask;
uint8_t max_pulse_width;
const stm32_dma_stream_t* dma;

6
libraries/AP_HAL_ChibiOS/SoftSigReaderInt.h

@ -22,7 +22,9 @@ @@ -22,7 +22,9 @@
#if HAL_USE_EICU == TRUE
#define INPUT_CAPTURE_FREQUENCY 1000000 //capture unit in microseconds
#define MAX_SIGNAL_TRANSITIONS 256
#ifndef SOFTSIG_MAX_SIGNAL_TRANSITIONS
#define SOFTSIG_MAX_SIGNAL_TRANSITIONS 256
#endif
class ChibiOS::SoftSigReaderInt {
@ -48,7 +50,7 @@ private: @@ -48,7 +50,7 @@ private:
static eicuchannel_t get_pair_channel(eicuchannel_t channel);
ObjectBuffer<uint16_t> sigbuf{MAX_SIGNAL_TRANSITIONS};
ObjectBuffer<uint16_t> sigbuf{SOFTSIG_MAX_SIGNAL_TRANSITIONS};
EICUConfig icucfg;
EICUChannelConfig channel_config;
EICUChannelConfig aux_channel_config;

Loading…
Cancel
Save