auto-sync
This commit is contained in:
parent
de089f2c8c
commit
a7d7cf9cf3
|
@ -60,11 +60,17 @@
|
|||
RCC_AHBENR_GPIOEEN | RCC_AHBENR_GPIOFEN)
|
||||
|
||||
#elif defined(STM32F4XX)
|
||||
#if STM32_HAS_GPIOF && STM32_HAS_GPIOG && STM32_HAS_GPIOI
|
||||
#define AHB1_EN_MASK (RCC_AHB1ENR_GPIOAEN | RCC_AHB1ENR_GPIOBEN | \
|
||||
RCC_AHB1ENR_GPIOCEN | RCC_AHB1ENR_GPIODEN | \
|
||||
RCC_AHB1ENR_GPIOEEN | RCC_AHB1ENR_GPIOFEN | \
|
||||
RCC_AHB1ENR_GPIOGEN | RCC_AHB1ENR_GPIOHEN | \
|
||||
RCC_AHB1ENR_GPIOIEN)
|
||||
#else
|
||||
#define AHB1_EN_MASK (RCC_AHB1ENR_GPIOAEN | RCC_AHB1ENR_GPIOBEN | \
|
||||
RCC_AHB1ENR_GPIOCEN | RCC_AHB1ENR_GPIODEN | \
|
||||
RCC_AHB1ENR_GPIOEEN)
|
||||
#endif /* STM32_HAS_GPIOF && STM32_HAS_GPIOG && STM32_HAS_GPIOI */
|
||||
#define AHB1_LPEN_MASK AHB1_EN_MASK
|
||||
|
||||
#else
|
||||
|
|
|
@ -642,7 +642,8 @@ static void usb_lld_serve_interrupt(USBDriver *usbp) {
|
|||
stm32_otg_t *otgp = usbp->otg;
|
||||
uint32_t sts, src;
|
||||
|
||||
sts = otgp->GINTSTS & otgp->GINTMSK;
|
||||
sts = otgp->GINTSTS;
|
||||
sts &= otgp->GINTMSK;
|
||||
otgp->GINTSTS = sts;
|
||||
|
||||
/* Reset interrupt handling.*/
|
||||
|
@ -765,7 +766,7 @@ static msg_t usb_lld_pump(void *p) {
|
|||
}
|
||||
chSysLock();
|
||||
}
|
||||
chSysUnlock();
|
||||
// we are never here but GCC cannot figure this out
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
@ -835,7 +836,7 @@ void usb_lld_init(void) {
|
|||
(uint8_t *)wsp + sizeof(Thread),
|
||||
CH_THREAD_FILL_VALUE);
|
||||
_thread_memfill((uint8_t *)wsp + sizeof(Thread),
|
||||
(uint8_t *)wsp + sizeof(USBD1.wa_pump) - sizeof(Thread),
|
||||
(uint8_t *)wsp + sizeof(USBD1.wa_pump),
|
||||
CH_STACK_FILL_VALUE);
|
||||
}
|
||||
#endif
|
||||
|
@ -857,7 +858,7 @@ void usb_lld_init(void) {
|
|||
(uint8_t *)wsp + sizeof(Thread),
|
||||
CH_THREAD_FILL_VALUE);
|
||||
_thread_memfill((uint8_t *)wsp + sizeof(Thread),
|
||||
(uint8_t *)wsp + sizeof(USBD2.wa_pump) - sizeof(Thread),
|
||||
(uint8_t *)wsp + sizeof(USBD2.wa_pump),
|
||||
CH_STACK_FILL_VALUE);
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -151,9 +151,11 @@ void rtc_lld_get_time(RTCDriver *rtcp, RTCTime *timespec) {
|
|||
rtc_lld_apb1_sync();
|
||||
|
||||
#if STM32_RTC_HAS_SUBSECONDS
|
||||
timespec->tv_msec =
|
||||
(1000 * ((RTCD1.id_rtc->PRER & 0x7FFF) - RTCD1.id_rtc->SSR)) /
|
||||
((RTCD1.id_rtc->PRER & 0x7FFF) + 1);
|
||||
{
|
||||
uint32_t prer = RTCD1.id_rtc->PRER & 0x7FFF;
|
||||
uint32_t ssr = RTCD1.id_rtc->SSR;
|
||||
timespec->tv_msec = (1000 * (prer - ssr)) / (prer + 1);
|
||||
}
|
||||
#endif /* STM32_RTC_HAS_SUBSECONDS */
|
||||
timespec->tv_time = RTCD1.id_rtc->TR;
|
||||
timespec->tv_date = RTCD1.id_rtc->DR;
|
||||
|
|
|
@ -399,7 +399,6 @@ void pwm_lld_init(void) {
|
|||
void pwm_lld_start(PWMDriver *pwmp) {
|
||||
uint32_t psc;
|
||||
uint32_t ccer;
|
||||
uint32_t dier;
|
||||
|
||||
if (pwmp->state == PWM_STOP) {
|
||||
/* Clock activation and timer reset.*/
|
||||
|
|
|
@ -201,27 +201,32 @@ typedef struct {
|
|||
#define RXCOUNT_COUNT_MASK 0x03FF
|
||||
#define TXCOUNT_COUNT_MASK 0x03FF
|
||||
|
||||
#define EPR_CTR_MASK (EPR_CTR_TX | EPR_CTR_RX)
|
||||
|
||||
#define EPR_SET(ep, epr) \
|
||||
STM32_USB->EPR[ep] = (epr) & ~EPR_TOGGLE_MASK
|
||||
STM32_USB->EPR[ep] = ((epr) & ~EPR_TOGGLE_MASK) | EPR_CTR_MASK
|
||||
|
||||
#define EPR_TOGGLE(ep, epr) \
|
||||
STM32_USB->EPR[ep] = (STM32_USB->EPR[ep] ^ ((epr) & EPR_TOGGLE_MASK))
|
||||
STM32_USB->EPR[ep] = (STM32_USB->EPR[ep] ^ ((epr) & EPR_TOGGLE_MASK)) \
|
||||
| EPR_CTR_MASK
|
||||
|
||||
#define EPR_SET_STAT_RX(ep, epr) \
|
||||
STM32_USB->EPR[ep] = (STM32_USB->EPR[ep] & \
|
||||
STM32_USB->EPR[ep] = ((STM32_USB->EPR[ep] & \
|
||||
~(EPR_TOGGLE_MASK & ~EPR_STAT_RX_MASK)) ^ \
|
||||
(epr)
|
||||
(epr)) | EPR_CTR_MASK
|
||||
|
||||
#define EPR_SET_STAT_TX(ep, epr) \
|
||||
STM32_USB->EPR[ep] = (STM32_USB->EPR[ep] & \
|
||||
STM32_USB->EPR[ep] = ((STM32_USB->EPR[ep] & \
|
||||
~(EPR_TOGGLE_MASK & ~EPR_STAT_TX_MASK)) ^ \
|
||||
(epr)
|
||||
(epr)) | EPR_CTR_MASK
|
||||
|
||||
#define EPR_CLEAR_CTR_RX(ep) \
|
||||
STM32_USB->EPR[ep] &= ~EPR_CTR_RX & ~EPR_TOGGLE_MASK
|
||||
STM32_USB->EPR[ep] = (STM32_USB->EPR[ep] & ~EPR_CTR_RX & ~EPR_TOGGLE_MASK)\
|
||||
| EPR_CTR_TX
|
||||
|
||||
#define EPR_CLEAR_CTR_TX(ep) \
|
||||
STM32_USB->EPR[ep] &= ~EPR_CTR_TX & ~EPR_TOGGLE_MASK
|
||||
STM32_USB->EPR[ep] = (STM32_USB->EPR[ep] & ~EPR_CTR_TX & ~EPR_TOGGLE_MASK)\
|
||||
| EPR_CTR_RX
|
||||
|
||||
/**
|
||||
* @brief Returns an endpoint descriptor pointer.
|
||||
|
|
|
@ -190,12 +190,12 @@ void adc_lld_start(ADCDriver *adcp) {
|
|||
rccEnableADC1(FALSE);
|
||||
#if STM32_ADCSW == STM32_ADCSW_HSI14
|
||||
/* Clock from HSI14, no need for jitter removal.*/
|
||||
ADC1->CFGR2 = 0x00001000;
|
||||
ADC1->CFGR2 = 0;
|
||||
#else
|
||||
#if STM32_ADCPRE == STM32_ADCPRE_DIV2
|
||||
ADC1->CFGR2 = 0x00001000 | ADC_CFGR2_JITOFFDIV2;
|
||||
ADC1->CFGR2 = ADC_CFGR2_JITOFFDIV2;
|
||||
#else
|
||||
ADC1->CFGR2 = 0x00001000 | ADC_CFGR2_JITOFFDIV4;
|
||||
ADC1->CFGR2 = ADC_CFGR2_JITOFFDIV4;
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
|
|
@ -142,10 +142,18 @@ void stm32_clock_init(void) {
|
|||
RCC->CR |= RCC_CR_HSION; /* Make sure HSI is ON. */
|
||||
while (!(RCC->CR & RCC_CR_HSIRDY))
|
||||
; /* Wait until HSI is stable. */
|
||||
|
||||
/* HSI is selected as new source without touching the other fields in
|
||||
CFGR. Clearing the register has to be postponed after HSI is the
|
||||
new source.*/
|
||||
RCC->CFGR &= ~RCC_CFGR_SW; /* Reset SW */
|
||||
RCC->CFGR |= RCC_CFGR_SWS_HSI; /* Select HSI as internal*/
|
||||
while ((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_HSI)
|
||||
; /* Wait until HSI is selected. */
|
||||
|
||||
/* Registers finally cleared to reset values.*/
|
||||
RCC->CR &= RCC_CR_HSITRIM | RCC_CR_HSION; /* CR Reset value. */
|
||||
RCC->CFGR = 0; /* CFGR reset value. */
|
||||
while ((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_HSI)
|
||||
; /* Waits until HSI is selected. */
|
||||
|
||||
#if STM32_HSE_ENABLED
|
||||
/* HSE activation.*/
|
||||
|
|
|
@ -152,10 +152,18 @@ void stm32_clock_init(void) {
|
|||
RCC->CR |= RCC_CR_HSION; /* Make sure HSI is ON. */
|
||||
while (!(RCC->CR & RCC_CR_HSIRDY))
|
||||
; /* Wait until HSI is stable. */
|
||||
|
||||
/* HSI is selected as new source without touching the other fields in
|
||||
CFGR. Clearing the register has to be postponed after HSI is the
|
||||
new source.*/
|
||||
RCC->CFGR &= ~RCC_CFGR_SW; /* Reset SW */
|
||||
RCC->CFGR |= RCC_CFGR_SWS_HSI; /* Select HSI as internal*/
|
||||
while ((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_HSI)
|
||||
; /* Wait until HSI is selected. */
|
||||
|
||||
/* Registers finally cleared to reset values.*/
|
||||
RCC->CR &= RCC_CR_HSITRIM | RCC_CR_HSION; /* CR Reset value. */
|
||||
RCC->CFGR = 0; /* CFGR reset value. */
|
||||
while ((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_HSI)
|
||||
; /* Waits until HSI is selected. */
|
||||
|
||||
#if STM32_HSE_ENABLED
|
||||
#if defined(STM32_HSE_BYPASS)
|
||||
|
|
|
@ -322,6 +322,7 @@ void adc_lld_stop(ADCDriver *adcp) {
|
|||
*/
|
||||
void adc_lld_start_conversion(ADCDriver *adcp) {
|
||||
uint32_t mode;
|
||||
uint32_t cr2;
|
||||
const ADCConversionGroup *grpp = adcp->grpp;
|
||||
|
||||
/* DMA setup.*/
|
||||
|
@ -348,15 +349,23 @@ void adc_lld_start_conversion(ADCDriver *adcp) {
|
|||
adcp->adc->SQR2 = grpp->sqr2;
|
||||
adcp->adc->SQR3 = grpp->sqr3;
|
||||
|
||||
/* ADC configuration and start, the start is performed using the method
|
||||
specified in the CR2 configuration, usually ADC_CR2_SWSTART.*/
|
||||
/* ADC configuration and start.*/
|
||||
adcp->adc->CR1 = grpp->cr1 | ADC_CR1_OVRIE | ADC_CR1_SCAN;
|
||||
if ((grpp->cr2 & ADC_CR2_SWSTART) != 0)
|
||||
adcp->adc->CR2 = grpp->cr2 | ADC_CR2_CONT | ADC_CR2_DMA |
|
||||
ADC_CR2_DDS | ADC_CR2_ADON;
|
||||
|
||||
/* Enforcing the mandatory bits in CR2.*/
|
||||
cr2 = grpp->cr2 | ADC_CR2_DMA | ADC_CR2_DDS | ADC_CR2_ADON;
|
||||
|
||||
/* The start method is different dependign if HW or SW triggered, the
|
||||
start is performed using the method specified in the CR2 configuration.*/
|
||||
if ((cr2 & ADC_CR2_SWSTART) != 0) {
|
||||
/* Initializing CR2 while keeping ADC_CR2_SWSTART at zero.*/
|
||||
adcp->adc->CR2 = (cr2 | ADC_CR2_CONT) & ~ADC_CR2_SWSTART;
|
||||
|
||||
/* Finally enabling ADC_CR2_SWSTART.*/
|
||||
adcp->adc->CR2 = (cr2 | ADC_CR2_CONT);
|
||||
}
|
||||
else
|
||||
adcp->adc->CR2 = grpp->cr2 | ADC_CR2_DMA |
|
||||
ADC_CR2_DDS | ADC_CR2_ADON;
|
||||
adcp->adc->CR2 = cr2;
|
||||
}
|
||||
|
||||
/**
|
||||
|
|
|
@ -224,6 +224,7 @@ CH_IRQ_HANDLER(OTG_FS_WKUP_IRQHandler) {
|
|||
CH_IRQ_EPILOGUE();
|
||||
}
|
||||
|
||||
#if !defined(STM32F401xx)
|
||||
/**
|
||||
* @brief EXTI[19] interrupt handler (ETH_WKUP).
|
||||
*
|
||||
|
@ -239,7 +240,6 @@ CH_IRQ_HANDLER(ETH_WKUP_IRQHandler) {
|
|||
CH_IRQ_EPILOGUE();
|
||||
}
|
||||
|
||||
#if !defined(STM32F401xx)
|
||||
/**
|
||||
* @brief EXTI[20] interrupt handler (OTG_HS_WKUP).
|
||||
*
|
||||
|
|
|
@ -169,10 +169,18 @@ void stm32_clock_init(void) {
|
|||
RCC->CR |= RCC_CR_HSION; /* Make sure HSI is ON. */
|
||||
while (!(RCC->CR & RCC_CR_HSIRDY))
|
||||
; /* Wait until HSI is stable. */
|
||||
|
||||
/* HSI is selected as new source without touching the other fields in
|
||||
CFGR. Clearing the register has to be postponed after HSI is the
|
||||
new source.*/
|
||||
RCC->CFGR &= ~RCC_CFGR_SW; /* Reset SW */
|
||||
RCC->CFGR |= RCC_CFGR_SWS_HSI; /* Select HSI as internal*/
|
||||
while ((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_HSI)
|
||||
; /* Wait until HSI is selected. */
|
||||
|
||||
/* Registers finally cleared to reset values.*/
|
||||
RCC->CR &= RCC_CR_HSITRIM | RCC_CR_HSION; /* CR Reset value. */
|
||||
RCC->CFGR = 0; /* CFGR reset value. */
|
||||
while ((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_HSI)
|
||||
; /* Waits until HSI is selected. */
|
||||
|
||||
#if STM32_HSE_ENABLED
|
||||
/* HSE activation.*/
|
||||
|
|
|
@ -1096,7 +1096,7 @@
|
|||
#define STM32_1WS_THRESHOLD 36000000
|
||||
#define STM32_2WS_THRESHOLD 54000000
|
||||
#define STM32_3WS_THRESHOLD 72000000
|
||||
#define STM32_4WS_THRESHOLD 840000000
|
||||
#define STM32_4WS_THRESHOLD 84000000
|
||||
#define STM32_5WS_THRESHOLD 0
|
||||
#define STM32_6WS_THRESHOLD 0
|
||||
#define STM32_7WS_THRESHOLD 0
|
||||
|
@ -1106,8 +1106,8 @@
|
|||
#define STM32_1WS_THRESHOLD 32000000
|
||||
#define STM32_2WS_THRESHOLD 48000000
|
||||
#define STM32_3WS_THRESHOLD 64000000
|
||||
#define STM32_4WS_THRESHOLD 800000000
|
||||
#define STM32_5WS_THRESHOLD 840000000
|
||||
#define STM32_4WS_THRESHOLD 80000000
|
||||
#define STM32_5WS_THRESHOLD 84000000
|
||||
#define STM32_6WS_THRESHOLD 0
|
||||
#define STM32_7WS_THRESHOLD 0
|
||||
#define STM32_8WS_THRESHOLD 0
|
||||
|
|
|
@ -47,7 +47,7 @@
|
|||
/**
|
||||
* @brief Kernel version string.
|
||||
*/
|
||||
#define CH_KERNEL_VERSION "2.6.6"
|
||||
#define CH_KERNEL_VERSION "2.6.7"
|
||||
|
||||
/**
|
||||
* @name Kernel version
|
||||
|
@ -66,7 +66,7 @@
|
|||
/**
|
||||
* @brief Kernel version patch number.
|
||||
*/
|
||||
#define CH_KERNEL_PATCH 6
|
||||
#define CH_KERNEL_PATCH 7
|
||||
/** @} */
|
||||
|
||||
/**
|
||||
|
|
|
@ -123,7 +123,7 @@ typedef struct {
|
|||
* @details This function writes a byte value to a channel. If the channel
|
||||
* is not ready to accept data then the calling thread is suspended.
|
||||
*
|
||||
* @param[in] ip pointer to a @p BaseChannel or derived class
|
||||
* @param[in] ip pointer to a @p BaseSequentialStream or derived class
|
||||
* @param[in] b the byte value to be written to the channel
|
||||
*
|
||||
* @return The operation status.
|
||||
|
@ -139,7 +139,7 @@ typedef struct {
|
|||
* @details This function reads a byte value from a channel. If the data
|
||||
* is not available then the calling thread is suspended.
|
||||
*
|
||||
* @param[in] ip pointer to a @p BaseChannel or derived class
|
||||
* @param[in] ip pointer to a @p BaseSequentialStream or derived class
|
||||
*
|
||||
* @return A byte value from the queue.
|
||||
* @retval Q_RESET if an end-of-file condition has been met.
|
||||
|
|
|
@ -358,7 +358,7 @@ eventmask_t chEvtWaitOne(eventmask_t mask) {
|
|||
chSchGoSleepS(THD_STATE_WTOREVT);
|
||||
m = ctp->p_epending & mask;
|
||||
}
|
||||
m &= -m;
|
||||
m ^= m & (m - 1);
|
||||
ctp->p_epending &= ~m;
|
||||
|
||||
chSysUnlock();
|
||||
|
@ -461,7 +461,7 @@ eventmask_t chEvtWaitOneTimeout(eventmask_t mask, systime_t time) {
|
|||
}
|
||||
m = ctp->p_epending & mask;
|
||||
}
|
||||
m &= -m;
|
||||
m ^= m & (m - 1);
|
||||
ctp->p_epending &= ~m;
|
||||
|
||||
chSysUnlock();
|
||||
|
|
|
@ -161,7 +161,7 @@ void _port_irq_epilogue(void) {
|
|||
#if CORTEX_USE_FPU
|
||||
/* Enforcing a lazy FPU state save. Note, it goes in the original
|
||||
context because the FPCAR register has not been modified.*/
|
||||
(void)__get_FPSCR();
|
||||
(void)__get_FPSCR();
|
||||
#endif
|
||||
|
||||
/* Current PSP value.*/
|
||||
|
|
|
@ -172,11 +172,11 @@
|
|||
|
||||
/**
|
||||
* @brief PendSV priority level.
|
||||
* @note This priority is enforced to be equal to @p CORTEX_BASEPRI_KERNEL,
|
||||
* this handler always have the highest priority that cannot preempt
|
||||
* the kernel.
|
||||
* @note This priority is enforced to be equal to
|
||||
* @p CORTEX_MAX_KERNEL_PRIORITY, this handler always have the
|
||||
* highest priority that cannot preempt the kernel.
|
||||
*/
|
||||
#define CORTEX_PRIORITY_PENDSV CORTEX_BASEPRI_KERNEL
|
||||
#define CORTEX_PRIORITY_PENDSV CORTEX_MAX_KERNEL_PRIORITY
|
||||
|
||||
/*===========================================================================*/
|
||||
/* Port exported info. */
|
||||
|
|
|
@ -1,5 +1,5 @@
|
|||
|
||||
In this folder we have ChibiOS 2.6.6 with rusefi_chibios.patch applied.
|
||||
In this folder we have ChibiOS 2.6.7 with rusefi_chibios.patch applied.
|
||||
http://chibios.org/
|
||||
|
||||
rusefi_chibios.patch is only about minor improvements to fatal error message - like __FILE__ info and maybe better messages.
|
|
@ -1,7 +1,7 @@
|
|||
Index: chibios/boards/ST_STM32F4_DISCOVERY/board.h
|
||||
Index: boards/ST_STM32F4_DISCOVERY/board.h
|
||||
===================================================================
|
||||
--- chibios/boards/ST_STM32F4_DISCOVERY/board.h (revision 6923)
|
||||
+++ chibios/boards/ST_STM32F4_DISCOVERY/board.h (working copy)
|
||||
--- boards/ST_STM32F4_DISCOVERY/board.h (revision 2723)
|
||||
+++ boards/ST_STM32F4_DISCOVERY/board.h (working copy)
|
||||
@@ -27,6 +27,7 @@
|
||||
#define BOARD_ST_STM32F4_DISCOVERY
|
||||
#define BOARD_NAME "STMicroelectronics STM32F4-Discovery"
|
||||
|
@ -10,65 +10,10 @@ Index: chibios/boards/ST_STM32F4_DISCOVERY/board.h
|
|||
|
||||
/*
|
||||
* Board oscillators-related settings.
|
||||
Index: chibios/os/hal/platforms/STM32F4xx/adc_lld.c
|
||||
Index: os/kernel/src/chdebug.c
|
||||
===================================================================
|
||||
--- chibios/os/hal/platforms/STM32F4xx/adc_lld.c (revision 6923)
|
||||
+++ chibios/os/hal/platforms/STM32F4xx/adc_lld.c (working copy)
|
||||
@@ -67,6 +67,8 @@
|
||||
/* Driver local functions. */
|
||||
/*===========================================================================*/
|
||||
|
||||
+#include "error_handling.h"
|
||||
+
|
||||
/**
|
||||
* @brief ADC DMA ISR service routine.
|
||||
*
|
||||
@@ -75,6 +77,8 @@
|
||||
*/
|
||||
static void adc_lld_serve_rx_interrupt(ADCDriver *adcp, uint32_t flags) {
|
||||
|
||||
+ efiAssertVoid(getRemainingStack(chThdSelf()) > 64, "sys_adc");
|
||||
+
|
||||
/* DMA errors handling.*/
|
||||
if ((flags & (STM32_DMA_ISR_TEIF | STM32_DMA_ISR_DMEIF)) != 0) {
|
||||
/* DMA, this could help only if the DMA tries to access an unmapped
|
||||
Index: chibios/os/kernel/include/chdebug.h
|
||||
===================================================================
|
||||
--- chibios/os/kernel/include/chdebug.h (revision 6923)
|
||||
+++ chibios/os/kernel/include/chdebug.h (working copy)
|
||||
@@ -59,6 +59,17 @@
|
||||
#define CH_TRACE_BUFFER_SIZE 64
|
||||
#endif
|
||||
|
||||
+#ifdef __cplusplus
|
||||
+extern "C"
|
||||
+{
|
||||
+#endif /* __cplusplus */
|
||||
+
|
||||
+void chDbgPanic3(const char *msg, const char * file, int line);
|
||||
+
|
||||
+#ifdef __cplusplus
|
||||
+}
|
||||
+#endif /* __cplusplus */
|
||||
+
|
||||
/**
|
||||
* @brief Fill value for thread stack area in debug mode.
|
||||
*/
|
||||
@@ -98,8 +109,8 @@
|
||||
#define chDbgCheckClassI()
|
||||
#define chDbgCheckClassS()
|
||||
#else
|
||||
-#define dbg_enter_lock() (dbg_lock_cnt = 1)
|
||||
-#define dbg_leave_lock() (dbg_lock_cnt = 0)
|
||||
+#define dbg_enter_lock() {dbg_lock_cnt = 1;ON_LOCK_HOOK;}
|
||||
+#define dbg_leave_lock() {dbg_lock_cnt = 0;ON_UNLOCK_HOOK;}
|
||||
#endif
|
||||
|
||||
/*===========================================================================*/
|
||||
Index: chibios/os/kernel/src/chdebug.c
|
||||
===================================================================
|
||||
--- chibios/os/kernel/src/chdebug.c (revision 6923)
|
||||
+++ chibios/os/kernel/src/chdebug.c (working copy)
|
||||
--- os/kernel/src/chdebug.c (revision 2723)
|
||||
+++ os/kernel/src/chdebug.c (working copy)
|
||||
@@ -114,7 +114,7 @@
|
||||
void dbg_check_lock(void) {
|
||||
|
||||
|
@ -87,32 +32,7 @@ Index: chibios/os/kernel/src/chdebug.c
|
|||
dbg_enter_lock();
|
||||
}
|
||||
|
||||
@@ -154,6 +154,10 @@
|
||||
dbg_leave_lock();
|
||||
}
|
||||
|
||||
+void firmwareError(const char *fmt, ...);
|
||||
+
|
||||
+extern int maxNesting;
|
||||
+
|
||||
/**
|
||||
* @brief Guard code for @p CH_IRQ_PROLOGUE().
|
||||
*
|
||||
@@ -160,11 +164,12 @@
|
||||
* @notapi
|
||||
*/
|
||||
void dbg_check_enter_isr(void) {
|
||||
-
|
||||
port_lock_from_isr();
|
||||
if ((dbg_isr_cnt < 0) || (dbg_lock_cnt != 0))
|
||||
chDbgPanic("SV#8");
|
||||
dbg_isr_cnt++;
|
||||
+ if (dbg_isr_cnt > maxNesting)
|
||||
+ maxNesting = dbg_isr_cnt;
|
||||
port_unlock_from_isr();
|
||||
}
|
||||
|
||||
@@ -193,7 +198,7 @@
|
||||
@@ -193,7 +193,7 @@
|
||||
void chDbgCheckClassI(void) {
|
||||
|
||||
if ((dbg_isr_cnt < 0) || (dbg_lock_cnt <= 0))
|
||||
|
@ -121,12 +41,12 @@ Index: chibios/os/kernel/src/chdebug.c
|
|||
}
|
||||
|
||||
/**
|
||||
@@ -268,10 +273,11 @@
|
||||
@@ -268,10 +268,11 @@
|
||||
*
|
||||
* @param[in] msg the pointer to the panic message string
|
||||
*/
|
||||
+
|
||||
+void chDbgPanic3(const char *msg, const char * file, int line);
|
||||
+void chDbgPanic3(const char *msg, char * file, int line);
|
||||
+
|
||||
void chDbgPanic(const char *msg) {
|
||||
-
|
||||
|
@ -136,149 +56,51 @@ Index: chibios/os/kernel/src/chdebug.c
|
|||
}
|
||||
#endif /* CH_DBG_ENABLED */
|
||||
|
||||
Index: chibios/os/kernel/src/chvt.c
|
||||
Index: os/ports/GCC/ARMCMx/chcore_v7m.h
|
||||
===================================================================
|
||||
--- chibios/os/kernel/src/chvt.c (revision 6923)
|
||||
+++ chibios/os/kernel/src/chvt.c (working copy)
|
||||
@@ -77,6 +77,9 @@
|
||||
VirtualTimer *p;
|
||||
--- os/ports/GCC/ARMCMx/chcore_v7m.h (revision 2723)
|
||||
+++ os/ports/GCC/ARMCMx/chcore_v7m.h (working copy)
|
||||
@@ -36,6 +36,8 @@
|
||||
#ifndef _CHCORE_V7M_H_
|
||||
#define _CHCORE_V7M_H_
|
||||
|
||||
chDbgCheckClassI();
|
||||
+ chDbgCheck(vtp != NULL, "chVTSetI 1");
|
||||
+ chDbgCheck(vtfunc != NULL, "chVTSetI 2");
|
||||
+ chDbgCheck(time != TIME_IMMEDIATE, "chVTSetI 3");
|
||||
chDbgCheck((vtp != NULL) && (vtfunc != NULL) && (time != TIME_IMMEDIATE),
|
||||
"chVTSetI");
|
||||
|
||||
Index: chibios/os/ports/GCC/ARMCMx/chcore_v6m.h
|
||||
===================================================================
|
||||
--- chibios/os/ports/GCC/ARMCMx/chcore_v6m.h (revision 6923)
|
||||
+++ chibios/os/ports/GCC/ARMCMx/chcore_v6m.h (working copy)
|
||||
@@ -270,6 +270,8 @@
|
||||
*/
|
||||
#define PORT_FAST_IRQ_HANDLER(id) void id(void)
|
||||
|
||||
+int getRemainingStack(Thread *otp);
|
||||
+#include "chdebug.h"
|
||||
+
|
||||
/**
|
||||
* @brief Port-related initialization code.
|
||||
*/
|
||||
Index: chibios/os/ports/GCC/ARMCMx/chcore_v7m.h
|
||||
===================================================================
|
||||
--- chibios/os/ports/GCC/ARMCMx/chcore_v7m.h (revision 6923)
|
||||
+++ chibios/os/ports/GCC/ARMCMx/chcore_v7m.h (working copy)
|
||||
@@ -486,6 +486,10 @@
|
||||
/*===========================================================================*/
|
||||
/* Port constants. */
|
||||
/*===========================================================================*/
|
||||
@@ -486,6 +488,8 @@
|
||||
#define port_wait_for_interrupt()
|
||||
#endif
|
||||
|
||||
+void chDbgStackOverflowPanic(Thread *otp);
|
||||
+
|
||||
+int getRemainingStack(Thread *otp);
|
||||
+
|
||||
/**
|
||||
* @brief Performs a context switch between two threads.
|
||||
* @details This is the most critical code in any port, this function
|
||||
@@ -500,9 +504,8 @@
|
||||
#define port_switch(ntp, otp) _port_switch(ntp, otp)
|
||||
#else
|
||||
@@ -502,7 +506,7 @@
|
||||
#define port_switch(ntp, otp) { \
|
||||
- register struct intctx *r13 asm ("r13"); \
|
||||
- if ((stkalign_t *)(r13 - 1) < otp->p_stklimit) \
|
||||
register struct intctx *r13 asm ("r13"); \
|
||||
if ((stkalign_t *)(r13 - 1) < otp->p_stklimit) \
|
||||
- chDbgPanic("stack overflow"); \
|
||||
+ if (getRemainingStack(otp) < 0) \
|
||||
+ chDbgStackOverflowPanic(otp); \
|
||||
_port_switch(ntp, otp); \
|
||||
}
|
||||
#endif
|
||||
Index: chibios/os/ports/GCC/ARMCMx/rules.mk
|
||||
Index: os/ports/GCC/ARMCMx/rules.mk
|
||||
===================================================================
|
||||
--- chibios/os/ports/GCC/ARMCMx/rules.mk (revision 6923)
|
||||
+++ chibios/os/ports/GCC/ARMCMx/rules.mk (working copy)
|
||||
@@ -1,45 +1,5 @@
|
||||
# ARM Cortex-Mx common makefile scripts and rules.
|
||||
|
||||
-##############################################################################
|
||||
-# Processing options coming from the upper Makefile.
|
||||
-#
|
||||
-
|
||||
-# Compiler options
|
||||
-OPT = $(USE_OPT)
|
||||
-COPT = $(USE_COPT)
|
||||
-CPPOPT = $(USE_CPPOPT)
|
||||
-
|
||||
-# Garbage collection
|
||||
-ifeq ($(USE_LINK_GC),yes)
|
||||
- OPT += -ffunction-sections -fdata-sections -fno-common
|
||||
- LDOPT := ,--gc-sections
|
||||
-else
|
||||
- LDOPT :=
|
||||
-endif
|
||||
-
|
||||
-# Linker extra options
|
||||
-ifneq ($(USE_LDOPT),)
|
||||
- LDOPT := $(LDOPT),$(USE_LDOPT)
|
||||
-endif
|
||||
-
|
||||
-# Link time optimizations
|
||||
-ifeq ($(USE_LTO),yes)
|
||||
- OPT += -flto
|
||||
-endif
|
||||
-
|
||||
-# FPU-related options
|
||||
-ifeq ($(USE_FPU),)
|
||||
- USE_FPU = no
|
||||
-endif
|
||||
-ifneq ($(USE_FPU),no)
|
||||
- OPT += -mfloat-abi=$(USE_FPU) -mfpu=fpv4-sp-d16 -fsingle-precision-constant
|
||||
- DDEFS += -DCORTEX_USE_FPU=TRUE
|
||||
- DADEFS += -DCORTEX_USE_FPU=TRUE
|
||||
-else
|
||||
- DDEFS += -DCORTEX_USE_FPU=FALSE
|
||||
- DADEFS += -DCORTEX_USE_FPU=FALSE
|
||||
-endif
|
||||
-
|
||||
# Output directory and files
|
||||
ifeq ($(BUILDDIR),)
|
||||
BUILDDIR = build
|
||||
@@ -50,6 +10,14 @@
|
||||
OUTFILES = $(BUILDDIR)/$(PROJECT).elf $(BUILDDIR)/$(PROJECT).hex \
|
||||
$(BUILDDIR)/$(PROJECT).bin $(BUILDDIR)/$(PROJECT).dmp
|
||||
|
||||
+# Automatic compiler options
|
||||
+OPT = $(USE_OPT)
|
||||
+COPT = $(USE_COPT)
|
||||
+CPPOPT = $(USE_CPPOPT)
|
||||
+ifeq ($(USE_LINK_GC),yes)
|
||||
+ OPT += -ffunction-sections -fdata-sections -fno-common
|
||||
+endif
|
||||
+
|
||||
# Source files groups and paths
|
||||
ifeq ($(USE_THUMB),yes)
|
||||
TCSRC += $(CSRC)
|
||||
@@ -92,8 +60,12 @@
|
||||
--- os/ports/GCC/ARMCMx/rules.mk (revision 2723)
|
||||
+++ os/ports/GCC/ARMCMx/rules.mk (working copy)
|
||||
@@ -60,7 +60,7 @@
|
||||
ASFLAGS = $(MCFLAGS) -Wa,-amhls=$(LSTDIR)/$(notdir $(<:.s=.lst)) $(ADEFS)
|
||||
ASXFLAGS = $(MCFLAGS) -Wa,-amhls=$(LSTDIR)/$(notdir $(<:.S=.lst)) $(ADEFS)
|
||||
CFLAGS = $(MCFLAGS) $(OPT) $(COPT) $(CWARN) -Wa,-alms=$(LSTDIR)/$(notdir $(<:.c=.lst)) $(DEFS)
|
||||
-CPPFLAGS = $(MCFLAGS) $(OPT) $(CPPOPT) $(CPPWARN) -Wa,-alms=$(LSTDIR)/$(notdir $(<:.cpp=.lst)) $(DEFS)
|
||||
-LDFLAGS = $(MCFLAGS) $(OPT) -nostartfiles $(LLIBDIR) -Wl,-Map=$(BUILDDIR)/$(PROJECT).map,--cref,--no-warn-mismatch,--library-path=$(RULESPATH),--script=$(LDSCRIPT)$(LDOPT)
|
||||
+CPPFLAGS = $(MCFLAGS) $(CPPOPT) $(CPPWARN) -Wa,-alms=$(LSTDIR)/$(notdir $(<:.cpp=.lst)) $(DEFS)
|
||||
+ifeq ($(USE_LINK_GC),yes)
|
||||
+ LDFLAGS = $(MCFLAGS) -nostartfiles -T$(LDSCRIPT) -Wl,-Map=$(BUILDDIR)/$(PROJECT).map,--cref,--no-warn-mismatch,--gc-sections $(LLIBDIR)
|
||||
+else
|
||||
+ LDFLAGS = $(MCFLAGS) -nostartfiles -T$(LDSCRIPT) -Wl,-Map=$(BUILDDIR)/$(PROJECT).map,--cref,--no-warn-mismatch $(LLIBDIR)
|
||||
+endif
|
||||
|
||||
# Thumb interwork enabled only if needed because it kills performance.
|
||||
ifneq ($(TSRC),)
|
||||
@@ -122,7 +94,6 @@
|
||||
endif
|
||||
|
||||
# Generate dependency information
|
||||
-ASFLAGS += -MD -MP -MF .dep/$(@F).d
|
||||
CFLAGS += -MD -MP -MF .dep/$(@F).d
|
||||
CPPFLAGS += -MD -MP -MF .dep/$(@F).d
|
||||
|
||||
@@ -142,7 +113,7 @@
|
||||
ifeq ($(USE_LINK_GC),yes)
|
||||
LDFLAGS = $(MCFLAGS) -nostartfiles -T$(LDSCRIPT) -Wl,-Map=$(BUILDDIR)/$(PROJECT).map,--cref,--no-warn-mismatch,--gc-sections $(LLIBDIR)
|
||||
else
|
||||
@@ -113,7 +113,7 @@
|
||||
$(BUILDDIR) $(OBJDIR) $(LSTDIR):
|
||||
ifneq ($(USE_VERBOSE_COMPILE),yes)
|
||||
@echo Compiler Options
|
||||
|
@ -287,289 +109,3 @@ Index: chibios/os/ports/GCC/ARMCMx/rules.mk
|
|||
@echo
|
||||
endif
|
||||
mkdir -p $(OBJDIR)
|
||||
@@ -195,7 +166,7 @@
|
||||
|
||||
$(ASMXOBJS) : $(OBJDIR)/%.o : %.S Makefile
|
||||
ifeq ($(USE_VERBOSE_COMPILE),yes)
|
||||
- @echo
|
||||
+ @echo
|
||||
$(CC) -c $(ASXFLAGS) $(TOPT) -I. $(IINCDIR) $< -o $@
|
||||
else
|
||||
@echo Compiling $(<F)
|
||||
@@ -233,9 +204,6 @@
|
||||
else
|
||||
@echo Creating $@
|
||||
@$(OD) $(ODFLAGS) $< > $@
|
||||
- @echo
|
||||
- @$(SZ) $<
|
||||
- @echo
|
||||
@echo Done
|
||||
endif
|
||||
|
||||
@@ -242,7 +210,6 @@
|
||||
clean:
|
||||
@echo Cleaning
|
||||
-rm -fR .dep $(BUILDDIR)
|
||||
- @echo
|
||||
@echo Done
|
||||
|
||||
#
|
||||
Index: chibios/os/ports/IAR/ARMCMx/chcore_v7m.h
|
||||
===================================================================
|
||||
--- chibios/os/ports/IAR/ARMCMx/chcore_v7m.h (revision 6923)
|
||||
+++ chibios/os/ports/IAR/ARMCMx/chcore_v7m.h (working copy)
|
||||
@@ -470,6 +470,8 @@
|
||||
#define port_wait_for_interrupt()
|
||||
#endif
|
||||
|
||||
+int getRemainingStack(Thread *otp);
|
||||
+
|
||||
/**
|
||||
* @brief Performs a context switch between two threads.
|
||||
* @details This is the most critical code in any port, this function
|
||||
@@ -484,7 +486,7 @@
|
||||
#define port_switch(ntp, otp) _port_switch(ntp, otp)
|
||||
#else
|
||||
#define port_switch(ntp, otp) { \
|
||||
- if ((stkalign_t *)(__get_SP() - sizeof(struct intctx)) < otp->p_stklimit) \
|
||||
+ if (getRemainingStack(otp) < 0) \
|
||||
chDbgPanic("stack overflow"); \
|
||||
_port_switch(ntp, otp); \
|
||||
}
|
||||
Index: chibios/os/ports/IAR/ARMCMx/chcoreasm_v7m.s
|
||||
===================================================================
|
||||
--- chibios/os/ports/IAR/ARMCMx/chcoreasm_v7m.s (revision 6923)
|
||||
+++ chibios/os/ports/IAR/ARMCMx/chcoreasm_v7m.s (working copy)
|
||||
@@ -34,7 +34,7 @@
|
||||
* Imports the Cortex-Mx configuration headers.
|
||||
*/
|
||||
#define _FROM_ASM_
|
||||
-#include "chconf.h"
|
||||
+#include "config\stm32f4ems\chconf.h"
|
||||
#include "chcore.h"
|
||||
|
||||
CONTEXT_OFFSET SET 12
|
||||
Index: chibios/os/ports/IAR/ARMCMx/cstartup.s
|
||||
===================================================================
|
||||
--- chibios/os/ports/IAR/ARMCMx/cstartup.s (revision 6923)
|
||||
+++ chibios/os/ports/IAR/ARMCMx/cstartup.s (working copy)
|
||||
@@ -37,6 +37,8 @@
|
||||
|
||||
SECTION .intvec:CODE:NOROOT(3)
|
||||
|
||||
+ SECTION .ccm:CODE:NOROOT(2)
|
||||
+
|
||||
SECTION CSTACK:DATA:NOROOT(3)
|
||||
PUBLIC __main_thread_stack_base__
|
||||
__main_thread_stack_base__:
|
||||
Index: chibios/os/various/chprintf.c
|
||||
===================================================================
|
||||
--- chibios/os/various/chprintf.c (revision 6923)
|
||||
+++ chibios/os/various/chprintf.c (working copy)
|
||||
@@ -29,11 +29,13 @@
|
||||
|
||||
#include "ch.h"
|
||||
#include "chprintf.h"
|
||||
-#include "memstreams.h"
|
||||
|
||||
#define MAX_FILLER 11
|
||||
-#define FLOAT_PRECISION 100000
|
||||
-
|
||||
+/**
|
||||
+ * That's out default %f precision here. Two digits should be fine?
|
||||
+ * That's important on the lcd screen
|
||||
+ */
|
||||
+#define FLOAT_PRECISION 100
|
||||
static char *long_to_string_with_divisor(char *p,
|
||||
long num,
|
||||
unsigned radix,
|
||||
@@ -73,10 +75,22 @@
|
||||
}
|
||||
|
||||
#if CHPRINTF_USE_FLOAT
|
||||
-static char *ftoa(char *p, double num) {
|
||||
+char *ftoa(char *p, double num, unsigned long precision) {
|
||||
+ if (num < 0) {
|
||||
+ *p++ = '-';
|
||||
+ return ftoa(p, -num, precision);
|
||||
+ }
|
||||
long l;
|
||||
- unsigned long precision = FLOAT_PRECISION;
|
||||
+ if (isnan(num)) {
|
||||
+ *p++ = 'N';
|
||||
+ *p++ = 'a';
|
||||
+ *p++ = 'N';
|
||||
+ return p;
|
||||
+ }
|
||||
|
||||
+ if (precision == 0)
|
||||
+ precision = FLOAT_PRECISION;
|
||||
+
|
||||
l = (long)num;
|
||||
p = long_to_string_with_divisor(p, l, 10, 0);
|
||||
*p++ = '.';
|
||||
@@ -85,6 +99,9 @@
|
||||
}
|
||||
#endif
|
||||
|
||||
+#include "error_handling.h"
|
||||
+int getRemainingStack(Thread *otp);
|
||||
+
|
||||
/**
|
||||
* @brief System formatted output function.
|
||||
* @details This function implements a minimal @p vprintf()-like functionality
|
||||
@@ -121,6 +138,9 @@
|
||||
char tmpbuf[MAX_FILLER + 1];
|
||||
#endif
|
||||
|
||||
+ efiAssertVoid(getRemainingStack(chThdSelf()) > 64, "lowstck#1c");
|
||||
+
|
||||
+
|
||||
while (TRUE) {
|
||||
c = *fmt++;
|
||||
if (c == 0)
|
||||
@@ -129,6 +149,7 @@
|
||||
chSequentialStreamPut(chp, (uint8_t)c);
|
||||
continue;
|
||||
}
|
||||
+ // we are here if c == '%' meaning we have a control sequence
|
||||
p = tmpbuf;
|
||||
s = tmpbuf;
|
||||
left_align = FALSE;
|
||||
@@ -211,7 +232,7 @@
|
||||
*p++ = '-';
|
||||
f = -f;
|
||||
}
|
||||
- p = ftoa(p, f);
|
||||
+ p = ftoa(p, f, precision);
|
||||
break;
|
||||
#endif
|
||||
case 'X':
|
||||
@@ -250,8 +271,8 @@
|
||||
chSequentialStreamPut(chp, (uint8_t)filler);
|
||||
} while (++width != 0);
|
||||
}
|
||||
- while (--i >= 0)
|
||||
- chSequentialStreamPut(chp, (uint8_t)*s++);
|
||||
+ chSequentialStreamWrite(chp, (uint8_t*)s, i);
|
||||
+ s += i;
|
||||
|
||||
while (width) {
|
||||
chSequentialStreamPut(chp, (uint8_t)filler);
|
||||
@@ -260,48 +281,4 @@
|
||||
}
|
||||
}
|
||||
|
||||
-/**
|
||||
- * @brief System formatted output function.
|
||||
- * @details This function implements a minimal @p vprintf()-like functionality
|
||||
- * with output on a @p BaseSequentialStream.
|
||||
- * The general parameters format is: %[-][width|*][.precision|*][l|L]p.
|
||||
- * The following parameter types (p) are supported:
|
||||
- * - <b>x</b> hexadecimal integer.
|
||||
- * - <b>X</b> hexadecimal long.
|
||||
- * - <b>o</b> octal integer.
|
||||
- * - <b>O</b> octal long.
|
||||
- * - <b>d</b> decimal signed integer.
|
||||
- * - <b>D</b> decimal signed long.
|
||||
- * - <b>u</b> decimal unsigned integer.
|
||||
- * - <b>U</b> decimal unsigned long.
|
||||
- * - <b>c</b> character.
|
||||
- * - <b>s</b> string.
|
||||
- * .
|
||||
- *
|
||||
- * @param[in] str pointer to a buffer
|
||||
- * @param[in] size maximum size of the buffer
|
||||
- * @param[in] fmt formatting string
|
||||
- * @return The size of the generated string.
|
||||
- *
|
||||
- * @api
|
||||
- */
|
||||
-int chsnprintf(char *str, size_t size, const char *fmt, ...) {
|
||||
- va_list ap;
|
||||
- MemoryStream ms;
|
||||
- BaseSequentialStream *chp;
|
||||
-
|
||||
- /* Memory stream object to be used as a string writer.*/
|
||||
- msObjectInit(&ms, (uint8_t *)str, size, 0);
|
||||
-
|
||||
- /* Performing the print operation using the common code.*/
|
||||
- chp = (BaseSequentialStream *)&ms;
|
||||
- va_start(ap, fmt);
|
||||
- chvprintf(chp, fmt, ap);
|
||||
- va_end(ap);
|
||||
-
|
||||
- /* Final zero and size return.*/
|
||||
- chSequentialStreamPut(chp, 0);
|
||||
- return ms.eos - 1;
|
||||
-}
|
||||
-
|
||||
/** @} */
|
||||
Index: chibios/os/various/chprintf.h
|
||||
===================================================================
|
||||
--- chibios/os/various/chprintf.h (revision 6923)
|
||||
+++ chibios/os/various/chprintf.h (working copy)
|
||||
@@ -26,6 +26,7 @@
|
||||
#define _CHPRINTF_H_
|
||||
|
||||
#include <stdarg.h>
|
||||
+#include <math.h>
|
||||
|
||||
/**
|
||||
* @brief Float type support.
|
||||
@@ -38,7 +39,7 @@
|
||||
extern "C" {
|
||||
#endif
|
||||
void chvprintf(BaseSequentialStream *chp, const char *fmt, va_list ap);
|
||||
- int chsnprintf(char *str, size_t size, const char *fmt, ...);
|
||||
+ char *ftoa(char *p, double num, unsigned long precision);
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
@@ -66,7 +67,7 @@
|
||||
*
|
||||
* @api
|
||||
*/
|
||||
-static INLINE void chprintf(BaseSequentialStream *chp, const char *fmt, ...) {
|
||||
+static inline void chprintf(BaseSequentialStream *chp, const char *fmt, ...) {
|
||||
va_list ap;
|
||||
|
||||
va_start(ap, fmt);
|
||||
Index: chibios/os/various/fatfs_bindings/fatfs_diskio.c
|
||||
===================================================================
|
||||
--- chibios/os/various/fatfs_bindings/fatfs_diskio.c (revision 6923)
|
||||
+++ chibios/os/various/fatfs_bindings/fatfs_diskio.c (working copy)
|
||||
@@ -5,11 +5,12 @@
|
||||
/* disk I/O modules and attach it to FatFs module with common interface. */
|
||||
/*-----------------------------------------------------------------------*/
|
||||
|
||||
-#include "ch.h"
|
||||
-#include "hal.h"
|
||||
+#include "main.h"
|
||||
#include "ffconf.h"
|
||||
#include "diskio.h"
|
||||
|
||||
+#if EFI_FILE_LOGGING || defined(__DOXYGEN__)
|
||||
+
|
||||
#if HAL_USE_MMC_SPI && HAL_USE_SDC
|
||||
#error "cannot specify both MMC_SPI and SDC drivers"
|
||||
#endif
|
||||
@@ -250,5 +251,5 @@
|
||||
#endif
|
||||
}
|
||||
|
||||
+#endif
|
||||
|
||||
-
|
||||
Index: chibios/readme.txt
|
||||
===================================================================
|
||||
--- chibios/readme.txt (revision 6921)
|
||||
+++ chibios/readme.txt (working copy)
|
||||
@@ -1,4 +1,5 @@
|
||||
|
||||
-In this folder we have ChibiOS 2.6.1 with rusefi_chibios.patch applied
|
||||
+In this folder we have ChibiOS 2.6.6 with rusefi_chibios.patch applied.
|
||||
+http://chibios.org/
|
||||
|
||||
rusefi_chibios.patch is only about minor improvements to fatal error message - like __FILE__ info and maybe better messages.
|
||||
\ No newline at end of file
|
||||
|
|
|
@ -0,0 +1,29 @@
|
|||
package com.rusefi;
|
||||
|
||||
import static com.rusefi.AutoTest.setEngineType;
|
||||
import static com.rusefi.RealHwTest.startRealHardwareTest;
|
||||
|
||||
public class EnduranceTest {
|
||||
public static void main(String[] args) {
|
||||
|
||||
try {
|
||||
String port = startRealHardwareTest(args);
|
||||
|
||||
if (port == null)
|
||||
return;
|
||||
|
||||
IoUtil.realHardwareConnect(port);
|
||||
for (int i = 0; i < 1000; i++) {
|
||||
setEngineType(3);
|
||||
IoUtil.changeRpm(1200);
|
||||
setEngineType(28);
|
||||
IoUtil.changeRpm(2400);
|
||||
FileLog.MAIN.logLine("++++++++++++++++++++++++++++++++++++ " + i + " +++++++++++++++");
|
||||
}
|
||||
|
||||
} catch (Throwable e) {
|
||||
e.printStackTrace();
|
||||
System.exit(-1);
|
||||
}
|
||||
}
|
||||
}
|
|
@ -10,24 +10,10 @@ import static com.rusefi.AutoTest.*;
|
|||
public class RealHwTest {
|
||||
public static void main(String[] args) {
|
||||
long start = System.currentTimeMillis();
|
||||
/**
|
||||
* with real hardware we have noise on all analog inputs which gives us random sensor data, we cannot really
|
||||
* test exact numbers yet
|
||||
*/
|
||||
TestingUtils.isRealHardware = true;
|
||||
FileLog.MAIN.start();
|
||||
String port;
|
||||
if (args.length == 1) {
|
||||
port = args[0];
|
||||
} else if (args.length == 0) {
|
||||
port = IoUtil.getDefaultPort();
|
||||
if (port == null)
|
||||
return;
|
||||
String port = startRealHardwareTest(args);
|
||||
|
||||
} else {
|
||||
System.out.println("Only one optional argument expected: port number");
|
||||
if (port == null)
|
||||
return;
|
||||
}
|
||||
boolean failed = false;
|
||||
try {
|
||||
runRealHardwareTest(port);
|
||||
|
@ -45,6 +31,25 @@ public class RealHwTest {
|
|||
System.exit(0); // this is a safer method eliminating the issue of non-daemon threads
|
||||
}
|
||||
|
||||
static String startRealHardwareTest(String[] args) {
|
||||
/**
|
||||
* with real hardware we have noise on all analog inputs which gives us random sensor data, we cannot really
|
||||
* test exact numbers yet
|
||||
*/
|
||||
TestingUtils.isRealHardware = true;
|
||||
FileLog.MAIN.start();
|
||||
String port;
|
||||
if (args.length == 1) {
|
||||
port = args[0];
|
||||
} else if (args.length == 0) {
|
||||
port = IoUtil.getDefaultPort();
|
||||
} else {
|
||||
System.out.println("Only one optional argument expected: port number");
|
||||
port = null;
|
||||
}
|
||||
return port;
|
||||
}
|
||||
|
||||
private static void runRealHardwareTest(String port) {
|
||||
IoUtil.realHardwareConnect(port);
|
||||
mainTestBody();
|
||||
|
|
Loading…
Reference in New Issue