Browse Source

AP_HAL_ChibiOS: move from HAL_NO_SHARED_DMA to AP_HAL_SHARED_DMA_ENABLED

This allows hwdef files to manipulate this value
apm_2208
Peter Barker 3 years ago committed by Peter Barker
parent
commit
13b03f79db
  1. 2
      libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp
  2. 4
      libraries/AP_HAL_ChibiOS/RCOutput.cpp
  3. 2
      libraries/AP_HAL_ChibiOS/Util.cpp
  4. 2
      libraries/AP_HAL_ChibiOS/hwdef/iomcu/hwdef.dat
  5. 2
      libraries/AP_HAL_ChibiOS/hwdef/iomcu_f103_8MHz/hwdef.dat
  6. 4
      libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py
  7. 2
      libraries/AP_HAL_ChibiOS/shared_dma.cpp
  8. 4
      libraries/AP_HAL_ChibiOS/shared_dma.h

2
libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp

@ -213,7 +213,7 @@ static void main_loop() @@ -213,7 +213,7 @@ static void main_loop()
ChibiOS::I2CBus::clear_all();
#endif
#ifndef HAL_NO_SHARED_DMA
#if AP_HAL_SHARED_DMA_ENABLED
ChibiOS::Shared_DMA::init();
#endif

4
libraries/AP_HAL_ChibiOS/RCOutput.cpp

@ -224,7 +224,7 @@ __RAMFUNC__ void RCOutput::dshot_update_tick(void* p) @@ -224,7 +224,7 @@ __RAMFUNC__ void RCOutput::dshot_update_tick(void* p)
chSysUnlockFromISR();
}
#ifndef HAL_NO_SHARED_DMA
#if AP_HAL_SHARED_DMA_ENABLED
// release locks on the groups that are pending in reverse order
void RCOutput::dshot_collect_dma_locks(uint32_t time_out_us)
{
@ -279,7 +279,7 @@ void RCOutput::dshot_collect_dma_locks(uint32_t time_out_us) @@ -279,7 +279,7 @@ void RCOutput::dshot_collect_dma_locks(uint32_t time_out_us)
}
}
}
#endif // HAL_NO_SHARED_DMA
#endif // AP_HAL_SHARED_DMA_ENABLED
/*
setup the output frequency for a group and start pwm output

2
libraries/AP_HAL_ChibiOS/Util.cpp

@ -461,7 +461,7 @@ __RAMFUNC__ void Util::thread_info(ExpandingString &str) @@ -461,7 +461,7 @@ __RAMFUNC__ void Util::thread_info(ExpandingString &str)
// request information on dma contention
void Util::dma_info(ExpandingString &str)
{
#ifndef HAL_NO_SHARED_DMA
#if AP_HAL_SHARED_DMA_ENABLED
ChibiOS::Shared_DMA::dma_info(str);
#endif
}

2
libraries/AP_HAL_ChibiOS/hwdef/iomcu/hwdef.dat

@ -119,7 +119,7 @@ define HAL_NO_TIMER_THREAD @@ -119,7 +119,7 @@ define HAL_NO_TIMER_THREAD
define HAL_NO_RCIN_THREAD
define HAL_NO_MONITOR_THREAD
define HAL_NO_RCOUT_THREAD
define HAL_NO_SHARED_DMA
define AP_HAL_SHARED_DMA_ENABLED 0
#defined to turn off undef warnings
define __FPU_PRESENT 0

2
libraries/AP_HAL_ChibiOS/hwdef/iomcu_f103_8MHz/hwdef.dat

@ -119,7 +119,7 @@ define HAL_NO_TIMER_THREAD @@ -119,7 +119,7 @@ define HAL_NO_TIMER_THREAD
define HAL_NO_RCIN_THREAD
define HAL_NO_MONITOR_THREAD
define HAL_NO_RCOUT_THREAD
define HAL_NO_SHARED_DMA
define AP_HAL_SHARED_DMA_ENABLED 0
#defined to turn off undef warnings
define __FPU_PRESENT 0

4
libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py

@ -1109,7 +1109,9 @@ def write_mcu_config(f): @@ -1109,7 +1109,9 @@ def write_mcu_config(f):
#define HAL_NO_TIMER_THREAD
#define HAL_NO_RCOUT_THREAD
#define HAL_NO_RCIN_THREAD
#define HAL_NO_SHARED_DMA FALSE
#ifndef AP_HAL_SHARED_DMA_ENABLED
#define AP_HAL_SHARED_DMA_ENABLED 0
#endif
#define HAL_NO_ROMFS_SUPPORT TRUE
#define CH_CFG_USE_TM FALSE
#define CH_CFG_USE_REGISTRY FALSE

2
libraries/AP_HAL_ChibiOS/shared_dma.cpp

@ -22,7 +22,7 @@ @@ -22,7 +22,7 @@
code to handle sharing of DMA channels between peripherals
*/
#if CH_CFG_USE_MUTEXES == TRUE && !defined(HAL_NO_SHARED_DMA)
#if CH_CFG_USE_MUTEXES == TRUE && AP_HAL_SHARED_DMA_ENABLED
#include <AP_Common/ExpandingString.h>

4
libraries/AP_HAL_ChibiOS/shared_dma.h

@ -23,7 +23,7 @@ @@ -23,7 +23,7 @@
// DMA stream ID for stream_id2 when only one is needed
#define SHARED_DMA_NONE 255
#ifndef HAL_NO_SHARED_DMA
#if AP_HAL_SHARED_DMA_ENABLED
class ChibiOS::Shared_DMA
{
@ -114,4 +114,4 @@ private: @@ -114,4 +114,4 @@ private:
} *_contention_stats;
};
#endif // HAL_NO_SHARED_DMA
#endif // AP_HAL_SHARED_DMA_ENABLED

Loading…
Cancel
Save