mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
HAL_ChibiOS: support ChibiOS kernel major 6
preparing for STM32H7 support
This commit is contained in:
parent
e79b7fb6d5
commit
bbd25350eb
@ -185,11 +185,9 @@ void AnalogSource::_add_value(float v, float vcc5V)
|
||||
/*
|
||||
callback from ADC driver when sample buffer is filled
|
||||
*/
|
||||
void AnalogIn::adccallback(ADCDriver *adcp, adcsample_t *buffer, size_t n)
|
||||
void AnalogIn::adccallback(ADCDriver *adcp)
|
||||
{
|
||||
if (buffer != samples) {
|
||||
return;
|
||||
}
|
||||
const adcsample_t *buffer = samples;
|
||||
for (uint8_t i = 0; i < ADC_DMA_BUF_DEPTH; i++) {
|
||||
for (uint8_t j = 0; j < ADC_GRP1_NUM_CHANNELS; j++) {
|
||||
sample_sum[j] += *buffer++;
|
||||
|
@ -63,7 +63,7 @@ public:
|
||||
float board_voltage(void) override { return _board_voltage; }
|
||||
float servorail_voltage(void) override { return _servorail_voltage; }
|
||||
uint16_t power_status_flags(void) override { return _power_flags; }
|
||||
static void adccallback(ADCDriver *adcp, adcsample_t *buffer, size_t n);
|
||||
static void adccallback(ADCDriver *adcp);
|
||||
|
||||
private:
|
||||
void read_adc(uint32_t *val);
|
||||
|
@ -63,7 +63,7 @@
|
||||
# endif
|
||||
#endif
|
||||
|
||||
#if (CH_KERNEL_MAJOR == 3 || CH_KERNEL_MAJOR == 4 || CH_KERNEL_MAJOR == 5)
|
||||
#if (CH_KERNEL_MAJOR == 3 || CH_KERNEL_MAJOR == 4 || CH_KERNEL_MAJOR == 5 || CH_KERNEL_MAJOR == 6)
|
||||
#define CAN1_TX_IRQHandler STM32_CAN1_TX_HANDLER
|
||||
#define CAN1_RX0_IRQHandler STM32_CAN1_RX0_HANDLER
|
||||
#define CAN1_RX1_IRQHandler STM32_CAN1_RX1_HANDLER
|
||||
@ -1213,10 +1213,16 @@ UAVCAN_STM32_IRQ_HANDLER(CAN1_RX1_IRQHandler)
|
||||
|
||||
# if UAVCAN_STM32_NUM_IFACES > 1
|
||||
|
||||
#if !defined(CAN2_TX_IRQHandler) ||\
|
||||
!defined(CAN2_RX0_IRQHandler) ||\
|
||||
!defined(CAN2_RX1_IRQHandler)
|
||||
# error "Misconfigured build"
|
||||
#if !defined(CAN2_TX_IRQHandler)
|
||||
# error "Misconfigured build1"
|
||||
#endif
|
||||
|
||||
#if !defined(CAN2_RX0_IRQHandler)
|
||||
# error "Misconfigured build2"
|
||||
#endif
|
||||
|
||||
#if !defined(CAN2_RX1_IRQHandler)
|
||||
# error "Misconfigured build3"
|
||||
#endif
|
||||
|
||||
UAVCAN_STM32_IRQ_HANDLER(CAN2_TX_IRQHandler);
|
||||
|
@ -820,8 +820,9 @@ void RCOutput::dma_allocate(Shared_DMA *ctx)
|
||||
for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
|
||||
pwm_group &group = pwm_group_list[i];
|
||||
if (group.dma_handle == ctx) {
|
||||
osalDbgAssert(group.dma == nullptr, "double DMA allocation");
|
||||
chSysLock();
|
||||
dmaStreamAllocate(group.dma, 10, dma_irq_callback, &group);
|
||||
group.dma = dmaStreamAllocI(group.dma_up_stream_id, 10, dma_irq_callback, &group);
|
||||
chSysUnlock();
|
||||
}
|
||||
}
|
||||
@ -836,7 +837,8 @@ void RCOutput::dma_deallocate(Shared_DMA *ctx)
|
||||
pwm_group &group = pwm_group_list[i];
|
||||
if (group.dma_handle == ctx) {
|
||||
chSysLock();
|
||||
dmaStreamRelease(group.dma);
|
||||
dmaStreamFreeI(group.dma);
|
||||
group.dma = nullptr;
|
||||
chSysUnlock();
|
||||
}
|
||||
}
|
||||
|
@ -36,13 +36,13 @@ bool SoftSigReader::attach_capture_timer(ICUDriver* icu_drv, icuchannel_t chan,
|
||||
}
|
||||
_icu_drv = icu_drv;
|
||||
//Setup Burst transfer of period and width measurement
|
||||
dma = STM32_DMA_STREAM(dma_stream);
|
||||
osalDbgAssert(dma == nullptr, "double DMA allocation");
|
||||
chSysLock();
|
||||
bool dma_allocated = dmaStreamAllocate(dma,
|
||||
dma = dmaStreamAllocI(dma_stream,
|
||||
12, //IRQ Priority
|
||||
(stm32_dmaisr_t)_irq_handler,
|
||||
(void *)this);
|
||||
osalDbgAssert(!dma_allocated, "stream already allocated");
|
||||
osalDbgAssert(dma, "stream allocation failed");
|
||||
chSysUnlock();
|
||||
//setup address for full word transfer from Timer
|
||||
dmaStreamSetPeripheral(dma, &icu_drv->tim->DMAR);
|
||||
|
@ -226,13 +226,13 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
//setup Rx DMA
|
||||
if(!_device_initialised) {
|
||||
if(sdef.dma_rx) {
|
||||
rxdma = STM32_DMA_STREAM(sdef.dma_rx_stream_id);
|
||||
osalDbgAssert(rxdma == nullptr, "double DMA allocation");
|
||||
chSysLock();
|
||||
bool dma_allocated = dmaStreamAllocate(rxdma,
|
||||
rxdma = dmaStreamAllocI(sdef.dma_rx_stream_id,
|
||||
12, //IRQ Priority
|
||||
(stm32_dmaisr_t)rxbuff_full_irq,
|
||||
(void *)this);
|
||||
osalDbgAssert(!dma_allocated, "stream already allocated");
|
||||
osalDbgAssert(rxdma, "stream alloc failed");
|
||||
chSysUnlock();
|
||||
#if defined(STM32F7)
|
||||
dmaStreamSetPeripheral(rxdma, &((SerialDriver*)sdef.serial)->usart->RDR);
|
||||
@ -315,13 +315,12 @@ void UARTDriver::dma_tx_allocate(Shared_DMA *ctx)
|
||||
{
|
||||
#if HAL_USE_SERIAL == TRUE
|
||||
osalDbgAssert(txdma == nullptr, "double DMA allocation");
|
||||
txdma = STM32_DMA_STREAM(sdef.dma_tx_stream_id);
|
||||
chSysLock();
|
||||
bool dma_allocated = dmaStreamAllocate(txdma,
|
||||
txdma = dmaStreamAllocI(sdef.dma_tx_stream_id,
|
||||
12, //IRQ Priority
|
||||
(stm32_dmaisr_t)tx_complete,
|
||||
(void *)this);
|
||||
osalDbgAssert(!dma_allocated, "stream already allocated");
|
||||
osalDbgAssert(txdma, "stream alloc failed");
|
||||
chSysUnlock();
|
||||
#if defined(STM32F7)
|
||||
dmaStreamSetPeripheral(txdma, &((SerialDriver*)sdef.serial)->usart->TDR);
|
||||
@ -334,7 +333,7 @@ void UARTDriver::dma_tx_allocate(Shared_DMA *ctx)
|
||||
void UARTDriver::dma_tx_deallocate(Shared_DMA *ctx)
|
||||
{
|
||||
chSysLock();
|
||||
dmaStreamRelease(txdma);
|
||||
dmaStreamFreeI(txdma);
|
||||
txdma = nullptr;
|
||||
chSysUnlock();
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user