HAL_ChibiOS: disable features that require advanced dma

This commit is contained in:
Siddharth Purohit 2018-08-29 18:44:12 +05:30 committed by Andrew Tridgell
parent 0f07480faf
commit 87a2dea9d4
5 changed files with 44 additions and 8 deletions

View File

@ -158,8 +158,9 @@ static void main_loop()
ChibiOS::I2CBus::clear_all();
#endif
#if STM32_DMA_ADVANCED
ChibiOS::Shared_DMA::init();
#endif
peripheral_power_enable();
hal.uartA->begin(115200);

View File

@ -392,13 +392,17 @@ void RCOutput::push_local(void)
// this gives us a width in 125 ns increments, giving 1000 steps over the 125 to 250 range
uint32_t width = ((group.pwm_cfg.frequency/1000000U) * period_us) / 8U;
pwmEnableChannel(group.pwm_drv, j, width);
} else if (group.current_mode < MODE_PWM_DSHOT150) {
}
else if (group.current_mode < MODE_PWM_DSHOT150) {
uint32_t width = (group.pwm_cfg.frequency/1000000U) * period_us;
pwmEnableChannel(group.pwm_drv, j, width);
} else if (group.current_mode >= MODE_PWM_DSHOT150 && group.current_mode <= MODE_PWM_DSHOT1200) {
}
#ifndef DISABLE_DSHOT
else if (group.current_mode >= MODE_PWM_DSHOT150 && group.current_mode <= MODE_PWM_DSHOT1200) {
// set period_us to time for pulse output, to enable very fast rates
period_us = dshot_pulse_time_us;
}
#endif //#ifndef DISABLE_DSHOT
if (period_us > widest_pulse) {
widest_pulse = period_us;
}
@ -480,6 +484,7 @@ void RCOutput::read_last_sent(uint16_t* period_us, uint8_t len)
*/
bool RCOutput::mode_requires_dma(enum output_mode mode) const
{
#ifndef DISABLE_DSHOT
switch (mode) {
case MODE_PWM_DSHOT150:
case MODE_PWM_DSHOT300:
@ -489,6 +494,7 @@ bool RCOutput::mode_requires_dma(enum output_mode mode) const
default:
break;
}
#endif //#ifndef DISABLE_DSHOT
return false;
}
@ -500,6 +506,7 @@ bool RCOutput::mode_requires_dma(enum output_mode mode) const
*/
bool RCOutput::setup_group_DMA(pwm_group &group, uint32_t bitrate, uint32_t bit_width, bool active_high)
{
#ifndef DISABLE_DSHOT
if (!group.dma_buffer) {
group.dma_buffer = (uint32_t *)hal.util->malloc_type(dshot_buffer_length, AP_HAL::Util::MEM_DMA_SAFE);
if (!group.dma_buffer) {
@ -567,6 +574,9 @@ bool RCOutput::setup_group_DMA(pwm_group &group, uint32_t bitrate, uint32_t bit_
}
group.dma_handle->unlock();
return true;
#else
return false;
#endif //#ifndef DISABLE_DSHOT
}
@ -592,7 +602,7 @@ void RCOutput::set_group_mode(pwm_group &group)
write(chan, 0);
}
break;
case MODE_PWM_DSHOT150 ... MODE_PWM_DSHOT1200: {
const uint16_t rates[(1 + MODE_PWM_DSHOT1200) - MODE_PWM_DSHOT150] = { 150, 300, 600, 1200 };
uint32_t rate = rates[uint8_t(group.current_mode - MODE_PWM_DSHOT150)] * 1000UL;
@ -608,7 +618,7 @@ void RCOutput::set_group_mode(pwm_group &group)
dshot_pulse_time_us = 1000000UL * dshot_bit_length / rate;
break;
}
case MODE_PWM_ONESHOT:
case MODE_PWM_ONESHOT125:
// for oneshot we set a period of 0, which results in no pulses till we trigger
@ -875,6 +885,7 @@ void RCOutput::fill_DMA_buffer_dshot(uint32_t *buffer, uint8_t stride, uint16_t
*/
void RCOutput::dshot_send(pwm_group &group, bool blocking)
{
#ifndef DISABLE_DSHOT
if (irq.waiter) {
// doing serial output, don't send DShot pulses
return;
@ -923,6 +934,7 @@ void RCOutput::dshot_send(pwm_group &group, bool blocking)
send_pulses_DMAR(group, dshot_buffer_length);
group.last_dshot_send_us = AP_HAL::micros64();
#endif //#ifndef DISABLE_DSHOT
}
/*
@ -932,6 +944,7 @@ void RCOutput::dshot_send(pwm_group &group, bool blocking)
*/
void RCOutput::send_pulses_DMAR(pwm_group &group, uint32_t buffer_length)
{
#ifndef DISABLE_DSHOT
/*
The DMA approach we are using is based on the DMAR method from
betaflight. We use the TIMn_UP DMA channel for the timer, and
@ -959,6 +972,7 @@ void RCOutput::send_pulses_DMAR(pwm_group &group, uint32_t buffer_length)
group.pwm_drv->tim->DCR = 0x0D | STM32_TIM_DCR_DBL(3);
dmaStreamEnable(group.dma);
#endif //#ifndef DISABLE_DSHOT
}
/*
@ -966,10 +980,12 @@ void RCOutput::send_pulses_DMAR(pwm_group &group, uint32_t buffer_length)
*/
void RCOutput::dma_unlock(void *p)
{
#if STM32_DMA_ADVANCED
pwm_group *group = (pwm_group *)p;
chSysLockFromISR();
group->dma_handle->unlock_from_IRQ();
chSysUnlockFromISR();
chSysUnlockFromISR();
#endif
}
/*
@ -1114,6 +1130,7 @@ bool RCOutput::serial_write_byte(uint8_t b)
*/
bool RCOutput::serial_write_bytes(const uint8_t *bytes, uint16_t len)
{
#if STM32_DMA_ADVANCED
if (!serial_group) {
return false;
}
@ -1132,6 +1149,9 @@ bool RCOutput::serial_write_bytes(const uint8_t *bytes, uint16_t len)
serial_group->dma_handle->unlock();
return true;
#else
return false;
#endif //#if STM32_DMA_ADVANCED
}
/*
@ -1239,6 +1259,7 @@ bool RCOutput::serial_read_byte(uint8_t &b)
*/
uint16_t RCOutput::serial_read_bytes(uint8_t *buf, uint16_t len)
{
#ifndef DISABLE_SERIAL_ESC_COMM
if (serial_group == nullptr) {
return 0;
}
@ -1292,6 +1313,10 @@ uint16_t RCOutput::serial_read_bytes(uint8_t *buf, uint16_t len)
palWriteLine(HAL_GPIO_LINE_GPIO54, 0);
#endif
return i;
#else
return false;
#endif //#ifndef DISABLE_SERIAL_ESC_COMM
}
/*
@ -1299,6 +1324,7 @@ uint16_t RCOutput::serial_read_bytes(uint8_t *buf, uint16_t len)
*/
void RCOutput::serial_end(void)
{
#ifndef DISABLE_SERIAL_ESC_COMM
if (serial_group) {
if (serial_thread == chThdGetSelfX()) {
chThdSetPriority(serial_priority);
@ -1317,6 +1343,7 @@ void RCOutput::serial_end(void)
}
}
serial_group = nullptr;
#endif //#ifndef DISABLE_SERIAL_ESC_COMM
}
/*

View File

@ -23,6 +23,10 @@
#if HAL_USE_PWM == TRUE
#if !STM32_DMA_ADVANCED
#define DISABLE_DSHOT
#endif
class ChibiOS::RCOutput : public AP_HAL::RCOutput {
public:
void init();

View File

@ -20,7 +20,7 @@
code to handle sharing of DMA channels between peripherals
*/
#if CH_CFG_USE_SEMAPHORES == TRUE
#if CH_CFG_USE_SEMAPHORES == TRUE && STM32_DMA_ADVANCED
using namespace ChibiOS;
@ -186,4 +186,4 @@ void Shared_DMA::lock_all(void)
}
}
#endif // CH_CFG_USE_SEMAPHORES
#endif // CH_CFG_USE_SEMAPHORES && STM32_DMA_ADVANCED

View File

@ -18,6 +18,8 @@
#include "AP_HAL_ChibiOS.h"
#if STM32_DMA_ADVANCED
#define SHARED_DMA_MAX_STREAM_ID (8*2)
// DMA stream ID for stream_id2 when only one is needed
@ -92,4 +94,6 @@ private:
Shared_DMA *obj;
} locks[SHARED_DMA_MAX_STREAM_ID];
};
#endif //#if STM32_DMA_ADVANCED