]> git.sur5r.net Git - freertos/blobdiff - FreeRTOS/Demo/CORTEX_STM32L152_Discovery_IAR/main.c
Update version number in preparation for maintenance release.
[freertos] / FreeRTOS / Demo / CORTEX_STM32L152_Discovery_IAR / main.c
index 8fc39d7a1bda3e3d8ea691e52736d6a954b53e17..195225cdc39d343bb90ee91081e4876bdd41fc29 100644 (file)
 /*\r
-    FreeRTOS V7.6.0 - Copyright (C) 2013 Real Time Engineers Ltd.\r
+    FreeRTOS V9.0.1 - Copyright (C) 2017 Real Time Engineers Ltd.\r
     All rights reserved\r
 \r
     VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.\r
 \r
-    ***************************************************************************\r
-     *                                                                       *\r
-     *    FreeRTOS provides completely free yet professionally developed,    *\r
-     *    robust, strictly quality controlled, supported, and cross          *\r
-     *    platform software that has become a de facto standard.             *\r
-     *                                                                       *\r
-     *    Help yourself get started quickly and support the FreeRTOS         *\r
-     *    project by purchasing a FreeRTOS tutorial book, reference          *\r
-     *    manual, or both from: http://www.FreeRTOS.org/Documentation        *\r
-     *                                                                       *\r
-     *    Thank you!                                                         *\r
-     *                                                                       *\r
-    ***************************************************************************\r
-\r
     This file is part of the FreeRTOS distribution.\r
 \r
     FreeRTOS is free software; you can redistribute it and/or modify it under\r
     the terms of the GNU General Public License (version 2) as published by the\r
-    Free Software Foundation >>!AND MODIFIED BY!<< the FreeRTOS exception.\r
+    Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception.\r
 \r
-    >>! NOTE: The modification to the GPL is included to allow you to distribute\r
-    >>! a combined work that includes FreeRTOS without being obliged to provide\r
-    >>! the source code for proprietary components outside of the FreeRTOS\r
-    >>! kernel.\r
+    ***************************************************************************\r
+    >>!   NOTE: The modification to the GPL is included to allow you to     !<<\r
+    >>!   distribute a combined work that includes FreeRTOS without being   !<<\r
+    >>!   obliged to provide the source code for proprietary components     !<<\r
+    >>!   outside of the FreeRTOS kernel.                                   !<<\r
+    ***************************************************************************\r
 \r
     FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY\r
     WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS\r
-    FOR A PARTICULAR PURPOSE.  Full license text is available from the following\r
+    FOR A PARTICULAR PURPOSE.  Full license text is available on the following\r
     link: http://www.freertos.org/a00114.html\r
 \r
-    1 tab == 4 spaces!\r
-\r
-    ***************************************************************************\r
-     *                                                                       *\r
-     *    Having a problem?  Start by reading the FAQ "My application does   *\r
-     *    not run, what could be wrong?"                                     *\r
-     *                                                                       *\r
-     *    http://www.FreeRTOS.org/FAQHelp.html                               *\r
-     *                                                                       *\r
-    ***************************************************************************\r
-\r
-    http://www.FreeRTOS.org - Documentation, books, training, latest versions,\r
-    license and Real Time Engineers Ltd. contact details.\r
-\r
-    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,\r
-    including FreeRTOS+Trace - an indispensable productivity tool, a DOS\r
-    compatible FAT file system, and our tiny thread aware UDP/IP stack.\r
-\r
-    http://www.OpenRTOS.com - Real Time Engineers ltd license FreeRTOS to High\r
-    Integrity Systems to sell under the OpenRTOS brand.  Low cost OpenRTOS\r
-    licenses offer ticketed support, indemnification and middleware.\r
-\r
-    http://www.SafeRTOS.com - High Integrity Systems also provide a safety\r
-    engineered and independently SIL3 certified version for use in safety and\r
-    mission critical applications that require provable dependability.\r
-\r
-    1 tab == 4 spaces!\r
-*/\r
-\r
-/*\r
-    FreeRTOS V7.6.0 - Copyright (C) 2013 Real Time Engineers Ltd.\r
-    All rights reserved\r
-\r
-    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.\r
-\r
     ***************************************************************************\r
      *                                                                       *\r
      *    FreeRTOS provides completely free yet professionally developed,    *\r
      *    robust, strictly quality controlled, supported, and cross          *\r
-     *    platform software that has become a de facto standard.             *\r
+     *    platform software that is more than just the market leader, it     *\r
+     *    is the industry's de facto standard.                               *\r
      *                                                                       *\r
-     *    Help yourself get started quickly and support the FreeRTOS         *\r
-     *    project by purchasing a FreeRTOS tutorial book, reference          *\r
-     *    manual, or both from: http://www.FreeRTOS.org/Documentation        *\r
-     *                                                                       *\r
-     *    Thank you!                                                         *\r
+     *    Help yourself get started quickly while simultaneously helping     *\r
+     *    to support the FreeRTOS project by purchasing a FreeRTOS           *\r
+     *    tutorial book, reference manual, or both:                          *\r
+     *    http://www.FreeRTOS.org/Documentation                              *\r
      *                                                                       *\r
     ***************************************************************************\r
 \r
-    This file is part of the FreeRTOS distribution.\r
-\r
-    FreeRTOS is free software; you can redistribute it and/or modify it under\r
-    the terms of the GNU General Public License (version 2) as published by the\r
-    Free Software Foundation >>!AND MODIFIED BY!<< the FreeRTOS exception.\r
-\r
-    >>! NOTE: The modification to the GPL is included to allow you to distribute\r
-    >>! a combined work that includes FreeRTOS without being obliged to provide\r
-    >>! the source code for proprietary components outside of the FreeRTOS\r
-    >>! kernel.\r
-\r
-    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY\r
-    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS\r
-    FOR A PARTICULAR PURPOSE.  Full license text is available from the following\r
-    link: http://www.freertos.org/a00114.html\r
-\r
-    1 tab == 4 spaces!\r
+    http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading\r
+    the FAQ page "My application does not run, what could be wrong?".  Have you\r
+    defined configASSERT()?\r
 \r
-    ***************************************************************************\r
-     *                                                                       *\r
-     *    Having a problem?  Start by reading the FAQ "My application does   *\r
-     *    not run, what could be wrong?"                                     *\r
-     *                                                                       *\r
-     *    http://www.FreeRTOS.org/FAQHelp.html                               *\r
-     *                                                                       *\r
-    ***************************************************************************\r
+    http://www.FreeRTOS.org/support - In return for receiving this top quality\r
+    embedded software for free we request you assist our global community by\r
+    participating in the support forum.\r
 \r
-    http://www.FreeRTOS.org - Documentation, books, training, latest versions,\r
-    license and Real Time Engineers Ltd. contact details.\r
+    http://www.FreeRTOS.org/training - Investing in training allows your team to\r
+    be as productive as possible as early as possible.  Now you can receive\r
+    FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers\r
+    Ltd, and the world's leading authority on the world's leading RTOS.\r
 \r
     http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,\r
     including FreeRTOS+Trace - an indispensable productivity tool, a DOS\r
     compatible FAT file system, and our tiny thread aware UDP/IP stack.\r
 \r
-    http://www.OpenRTOS.com - Real Time Engineers ltd license FreeRTOS to High\r
-    Integrity Systems to sell under the OpenRTOS brand.  Low cost OpenRTOS\r
-    licenses offer ticketed support, indemnification and middleware.\r
+    http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.\r
+    Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.\r
+\r
+    http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High\r
+    Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS\r
+    licenses offer ticketed support, indemnification and commercial middleware.\r
 \r
     http://www.SafeRTOS.com - High Integrity Systems also provide a safety\r
     engineered and independently SIL3 certified version for use in safety and\r
     1 tab == 4 spaces!\r
 */\r
 \r
+/******************************************************************************\r
+ * This project provides two demo applications.  A low power project that\r
+ * demonstrates the FreeRTOS tickless mode, and a more comprehensive test and\r
+ * demo application.  The configCREATE_LOW_POWER_DEMO setting (defined at the\r
+ * top of FreeRTOSConfig.h) is used to select between the two.  The low power\r
+ * demo is implemented and described in main_low_power.c.  The more\r
+ * comprehensive test and demo application is implemented and described in\r
+ * main_full.c.\r
+ *\r
+ * This file implements the code that is not demo specific, including the\r
+ * hardware setup and FreeRTOS hook functions.\r
+ */\r
+\r
 /* Kernel includes. */\r
 #include "FreeRTOS.h"\r
 #include "task.h"\r
-#include "queue.h"\r
 \r
 /* ST library functions. */\r
 #include "stm32l1xx.h"\r
 #include "discover_board.h"\r
-#include "discover_functions.h"\r
-\r
-/* Priorities at which the Rx and Tx tasks are created. */\r
-#define configQUEUE_RECEIVE_TASK_PRIORITY      ( tskIDLE_PRIORITY + 1 )\r
-#define        configQUEUE_SEND_TASK_PRIORITY          ( tskIDLE_PRIORITY + 2 )\r
-\r
-/* The number of items the queue can hold.  This is 1 as the Rx task will\r
-remove items as they are added so the Tx task should always find the queue\r
-empty. */\r
-#define mainQUEUE_LENGTH                                       ( 1 )\r
-\r
-/* 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
-/* The value that is sent from the Tx task to the Rx task on the queue. */\r
-#define mainQUEUED_VALUE                                       ( 100UL )\r
-\r
-/* 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
 \r
 /*-----------------------------------------------------------*/\r
 \r
 /*\r
- * The Rx and Tx tasks as described at the top of this file.\r
+ * Set up the hardware ready to run this demo.\r
  */\r
-static void prvQueueReceiveTask( void *pvParameters );\r
-static void prvQueueSendTask( void *pvParameters );\r
-\r
-/*-----------------------------------------------------------*/\r
-\r
-/* The queue to pass data from the Tx task to the Rx task. */\r
-static xQueueHandle xQueue = NULL;\r
+static void prvSetupHardware( void );\r
 \r
 /*\r
- * Set up the hardware ready to run this demo.\r
+ * main_low_power() is used when configCREATE_LOW_POWER_DEMO is set to 1.\r
+ * main_full() is used when configCREATE_LOW_POWER_DEMO is set to 0.\r
+ * configCREATE_LOW_POWER_DEMO is defined at the top of main.c.\r
  */\r
-static void prvSetupHardware( void );\r
+extern void main_low_power( void );\r
+extern void main_full( void );\r
+\r
+/* Prototypes for the standard FreeRTOS callback/hook functions implemented\r
+within this file. */\r
+void vApplicationMallocFailedHook( void );\r
+void vApplicationIdleHook( void );\r
+void vApplicationStackOverflowHook( TaskHandle_t pxTask, char *pcTaskName );\r
+void vApplicationTickHook( void );\r
 \r
 /*-----------------------------------------------------------*/\r
 \r
 int main( void )\r
 {\r
+       /* Prepare the hardware to run this demo. */\r
        prvSetupHardware();\r
 \r
-       /* Create the queue. */\r
-       xQueue = xQueueCreate( mainQUEUE_LENGTH, sizeof( unsigned long ) );\r
-       configASSERT( xQueue );\r
-\r
-       /* Start the two tasks as described at the top of this file. */\r
-       xTaskCreate( prvQueueReceiveTask, ( const signed char * const ) "Rx", configMINIMAL_STACK_SIZE, NULL, configQUEUE_RECEIVE_TASK_PRIORITY, NULL );\r
-       xTaskCreate( prvQueueSendTask, ( const signed char * const ) "TX", configMINIMAL_STACK_SIZE, NULL, configQUEUE_SEND_TASK_PRIORITY, NULL );\r
-\r
-       /* Start the scheduler running running. */\r
-       vTaskStartScheduler();\r
-\r
-       /* If all is well the next line of code will not be reached as the\r
-       scheduler will be running.  If the next line is reached then it is likely\r
-       there was insufficient FreeRTOS heap available for the idle task and/or\r
-       timer task to be created.  See http://www.freertos.org/a00111.html. */\r
-       for( ;; );\r
-}\r
-/*-----------------------------------------------------------*/\r
-\r
-static void prvQueueSendTask( void *pvParameters )\r
-{\r
-const unsigned long ulValueToSend = mainQUEUED_VALUE;\r
-\r
-       /* Remove compiler warning about unused parameter. */\r
-       ( void ) pvParameters;\r
-\r
-       for( ;; )\r
+       /* The configCREATE_LOW_POWER_DEMO setting is described at the top of\r
+       this file. */\r
+       #if configCREATE_LOW_POWER_DEMO == 1\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
-\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
-               task will already have removed the last queued item. */\r
-               xQueueSend( xQueue, &ulValueToSend, mainDONT_BLOCK );\r
+               main_low_power();\r
        }\r
-}\r
-/*-----------------------------------------------------------*/\r
-\r
-static void prvQueueReceiveTask( void *pvParameters )\r
-{\r
-unsigned long ulReceivedValue;\r
-\r
-       /* Remove compiler warning about unused parameter. */\r
-       ( void ) pvParameters;\r
-\r
-       for( ;; )\r
+       #else\r
        {\r
-               /* Wait until something arrives in the queue. */\r
-               xQueueReceive( xQueue, &ulReceivedValue, portMAX_DELAY );\r
-\r
-               /*  To get here something must have arrived, but is it the expected\r
-               value?  If it is, turn the LED on for a short while. */\r
-               if( ulReceivedValue == mainQUEUED_VALUE )\r
-               {\r
-                       GPIO_HIGH( LD_GPIO_PORT, LD_GREEN_GPIO_PIN );\r
-                       vTaskDelay( mainLED_TOGGLE_DELAY );\r
-                       GPIO_LOW( LD_GPIO_PORT, LD_GREEN_GPIO_PIN );\r
-               }\r
+               main_full();\r
        }\r
+       #endif\r
+\r
+       /* This line will never be reached. */\r
+       return 0;\r
 }\r
 /*-----------------------------------------------------------*/\r
 \r
@@ -261,64 +142,31 @@ EXTI_InitTypeDef EXTI_InitStructure;
 NVIC_InitTypeDef NVIC_InitStructure;\r
 void SystemCoreClockUpdate( void );\r
 \r
+       /* System function that updates the SystemCoreClock variable. */\r
        SystemCoreClockUpdate();\r
 \r
        /* 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
-       /*!< 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
-\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
-\r
-       /* Reset RTC Backup Domain */\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
+       /* Set internal voltage regulator to 1.5V. */\r
+       PWR_VoltageScalingConfig( PWR_VoltageScaling_Range2 );\r
 \r
-       /* RTC Clock Source Selection */\r
-       RCC_RTCCLKConfig( RCC_RTCCLKSource_LSE );\r
-\r
-       /* Enable the RTC */\r
-       RCC_RTCCLKCmd( ENABLE );\r
-\r
-       /* Disable HSE */\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
-\r
-       /* Set internal voltage regulator to 1.8V */\r
-       PWR_VoltageScalingConfig( PWR_VoltageScaling_Range1 );\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 +177,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
@@ -390,7 +238,7 @@ void vApplicationIdleHook( void )
 }\r
 /*-----------------------------------------------------------*/\r
 \r
-void vApplicationStackOverflowHook( xTaskHandle pxTask, signed char *pcTaskName )\r
+void vApplicationStackOverflowHook( TaskHandle_t pxTask, char *pcTaskName )\r
 {\r
        ( void ) pcTaskName;\r
        ( void ) pxTask;\r
@@ -413,555 +261,25 @@ void vApplicationTickHook( void )
 }\r
 /*-----------------------------------------------------------*/\r
 \r
-void vAssertCalled( void )\r
+void vAssertCalled( unsigned long ulLine, const char * const pcFileName )\r
 {\r
-volatile unsigned long ul = 0;\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
        taskEXIT_CRITICAL();\r
 }\r
 \r
-\r
-#if 0\r
-/**\r
-  ******************************************************************************\r
-  * @file    main.c\r
-  * @author  Microcontroller Division\r
-  * @version V1.0.3\r
-  * @date    May-2013\r
-  * @brief   Main program body\r
-  ******************************************************************************\r
-  * @copy\r
-  *\r
-  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS\r
-  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE\r
-  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY\r
-  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING\r
-  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE\r
-  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.\r
-  *\r
-  * <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>\r
-  */\r
-\r
-/* Includes ------------------------------------------------------------------*/\r
-\r
-#include "main.h"\r
-\r
-#define BOR_MODIFY\r
-#define BOR_LEVEL OB_BOR_OFF  /*!< BOR is disabled at power down, the reset is asserted when the VDD power supply reachs the PDR(Power Down Reset) threshold (1.5V) */\r
-\r
-\r
-/* Private variables ---------------------------------------------------------*/\r
-\r
-static TSL_tTick_ms_T last_tick_tsl;  /* Hold the last tsl time value */\r
-extern unsigned char Bias_Current;    /* Bias Current stored in E²Prom used for ICC mesurement precision */\r
-extern uint8_t t_bar[2];              /* LCD bar graph: used for displaying active function */\r
-extern bool self_test;                /* Auto_test activation flag: set by interrupt handler if user button is pressed for a few seconds */\r
-extern bool Idd_WakeUP;               /* */\r
-extern volatile bool KeyPressed;      /* */\r
-extern bool UserButton;               /* Set by interrupt handler to indicate that user button is pressed */\r
-uint8_t state_machine;                /* Machine status used by main() wich indicats the active function, set by user button in interrupt handler */\r
-uint16_t Int_CurrentSTBY;             /* */\r
-\r
-#ifdef STM32L1XX_MDP\r
-  uint8_t message[29] = "     ** 32L152CDISCOVERY  **";\r
-       #else\r
-       uint8_t message[29] = "     ** STM32L1-DISCOVERY **";\r
-#endif\r
-/*******************************************************************************/\r
-/**\r
-  * @brief main entry point.\r
-  * @par Parameters None\r
-  * @retval void None\r
-  * @par Required preconditions: None\r
-  */\r
-int main(void)\r
-{\r
-  bool StanbyWakeUp ;\r
-  float Current_STBY;\r
-  __IO uint32_t BOROptionBytes = 0;\r
-\r
- /*!< At this stage the microcontroller clock setting is already configured,\r
-       this is done through SystemInit() function which is called from startup\r
-       file (startup_stm32l1xx_md.s) before to branch to application main.\r
-       To reconfigure the default setting of SystemInit() function, refer to\r
-       system_stm32l1xx.c file\r
-     */\r
-\r
-  /* store Standby Current*/\r
-  Int_CurrentSTBY = Current_Measurement();\r
-\r
-  /* Check if the StandBy flag is set */\r
-  if (PWR_GetFlagStatus(PWR_FLAG_SB) != RESET)\r
-  {\r
-    /* System resumed from STANDBY mode */\r
-    /* Clear StandBy flag */\r
-    RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR,ENABLE);\r
-    PWR_ClearFlag(PWR_FLAG_SB);\r
-    /* set StandbyWakeup indicator*/\r
-    StanbyWakeUp = TRUE;\r
-  } else\r
-  {\r
-    /* Reset StandbyWakeup indicator*/\r
-    StanbyWakeUp = FALSE;\r
-  }\r
-\r
-       #ifdef BOR_MODIFY\r
-  /* Get BOR Option Bytes */\r
-  BOROptionBytes = FLASH_OB_GetBOR();\r
-\r
-  if((BOROptionBytes & 0x0F) != BOR_LEVEL)\r
-  {\r
-    /* Unlocks the option bytes block access */\r
-    FLASH_OB_Unlock();\r
-\r
-    /* Clears the FLASH pending flags */\r
-    FLASH_ClearFlag(FLASH_FLAG_EOP|FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR\r
-                  | FLASH_FLAG_SIZERR | FLASH_FLAG_OPTVERR);\r
-\r
-    /* Select the desired V(BOR) Level ---------------------------------------*/\r
-    FLASH_OB_BORConfig(BOR_LEVEL);\r
-\r
-    /* Launch the option byte loading */\r
-    FLASH_OB_Launch();\r
-  }\r
-#endif\r
-\r
-  /* Configure Clocks for Application need */\r
-  RCC_Configuration();\r
-\r
-  /* Set internal voltage regulator to 1.8V */\r
-  PWR_VoltageScalingConfig(PWR_VoltageScaling_Range1);\r
-\r
-  /* Wait Until the Voltage Regulator is ready */\r
-  while (PWR_GetFlagStatus(PWR_FLAG_VOS) != RESET) ;\r
-\r
-  /* Init I/O ports */\r
-  Init_GPIOs();\r
-\r
-  /* Initializes ADC */\r
-  ADC_Icc_Init();\r
-\r
-  /* Enable General interrupts */\r
-  enableGlobalInterrupts();\r
-\r
-  /* Init Touch Sensing configuration */\r
-  TSL_user_Init();\r
-\r
-  /* Initializes the LCD glass */\r
-  LCD_GLASS_Init();\r
-\r
-  /* Reset Keypressed flag used in interrupt and Scrollsentence */\r
-  KeyPressed = FALSE;\r
-\r
-  /* user button actif */\r
-  UserButton = TRUE;\r
-\r
-  /* Check if User button press at Power ON  */\r
-  if ((USERBUTTON_GPIO_PORT->IDR & USERBUTTON_GPIO_PIN) != 0x0)\r
-  {\r
-    /* Measure operational amplifier bias current and store value in E²Prom for application need*/\r
-    Bias_measurement();\r
-  }\r
-\r
-  /* Standard application startup */\r
-  if ( !StanbyWakeUp )\r
-  {\r
-    /* Reset autotest flag stored in memory */\r
-    AUTOTEST(FALSE) ;\r
-\r
-               /* Display Welcome message */\r
-    LCD_GLASS_ScrollSentence(message,1,SCROLL_SPEED);\r
-    if (!KeyPressed)\r
-    {\r
-       /* if welcome message not skipped Display blinking message JP1 ON*/\r
-      LCD_BlinkConfig(LCD_BlinkMode_AllSEG_AllCOM,LCD_BlinkFrequency_Div512);\r
-      LCD_GLASS_DisplayString("JP1 ON");\r
-      TEMPO;\r
-      TEMPO;\r
-      TEMPO;\r
-      TEMPO;\r
-      LCD_BlinkConfig(LCD_BlinkMode_Off,LCD_BlinkFrequency_Div32);\r
-    }\r
-  /* Wake up from Standby or autotest */\r
-  }  else  {\r
-    /*Check Autotest value stored in flash to get wakeup context*/\r
-    if (self_test)\r
-    {\r
-      /* Wake UP: Return of RESET by Auto test */\r
-      auto_test_part2();\r
-    } else {\r
-      /* Wake UP: Return of RESET by Current STAND BY measurement */\r
-      LCD_GLASS_ScrollSentence("     STANDBY WAKEUP",1,SCROLL_SPEED);\r
-      /* Substract bias current from operational amplifier*/\r
-      if ( Int_CurrentSTBY > Bias_Current )\r
-        Int_CurrentSTBY -= Bias_Current;\r
-      Current_STBY = Int_CurrentSTBY * Vdd_appli()/ADC_CONV;\r
-      Current_STBY *= 20L;\r
-      display_MuAmp((uint32_t)Current_STBY);\r
-      /* Wait for user button press to continue */\r
-      while(!KeyPressed);\r
-    }\r
-  }\r
-  /* Reset KeyPress Flag */\r
-  KeyPressed = FALSE;\r
-  /* Clear LCD bars */\r
-  BAR0_OFF;\r
-  BAR1_OFF;\r
-  BAR2_OFF;\r
-  BAR3_OFF;\r
-  /* Switch off the leds*/\r
-  GPIO_HIGH(LD_GPIO_PORT,LD_GREEN_GPIO_PIN);\r
-  GPIO_LOW(LD_GPIO_PORT,LD_BLUE_GPIO_PIN);\r
-  /* Set application state machine to VREF state  */\r
-  state_machine = STATE_VREF ;\r
-  /*Until application reset*/\r
-  while (1)\r
-  {\r
-  /* run autotest if requested by the user */\r
-    if (self_test)\r
-      auto_test();\r
-    /* Perform Actions depending on current application State  */\r
-    switch (state_machine)\r
-    {\r
-        /* VREF State : Display VRef value */\r
-        case STATE_VREF:\r
-          GPIO_TOGGLE(LD_GPIO_PORT,LD_BLUE_GPIO_PIN);\r
-          GPIO_TOGGLE(LD_GPIO_PORT,LD_GREEN_GPIO_PIN);\r
-          Vref_measure();\r
-          TEMPO ;\r
-        break;\r
-\r
-        /* Slider Value State : Display the TS slider value */\r
-        case STATE_SLIDER_VALUE:\r
-\r
-        // Execute STMTouch Driver state machine\r
-        if (TSL_user_Action() == TSL_STATUS_OK)\r
-          {\r
-            ProcessSensors(); // Execute sensors related tasks\r
-          }\r
-        break;\r
-\r
-        /* Slider button State : Display the curent TS button pressed  */\r
-        case STATE_SLIDER_BUTTON:\r
-        // Execute STMTouch Driver state machine\r
-        if (TSL_user_Action() == TSL_STATUS_OK)\r
-          {\r
-            ProcessSensorsButtons(); // Execute sensors related tasks\r
-          }\r
-          break;\r
-\r
-        /* ICC RUN State : ICC mesurements in Run and Sleep modes   */\r
-        case STATE_ICC_RUN:\r
-          LCD_GLASS_DisplayString(" RUN  ");\r
-          TEMPO;\r
-          Icc_RUN();\r
-          TEMPO;\r
-          TEMPO;\r
-          TEMPO;\r
-          TEMPO;\r
-          LCD_GLASS_DisplayString(" SLEEP ");\r
-          TEMPO;\r
-          Icc_SLEEP();\r
-          TEMPO;\r
-          TEMPO;\r
-          TEMPO;\r
-          TEMPO;\r
-        break;\r
-\r
-        /* ICC LOW POWER RUN State : ICC mesurements in LowPower run and LowPower Sleep modes */\r
-        case STATE_ICC_LP_RUN:\r
-          LCD_GLASS_DisplayString("LP RUN");\r
-          TEMPO;\r
-          Icc_LPRUN();\r
-          TEMPO;\r
-          TEMPO;\r
-          TEMPO;\r
-          TEMPO;\r
-          LCD_GLASS_DisplayString("LP SLP");\r
-          TEMPO;\r
-          Icc_LPSLEEP();\r
-          TEMPO;\r
-          TEMPO;\r
-          TEMPO;\r
-          TEMPO;\r
-        break;\r
-\r
-        /* ICC STOP  State : ICC mesurements in Stop and STOP NoRTC modes */\r
-        case STATE_ICC_STOP:\r
-          LCD_GLASS_DisplayString(" STOP ");\r
-          TEMPO;\r
-          Icc_STOP();\r
-          TEMPO;\r
-          TEMPO;\r
-          TEMPO;\r
-          TEMPO;\r
-          LCD_GLASS_DisplayString("SP-NRTC");\r
-          TEMPO;\r
-          Icc_Stop_NoRTC();\r
-          TEMPO;\r
-          TEMPO;\r
-          TEMPO;\r
-          TEMPO;\r
-          break;\r
-\r
-        /* ICC Standby  State : ICC mesurements in Standby mode */\r
-        case STATE_ICC_STBY:\r
-          LCD_GLASS_DisplayString("STBY  ");\r
-          TEMPO;\r
-          TEMPO;\r
-        ADC_Icc_Test(MCU_STBY);\r
-        /* Following break never performed dues to software reset in previous function */\r
-        break;\r
-\r
-        /* for safe: normaly never reaches */\r
-        default:\r
-          LCD_GLASS_Clear();\r
-          LCD_GLASS_DisplayString("ERROR");\r
-        break;\r
-      }\r
-      /* Reset KeyPress flag*/\r
-      KeyPressed = FALSE;\r
-    }\r
-}\r
-\r
-/**\r
-  * @brief  Configures the different system clocks.\r
-  * @param  None\r
-  * @retval None\r
-  */\r
-void RCC_Configuration(void)\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
-\r
-  /* Set HSI as sys clock*/\r
-  RCC_SYSCLKConfig(RCC_SYSCLKSource_HSI);\r
-\r
-  /* Set MSI clock range to ~4.194MHz*/\r
-  RCC_MSIRangeConfig(RCC_MSIRange_6);\r
-\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, LCD and PWR mngt clocks */\r
-  RCC_APB1PeriphClockCmd(RCC_APB1Periph_COMP | RCC_APB1Periph_LCD | RCC_APB1Periph_PWR,ENABLE);\r
-\r
-  /* Enable ADC & SYSCFG clocks */\r
-  RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1 | RCC_APB2Periph_SYSCFG , ENABLE);\r
-\r
-  /* Allow access to the RTC */\r
-  PWR_RTCAccessCmd(ENABLE);\r
-\r
-  /* Reset RTC Backup Domain */\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
-   /* RTC Clock Source Selection */\r
-  RCC_RTCCLKConfig(RCC_RTCCLKSource_LSE);\r
-\r
-  /* Enable the RTC */\r
-  RCC_RTCCLKCmd(ENABLE);\r
-\r
-  /*Disable HSE*/\r
-  RCC_HSEConfig(RCC_HSE_OFF);\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
-\r
-/**\r
-  * @brief  To initialize the I/O ports\r
-  * @caller main\r
-  * @param None\r
-  * @retval None\r
-  */\r
-void  Init_GPIOs (void)\r
-{\r
-  /* GPIO, EXTI and NVIC Init structure declaration */\r
-  GPIO_InitTypeDef GPIO_InitStructure;\r
-  EXTI_InitTypeDef EXTI_InitStructure;\r
-  NVIC_InitTypeDef NVIC_InitStructure;\r
-\r
-  /* Configure User Button pin as input */\r
-  GPIO_InitStructure.GPIO_Pin = USERBUTTON_GPIO_PIN;\r
-  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN;\r
-  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;\r
-  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_40MHz;\r
-  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
-\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
-  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 and set EXTI0 Interrupt to the lowest priority */\r
-  NVIC_InitStructure.NVIC_IRQChannel = EXTI0_IRQn ;\r
-  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0x0F;\r
-  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0x0F;\r
-  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;\r
-  NVIC_Init(&NVIC_InitStructure);\r
-\r
-  /* Configure the LED_pin as output push-pull for LD3 & LD4 usage*/\r
-  GPIO_InitStructure.GPIO_Pin = LD_GREEN_GPIO_PIN | LD_BLUE_GPIO_PIN;\r
-  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;\r
-  GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;\r
-  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;\r
-  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;\r
-  GPIO_Init(LD_GPIO_PORT, &GPIO_InitStructure);\r
-\r
-  /* Force a low level on LEDs*/\r
-  GPIO_LOW(LD_GPIO_PORT,LD_GREEN_GPIO_PIN);\r
-  GPIO_LOW(LD_GPIO_PORT,LD_BLUE_GPIO_PIN);\r
-\r
-/* Counter enable: GPIO set in output for enable the counter */\r
-  GPIO_InitStructure.GPIO_Pin = CTN_CNTEN_GPIO_PIN;\r
-  GPIO_Init( CTN_GPIO_PORT, &GPIO_InitStructure);\r
-\r
-/* To prepare to start counter */\r
-  GPIO_HIGH(CTN_GPIO_PORT,CTN_CNTEN_GPIO_PIN);\r
-\r
-/* Configure Port A LCD Output pins as alternate function */\r
-  GPIO_InitStructure.GPIO_Pin = GPIO_Pin_1 | GPIO_Pin_2 | GPIO_Pin_3 | GPIO_Pin_8 | GPIO_Pin_9 |GPIO_Pin_10 |GPIO_Pin_15;\r
-  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;\r
-  GPIO_Init( GPIOA, &GPIO_InitStructure);\r
-\r
-/* Select LCD alternate function for Port A LCD Output pins */\r
-  GPIO_PinAFConfig(GPIOA, GPIO_PinSource1,GPIO_AF_LCD) ;\r
-  GPIO_PinAFConfig(GPIOA, GPIO_PinSource2,GPIO_AF_LCD) ;\r
-  GPIO_PinAFConfig(GPIOA, GPIO_PinSource3,GPIO_AF_LCD) ;\r
-  GPIO_PinAFConfig(GPIOA, GPIO_PinSource8,GPIO_AF_LCD) ;\r
-  GPIO_PinAFConfig(GPIOA, GPIO_PinSource9,GPIO_AF_LCD) ;\r
-  GPIO_PinAFConfig(GPIOA, GPIO_PinSource10,GPIO_AF_LCD) ;\r
-  GPIO_PinAFConfig(GPIOA, GPIO_PinSource15,GPIO_AF_LCD) ;\r
-\r
-  /* Configure Port B LCD Output pins as alternate function */\r
-  GPIO_InitStructure.GPIO_Pin = GPIO_Pin_3 | GPIO_Pin_4 | GPIO_Pin_5 | GPIO_Pin_8 | GPIO_Pin_9 \\r
-                                 | GPIO_Pin_10 | GPIO_Pin_11 | GPIO_Pin_12 | GPIO_Pin_13 | GPIO_Pin_14 | GPIO_Pin_15;\r
-  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;\r
-  GPIO_Init( GPIOB, &GPIO_InitStructure);\r
-\r
-  /* Select LCD alternate function for Port B LCD Output pins */\r
-  GPIO_PinAFConfig(GPIOB, GPIO_PinSource3,GPIO_AF_LCD) ;\r
-  GPIO_PinAFConfig(GPIOB, GPIO_PinSource4,GPIO_AF_LCD) ;\r
-  GPIO_PinAFConfig(GPIOB, GPIO_PinSource5,GPIO_AF_LCD) ;\r
-  GPIO_PinAFConfig(GPIOB, GPIO_PinSource8,GPIO_AF_LCD) ;\r
-  GPIO_PinAFConfig(GPIOB, GPIO_PinSource9,GPIO_AF_LCD) ;\r
-  GPIO_PinAFConfig(GPIOB, GPIO_PinSource10,GPIO_AF_LCD) ;\r
-  GPIO_PinAFConfig(GPIOB, GPIO_PinSource11,GPIO_AF_LCD) ;\r
-  GPIO_PinAFConfig(GPIOB, GPIO_PinSource12,GPIO_AF_LCD) ;\r
-  GPIO_PinAFConfig(GPIOB, GPIO_PinSource13,GPIO_AF_LCD) ;\r
-  GPIO_PinAFConfig(GPIOB, GPIO_PinSource14,GPIO_AF_LCD) ;\r
-  GPIO_PinAFConfig(GPIOB, GPIO_PinSource15,GPIO_AF_LCD) ;\r
-\r
-  /* Configure Port C LCD Output pins as alternate function */\r
-  GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1 | GPIO_Pin_2 | GPIO_Pin_3 | GPIO_Pin_6 \\r
-                                 | GPIO_Pin_7 | GPIO_Pin_8 | GPIO_Pin_9 | GPIO_Pin_10 |GPIO_Pin_11 ;\r
-  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;\r
-  GPIO_Init( GPIOC, &GPIO_InitStructure);\r
-\r
-  /* Select LCD alternate function for Port B LCD Output pins */\r
-  GPIO_PinAFConfig(GPIOC, GPIO_PinSource0,GPIO_AF_LCD) ;\r
-  GPIO_PinAFConfig(GPIOC, GPIO_PinSource1,GPIO_AF_LCD) ;\r
-  GPIO_PinAFConfig(GPIOC, GPIO_PinSource2,GPIO_AF_LCD) ;\r
-  GPIO_PinAFConfig(GPIOC, GPIO_PinSource3,GPIO_AF_LCD) ;\r
-  GPIO_PinAFConfig(GPIOC, GPIO_PinSource6,GPIO_AF_LCD) ;\r
-  GPIO_PinAFConfig(GPIOC, GPIO_PinSource7,GPIO_AF_LCD) ;\r
-  GPIO_PinAFConfig(GPIOC, GPIO_PinSource8,GPIO_AF_LCD) ;\r
-  GPIO_PinAFConfig(GPIOC, GPIO_PinSource9,GPIO_AF_LCD) ;\r
-  GPIO_PinAFConfig(GPIOC, GPIO_PinSource10,GPIO_AF_LCD) ;\r
-  GPIO_PinAFConfig(GPIOC, GPIO_PinSource11,GPIO_AF_LCD) ;\r
-\r
-  /* Configure ADC (IDD_MEASURE) pin as Analogue */\r
-  GPIO_InitStructure.GPIO_Pin = IDD_MEASURE  ;\r
-  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AN;\r
-  GPIO_Init( IDD_MEASURE_PORT, &GPIO_InitStructure);\r
-}\r
-\r
-\r
-/**\r
-  * @brief  Executed when a sensor is in Error state\r
-  * @param  None\r
-  * @retval None\r
-  */\r
-void MyLinRots_ErrorStateProcess(void)\r
-{\r
-  // Add here your own processing when a sensor is in Error state\r
-  TSL_linrot_SetStateOff();\r
-}\r
-\r
-\r
-/**\r
-  * @brief  Executed when a sensor is in Off state\r
-  * @param  None\r
-  * @retval None\r
-  */\r
-void MyLinRots_OffStateProcess(void)\r
-{\r
-  // Add here your own processing when a sensor is in Off state\r
-}\r
-\r
-\r
-\r
-/**\r
-  * @brief  Inserts a delay time.\r
-  * @param  nTime: specifies the delay time length, in 1 ms.\r
-  * @retval None\r
-  */\r
-void Delay(uint32_t nTime)\r
-{\r
-  while (TSL_tim_CheckDelay_ms((TSL_tTick_ms_T) nTime, &last_tick_tsl) != TSL_STATUS_OK);\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
-void vApplicationStackOverflowHook( void )\r
-{\r
-}\r
-\r
-/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/\r
-\r
-#endif\r
-\r