mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: fixed memory handling in SoftSigReader
This commit is contained in:
parent
8be59c73c7
commit
e2c8fe27ef
|
@ -49,7 +49,7 @@ bool SoftSigReader::attach_capture_timer(ICUDriver* icu_drv, icuchannel_t chan,
|
|||
dmaStreamSetMode(dma, dmamode | STM32_DMA_CR_DIR_P2M | STM32_DMA_CR_PSIZE_WORD |
|
||||
STM32_DMA_CR_MSIZE_WORD | STM32_DMA_CR_MINC | STM32_DMA_CR_TCIE);
|
||||
|
||||
icucfg.mode = ICU_INPUT_ACTIVE_HIGH;
|
||||
icucfg.mode = ICU_INPUT_ACTIVE_LOW;
|
||||
icucfg.frequency = INPUT_CAPTURE_FREQUENCY;
|
||||
icucfg.channel = chan;
|
||||
icucfg.width_cb = NULL;
|
||||
|
@ -104,8 +104,10 @@ bool SoftSigReader::read(uint32_t &widths0, uint32_t &widths1)
|
|||
bool SoftSigReader::set_bounce_buf_size(uint16_t buf_size)
|
||||
{
|
||||
if (buf_size > _bounce_buf_size) {
|
||||
delete[] signal;
|
||||
signal = (uint32_t*)hal.util->malloc_type(sizeof(uint32_t)*_bounce_buf_size, AP_HAL::Util::MEM_DMA_SAFE);
|
||||
if (signal) {
|
||||
hal.util->free_type(signal, sizeof(uint32_t)*_bounce_buf_size, AP_HAL::Util::MEM_DMA_SAFE);
|
||||
}
|
||||
signal = (uint32_t*)hal.util->malloc_type(sizeof(uint32_t)*buf_size, AP_HAL::Util::MEM_DMA_SAFE);
|
||||
if (signal == nullptr) {
|
||||
return false;
|
||||
}
|
||||
|
@ -117,4 +119,4 @@ bool SoftSigReader::set_bounce_buf_size(uint16_t buf_size)
|
|||
}
|
||||
|
||||
|
||||
#endif //CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||
#endif //CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||
|
|
|
@ -22,7 +22,8 @@
|
|||
|
||||
#define INPUT_CAPTURE_FREQUENCY 1000000 //capture unit in microseconds
|
||||
#define MAX_SIGNAL_TRANSITIONS 256
|
||||
#define DEFAULT_BOUNCE_BUF_SIZE 16
|
||||
#define DEFAULT_BOUNCE_BUF_SIZE 32
|
||||
|
||||
class ChibiOS::SoftSigReader {
|
||||
public:
|
||||
bool attach_capture_timer(ICUDriver* icu_drv, icuchannel_t chan, uint8_t dma_stream, uint32_t dma_channel);
|
||||
|
|
Loading…
Reference in New Issue