]> git.sur5r.net Git - freertos/blobdiff - FreeRTOS/Demo/CORTEX_STM32L152_Discovery_IAR/main.c
STM32L discovery demo is now demonstrating three low power modes - still needs clean up.
[freertos] / FreeRTOS / Demo / CORTEX_STM32L152_Discovery_IAR / main.c
index 8fc39d7a1bda3e3d8ea691e52736d6a954b53e17..6193f1833e0cc66a07cb39d9efc2d8fe449479bb 100644 (file)
 #include "FreeRTOS.h"\r
 #include "task.h"\r
 #include "queue.h"\r
+#include "semphr.h"\r
 \r
 /* ST library functions. */\r
 #include "stm32l1xx.h"\r
 #include "discover_board.h"\r
 #include "discover_functions.h"\r
+#include "stm32l_discovery_lcd.h"\r
 \r
 /* Priorities at which the Rx and Tx tasks are created. */\r
 #define configQUEUE_RECEIVE_TASK_PRIORITY      ( tskIDLE_PRIORITY + 1 )\r
@@ -150,9 +152,6 @@ empty. */
 /* The LED used to indicate that a value has been received on the queue. */\r
 #define mainQUEUE_LED                                          ( 0 )\r
 \r
-/* The rate at which the Tx task sends to the queue. */\r
-#define mainTX_DELAY                                           ( 500UL / portTICK_RATE_MS )\r
-\r
 /* A block time of zero simply means "don't block". */\r
 #define mainDONT_BLOCK                                         ( 0 )\r
 \r
@@ -162,7 +161,7 @@ empty. */
 /* The length of time the LED will remain on for.  It is on just long enough\r
 to be able to see with the human eye so as not to distort the power readings too\r
 much. */\r
-#define mainLED_TOGGLE_DELAY                           ( 20 / portTICK_RATE_MS )\r
+#define mainLED_TOGGLE_DELAY                           ( 10 / portTICK_RATE_MS )\r
 \r
 /*-----------------------------------------------------------*/\r
 \r
@@ -184,10 +183,16 @@ static void prvSetupHardware( void );
 \r
 /*-----------------------------------------------------------*/\r
 \r
+static const portTickType xMaxBlockTime = ( 500L / portTICK_RATE_MS ), xMinBlockTime = ( 100L / portTICK_RATE_MS );\r
+portTickType xSendBlockTime = ( 100UL / portTICK_RATE_MS );\r
+static xSemaphoreHandle xTxSemaphore = NULL;\r
+\r
 int main( void )\r
 {\r
        prvSetupHardware();\r
 \r
+       xTxSemaphore = xSemaphoreCreateBinary();\r
+\r
        /* Create the queue. */\r
        xQueue = xQueueCreate( mainQUEUE_LENGTH, sizeof( unsigned long ) );\r
        configASSERT( xQueue );\r
@@ -216,10 +221,9 @@ const unsigned long ulValueToSend = mainQUEUED_VALUE;
 \r
        for( ;; )\r
        {\r
-               /* Place this task into the blocked state until it is time to run again.\r
-               The kernel will place the MCU into the Retention low power sleep state\r
-               when the idle task next runs. */\r
-               vTaskDelay( mainTX_DELAY );\r
+               /* Place this task into the blocked state until it is time to run\r
+               again. */\r
+               xSemaphoreTake( xTxSemaphore, xSendBlockTime );\r
 \r
                /* Send to the queue - causing the queue receive task to flash its LED.\r
                It should not be necessary to block on the queue send because the Rx\r
@@ -253,6 +257,39 @@ unsigned long ulReceivedValue;
 }\r
 /*-----------------------------------------------------------*/\r
 \r
+void EXTI0_IRQHandler(void)\r
+{\r
+static const portTickType xIncrement = 200UL / portTICK_RATE_MS;\r
+\r
+       if( xSendBlockTime == portMAX_DELAY )\r
+       {\r
+               portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;\r
+\r
+               /* Unblock the Tx task again. */\r
+               xSemaphoreGiveFromISR( xTxSemaphore, &xHigherPriorityTaskWoken );\r
+\r
+               /* Start over with the short block time that will not result in the\r
+               tick being turned off or a low power mode being entered. */\r
+               xSendBlockTime = xMinBlockTime;\r
+\r
+               portYIELD_FROM_ISR( xHigherPriorityTaskWoken );\r
+       }\r
+       else\r
+       {\r
+               xSendBlockTime += xIncrement;\r
+\r
+               if( xSendBlockTime > xMaxBlockTime )\r
+               {\r
+                       /* Set the send block time to be infinite to force entry into the STOP\r
+                       sleep mode. */\r
+                       xSendBlockTime = portMAX_DELAY;\r
+               }\r
+       }\r
+\r
+       EXTI_ClearITPendingBit( EXTI_Line0 );\r
+}\r
+/*-----------------------------------------------------------*/\r
+\r
 static void prvSetupHardware( void )\r
 {\r
 /* GPIO, EXTI and NVIC Init structure declaration */\r
@@ -266,59 +303,57 @@ void SystemCoreClockUpdate( void );
        /* Essential on STM32 Cortex-M devices. */\r
        NVIC_PriorityGroupConfig( NVIC_PriorityGroup_4 );\r
 \r
-       /* Enable HSI Clock */\r
-       RCC_HSICmd(ENABLE);\r
+       /* Systick is fed from HCLK/8. */\r
+       SysTick_CLKSourceConfig( SysTick_CLKSource_HCLK_Div8 );\r
+\r
+       /* Enable HSI Clock. */\r
+//     RCC_HSICmd( ENABLE );\r
 \r
-       /*!< Wait till HSI is ready */\r
-       while( RCC_GetFlagStatus( RCC_FLAG_HSIRDY ) == RESET );\r
+       /*!< Wait till HSI is ready. */\r
+//     while( RCC_GetFlagStatus( RCC_FLAG_HSIRDY ) == RESET );\r
 \r
        /* Set HSI as sys clock*/\r
-       RCC_SYSCLKConfig( RCC_SYSCLKSource_HSI );\r
+//     RCC_SYSCLKConfig( RCC_SYSCLKSource_HSI );\r
 \r
-       /* Set MSI clock range to ~4.194MHz*/\r
+       /* Set MSI clock range to ~4.194MHz*/\r
        RCC_MSIRangeConfig( RCC_MSIRange_6 );\r
 \r
-       /* Enable the GPIOs clocks */\r
+       /* Enable the GPIOs clocks. */\r
        RCC_AHBPeriphClockCmd( RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB | RCC_AHBPeriph_GPIOC| RCC_AHBPeriph_GPIOD| RCC_AHBPeriph_GPIOE| RCC_AHBPeriph_GPIOH, ENABLE );\r
 \r
-       /* Enable comparator, PWR mngt clocks */\r
-       RCC_APB1PeriphClockCmd( RCC_APB1Periph_COMP | RCC_APB1Periph_PWR,ENABLE );\r
+       /* Enable comparator clocks. */\r
+       RCC_APB1PeriphClockCmd( RCC_APB1Periph_COMPENABLE );\r
 \r
-       /* Enable ADC & SYSCFG clocks */\r
+       /* Enable SYSCFG clocks. */\r
        RCC_APB2PeriphClockCmd( RCC_APB2Periph_SYSCFG , ENABLE );\r
 \r
        /* Allow access to the RTC */\r
-       PWR_RTCAccessCmd( ENABLE );\r
+//     PWR_RTCAccessCmd( ENABLE );\r
 \r
        /* Reset RTC Backup Domain */\r
-       RCC_RTCResetCmd( ENABLE );\r
-       RCC_RTCResetCmd( DISABLE );\r
+//     RCC_RTCResetCmd( ENABLE );\r
+//     RCC_RTCResetCmd( DISABLE );\r
 \r
        /* LSE Enable */\r
-       RCC_LSEConfig( RCC_LSE_ON );\r
+//     RCC_LSEConfig( RCC_LSE_ON );\r
+       //RCC_LSICmd( ENABLE ); //_RB_\r
 \r
        /* Wait until LSE is ready */\r
-       while( RCC_GetFlagStatus( RCC_FLAG_LSERDY ) == RESET );\r
-\r
-       /* RTC Clock Source Selection */\r
-       RCC_RTCCLKConfig( RCC_RTCCLKSource_LSE );\r
-\r
-       /* Enable the RTC */\r
-       RCC_RTCCLKCmd( ENABLE );\r
+//     while( RCC_GetFlagStatus( RCC_FLAG_LSERDY ) == RESET );\r
 \r
        /* Disable HSE */\r
-       RCC_HSEConfig( RCC_HSE_OFF );\r
+//     RCC_HSEConfig( RCC_HSE_OFF );\r
 \r
-       if( RCC_GetFlagStatus( RCC_FLAG_HSERDY ) != RESET )\r
-       {\r
-               /* Stay in infinite loop if HSE is not disabled*/\r
-               while( 1 );\r
-       }\r
+//     if( RCC_GetFlagStatus( RCC_FLAG_HSERDY ) != RESET )\r
+//     {\r
+               /* Stay in infinite loop if HSE is not disabled*/\r
+//             while( 1 );\r
+//     }\r
 \r
-       /* Set internal voltage regulator to 1.8V */\r
-       PWR_VoltageScalingConfig( PWR_VoltageScaling_Range1 );\r
+       /* Set internal voltage regulator to 1.5V. */\r
+       PWR_VoltageScalingConfig( PWR_VoltageScaling_Range2 );\r
 \r
-       /* Wait Until the Voltage Regulator is ready */\r
+       /* Wait Until the Voltage Regulator is ready. */\r
        while( PWR_GetFlagStatus( PWR_FLAG_VOS ) != RESET );\r
 \r
        /* Configure User Button pin as input */\r
@@ -329,7 +364,7 @@ void SystemCoreClockUpdate( void );
        GPIO_Init( USERBUTTON_GPIO_PORT, &GPIO_InitStructure );\r
 \r
        /* Select User Button pin as input source for EXTI Line */\r
-       SYSCFG_EXTILineConfig( EXTI_PortSourceGPIOA,EXTI_PinSource0 );\r
+       SYSCFG_EXTILineConfig( EXTI_PortSourceGPIOA, EXTI_PinSource0 );\r
 \r
        /* Configure EXT1 Line 0 in interrupt mode trigged on Rising edge */\r
        EXTI_InitStructure.EXTI_Line = EXTI_Line0 ;  /* PA0 for User button AND IDD_WakeUP */\r
@@ -413,16 +448,36 @@ void vApplicationTickHook( void )
 }\r
 /*-----------------------------------------------------------*/\r
 \r
-void vAssertCalled( void )\r
+void vMainPostStopProcessing( void )\r
 {\r
-volatile unsigned long ul = 0;\r
+extern void SetSysClock( void );\r
+\r
+       SetSysClock();\r
+       /* Unblock the Tx task again. */\r
+//     xSemaphoreGiveFromISR( xTxSemaphore, NULL );\r
+\r
+       /* Start over with the short block time that will not result in the\r
+       tick being turned off or a low power mode being entered. */\r
+//     xSendBlockTime = xMinBlockTime;\r
+}\r
+/*-----------------------------------------------------------*/\r
+\r
+void vAssertCalled( unsigned long ulLine, const char * const pcFileName )\r
+{\r
+volatile unsigned long ulSetToNonZeroInDebuggerToContinue = 0;\r
+\r
+       /* Parameters are not used. */\r
+       ( void ) ulLine;\r
+       ( void ) pcFileName;\r
 \r
        taskENTER_CRITICAL();\r
        {\r
-               /* Set ul to a non-zero value using the debugger to step out of this\r
-               function. */\r
-               while( ul == 0 )\r
+               while( ulSetToNonZeroInDebuggerToContinue == 0 )\r
                {\r
+                       /* Use the debugger to set ulSetToNonZeroInDebuggerToContinue to a\r
+                       non zero value to step out of this function to the point that raised\r
+                       this assert(). */\r
+                       __asm volatile( "NOP" );\r
                        __asm volatile( "NOP" );\r
                }\r
        }\r
@@ -430,6 +485,35 @@ volatile unsigned long ul = 0;
 }\r
 \r
 \r
+\r
+\r
+#ifdef  USE_FULL_ASSERT\r
+\r
+/**\r
+  * @brief  Reports the name of the source file and the source line number\r
+  *         where the assert_param error has occurred.\r
+  * @param  file: pointer to the source file name\r
+  * @param  line: assert_param error line source number\r
+  * @retval None\r
+  */\r
+void assert_failed(uint8_t* file, uint32_t line)\r
+{\r
+  /* User can add his own implementation to report the file name and line number,\r
+     ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */\r
+  /* Infinite loop */\r
+  while (1);\r
+}\r
+\r
+#endif\r
+\r
+\r
+\r
+\r
+\r
+\r
+\r
+\r
+\r
 #if 0\r
 /**\r
   ******************************************************************************\r
@@ -962,6 +1046,273 @@ void vApplicationStackOverflowHook( void )
 }\r
 \r
 /******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/\r
+       /* Ensure the interrupt is clear before exiting.  The RTC uses EXTI line 20\r
+       to bring the CPU out of sleep. */\r
+\r
+\r
+\r
+\r
+\r
+\r
+\r
+\r
+\r
+void _vPortSuppressTicksAndSleep( portTickType xExpectedIdleTime )\r
+{\r
+uint32_t ulWakeupValue, ulCompleteTickPeriods;\r
+eSleepModeStatus eSleepAction;\r
+portTickType xModifiableIdleTime;\r
+\r
+       /* THIS FUNCTION IS CALLED WITH THE SCHEDULER SUSPENDED. */\r
+\r
+       /* Make sure the wakeup timer reload value does not overflow the counter. */\r
+       if( xExpectedIdleTime > xMaximumPossibleSuppressedTicks )\r
+       {\r
+               xExpectedIdleTime = xMaximumPossibleSuppressedTicks;\r
+       }\r
+\r
+       /* Calculate the reload value required to wait xExpectedIdleTime tick\r
+       periods. */\r
+       ulWakeupValue = ( ( ulWakeupValueForOneTick + 1UL ) * xExpectedIdleTime ) - 1UL;\r
+       if( ulWakeupValue > ulStoppedTimerCompensation )\r
+       {\r
+               /* Compensate for the fact that the RTC is going to be stopped\r
+               momentarily. */\r
+               ulWakeupValue -= ulStoppedTimerCompensation;\r
+       }\r
+\r
+       /* Stop the RTC momentarily.  The time the RTC is stopped for is accounted\r
+       for as best it can be, but using the tickless mode will inevitably result in\r
+       some tiny drift of the time maintained by the kernel with respect to\r
+       calendar time. */\r
+       prvDisableWakeupTimer();\r
+\r
+       /* Enter a critical section but don't use the taskENTER_CRITICAL() method as\r
+       that will mask interrupts that should exit sleep mode. */\r
+       __asm volatile ( "cpsid i" );\r
+\r
+       /* The tick flag is set to false before sleeping.  If it is true when sleep\r
+       mode is exited then sleep mode was probably exited because the tick was\r
+       suppressed for the entire xExpectedIdleTime period. */\r
+       ulTickFlag = pdFALSE;\r
+\r
+       /* If a context switch is pending then abandon the low power entry as\r
+       the context switch might have been pended by an external interrupt that\r
+       requires processing. */\r
+       eSleepAction = eTaskConfirmSleepModeStatus();\r
+       if( eSleepAction == eAbortSleep )\r
+       {\r
+               /* Restart tick. */\r
+               prvEnableWakeupTimer();\r
+\r
+               /* Re-enable interrupts - see comments above the cpsid instruction()\r
+               above. */\r
+               __asm volatile ( "cpsie i" );\r
+       }\r
+       else\r
+       {\r
+               /* Adjust the alarm value to take into account that the current time\r
+               slice is already partially complete. */\r
+//             ulWakeupValue -= ( RTC->WUTR & RTC_WUTR_WUT ); /* Current value. */\r
+\r
+               /* Disable the write protection for RTC registers */\r
+               RTC->WPR = 0xCA;\r
+               RTC->WPR = 0x53;\r
+\r
+               /* Set the Wakeup Timer value */\r
+               RTC->WUTR = ulWakeupValue;\r
+\r
+               /* Enable the Wakeup Timer */\r
+               RTC->CR |= (uint32_t)RTC_CR_WUTE;\r
+\r
+               /* Enable the write protection for RTC registers. */\r
+               RTC->WPR = 0xFF;\r
+\r
+               /* Allow the application to define some pre-sleep processing. */\r
+               xModifiableIdleTime = xExpectedIdleTime;\r
+               configPRE_SLEEP_PROCESSING( xModifiableIdleTime );\r
+\r
+               /* xExpectedIdleTime being set to 0 by configPRE_SLEEP_PROCESSING()\r
+               means the application defined code has already executed the WAIT\r
+               instruction. */\r
+               if( xModifiableIdleTime > 0 )\r
+               {\r
+                       /* Sleep until something happens. */\r
+                       __asm volatile ( "wfi" );\r
+                       __asm volatile ( "dsb" );\r
+               }\r
+\r
+               /* Allow the application to define some post sleep processing. */\r
+               configPOST_SLEEP_PROCESSING( xModifiableIdleTime );\r
+\r
+               /* Stop RTC.  Again, the time the clock is stopped for is accounted\r
+               for as best it can be, but using the tickless mode will inevitably\r
+               result in some tiny drift of the time maintained by the kernel with\r
+               respect to calendar time. */\r
+               prvDisableWakeupTimer();\r
+\r
+               /* Re-enable interrupts - see comments above the cpsid instruction()\r
+               above. */\r
+               __asm volatile ( "cpsie i" );\r
+\r
+               if( ulTickFlag != pdFALSE )\r
+               {\r
+                       /* The tick interrupt has already executed, although because this\r
+                       function is called with the scheduler suspended the actual tick\r
+                       processing will not occur until after this function has exited.\r
+                       Reset the alarm value with whatever remains of this tick period. */\r
+                       ulWakeupValue = ulWakeupValueForOneTick;//_RB_ - ( RTC->WUTR & RTC_WUTR_WUT ); /* Current value. */\r
+\r
+                       /* Disable the write protection for RTC registers */\r
+                       RTC->WPR = 0xCA;\r
+                       RTC->WPR = 0x53;\r
+\r
+                       /* Set the Wakeup Timer value */\r
+                       RTC->WUTR = ulWakeupValue;\r
+\r
+                       /* Enable the write protection for RTC registers. */\r
+                       RTC->WPR = 0xFF;\r
+\r
+                       /* The tick interrupt handler will already have pended the tick\r
+                       processing in the kernel.  As the pending tick will be processed as\r
+                       soon as this function exits, the tick value     maintained by the tick\r
+                       is stepped forward by one less than the time spent sleeping.  The\r
+                       actual stepping of the tick appears later in this function. */\r
+                       ulCompleteTickPeriods = xExpectedIdleTime - 1UL;\r
+               }\r
+               else\r
+               {\r
+                       /* Something other than the tick interrupt ended the sleep.  How\r
+                       many complete tick periods passed while the processor was\r
+                       sleeping? */\r
+                       ulCompleteTickPeriods = ( RTC->WUTR & RTC_WUTR_WUT ) / ulWakeupValueForOneTick;\r
+\r
+                       /* The alarm value is set to whatever fraction of a single tick\r
+                       period remains. */\r
+                       ulWakeupValue = ( RTC->WUTR & RTC_WUTR_WUT ) - ( ulCompleteTickPeriods * ulWakeupValueForOneTick );\r
+\r
+                       /* Disable the write protection for RTC registers */\r
+                       RTC->WPR = 0xCA;\r
+                       RTC->WPR = 0x53;\r
+\r
+                       /* Set the Wakeup Timer value */\r
+                       RTC->WUTR = ulWakeupValue;\r
+\r
+                       /* Enable the write protection for RTC registers. */\r
+                       RTC->WPR = 0xFF;\r
+               }\r
+\r
+               /* Restart the RTC so it runs down from the wakeup value.  The wakeup\r
+               value will get set to the value required to generate exactly one tick\r
+               period the next time the wakeup interrupt executes. */\r
+               prvEnableWakeupTimer();\r
+\r
+               /* Wind the tick forward by the number of tick periods that the CPU\r
+               remained in a low power state. */\r
+               vTaskStepTick( ulCompleteTickPeriods );\r
+       }\r
+}\r
+\r
+\r
+\r
+\r
+\r
+\r
+\r
+\r
+\r
+\r
+//     RTC_ClearITPendingBit( RTC_IT_WUT );\r
+//     EXTI_ClearITPendingBit( EXTI_Line20 );\r
+\r
+\r
+\r
+#ifdef USE_RTC\r
+NVIC_InitTypeDef NVIC_InitStructure;\r
+EXTI_InitTypeDef EXTI_InitStructure;\r
+\r
+       /* Enable access to the RTC registers. */\r
+       PWR_RTCAccessCmd( ENABLE );\r
+       RCC_RTCResetCmd( ENABLE );\r
+       RCC_RTCResetCmd( DISABLE );\r
+\r
+       /* LSE Enable */\r
+       RCC_LSEConfig( RCC_LSE_ON );\r
+\r
+       /* Wait until LSE is ready. */\r
+       while( RCC_GetFlagStatus( RCC_FLAG_LSERDY ) == RESET );\r
+\r
+       /* Enable the PWR clock. */\r
+       RCC_APB1PeriphClockCmd( RCC_APB1Periph_PWR, ENABLE );\r
+\r
+       /* LSE used as RTC clock source. */\r
+       RCC_RTCCLKConfig( RCC_RTCCLKSource_LSE ); /* 32.768KHz external */\r
+\r
+       /* Enable the RTC clock and wait for sync. */\r
+       RCC_RTCCLKCmd( ENABLE );\r
+       RTC_WaitForSynchro();\r
+\r
+       /* Watchdog timer user EXTI line 20 to wake from sleep. */\r
+       EXTI_ClearITPendingBit( EXTI_Line20 );\r
+       EXTI_InitStructure.EXTI_Line = EXTI_Line20;\r
+       EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;\r
+       EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising;\r
+       EXTI_InitStructure.EXTI_LineCmd = ENABLE;\r
+       EXTI_Init( &EXTI_InitStructure );\r
+\r
+       /* Enable the RTC Wakeup Interrupt. */\r
+       NVIC_InitStructure.NVIC_IRQChannel = RTC_WKUP_IRQn;\r
+       NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = configLIBRARY_LOWEST_INTERRUPT_PRIORITY;\r
+       NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;\r
+       NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;\r
+       NVIC_Init( &NVIC_InitStructure );\r
+\r
+       /* Drive the wakeup clock from LSE/2 (32768/2) */\r
+       RTC_WakeUpClockConfig( RTC_WakeUpClock_RTCCLK_Div2 );\r
+\r
+       /* Set count and reload values. */\r
+       RTC_SetWakeUpCounter( ulReloadValueForOneTick );\r
+\r
+       /* Enable the RTC Wakeup Interrupt. */\r
+       RTC_ITConfig( RTC_IT_WUT, ENABLE );\r
+\r
+       /* Enable Wakeup Counter. */\r
+       RTC_WakeUpCmd( ENABLE );\r
+#endif\r
+\r
+\r
+static void prvDisableWakeupTimer( void )\r
+{\r
+       RTC->WPR = 0xCA;\r
+       RTC->WPR = 0x53;\r
+\r
+       /* Disable the Wakeup Timer */\r
+       RTC->CR &= (uint32_t)~RTC_CR_WUTE;\r
+\r
+       /* Wait till RTC WUTWF flag is set. */\r
+       /* _RB_ Timeout needed. */\r
+       do\r
+       {\r
+       } while( ( RTC->ISR & RTC_ISR_WUTWF ) == 0x00 );\r
+\r
+       /* Enable the write protection for RTC registers */\r
+       RTC->WPR = 0xFF;\r
+}\r
+/*-----------------------------------------------------------*/\r
+\r
+static void prvEnableWakeupTimer( void )\r
+{\r
+       RTC->WPR = 0xCA;\r
+       RTC->WPR = 0x53;\r
+\r
+       /* Enable the Wakeup Timer */\r
+       RTC->CR |= (uint32_t)RTC_CR_WUTE;\r
+\r
+       /* Enable the write protection for RTC registers */\r
+       RTC->WPR = 0xFF;\r
+}\r
+/*-----------------------------------------------------------*/\r
+\r
 \r
 #endif\r
 \r