LPC2k_ee.h
Go to the documentation of this file.
00001 /************************************************************************/
00002 /*                                                                      */
00003 /*                      LPC2k_ee.H:  Header file enabling EEPROM support                        */
00004 /*              for Philips LPC2000 microcontroller's on-chip Flash memory              */
00005 /*                              (revision 1.0, May 13th, 2005.)                                         */
00006 /*                                                                      */
00007 /*                      This file is to be used with LPC2k_ee.c file                            */
00008 /*                                                                      */
00009 /* IMPORTANT: on-chip Flash memory sector(s) intended to be used as     */
00010 /* an EEPROM will be unavailable for regular code storage! The smallest */
00011 /* amount of Flash memory that can be used as an EEPROM is a single     */
00012 /* Flash sector (regardless of the Flash sector actual size).                   */
00013 /*                                                                      */
00014 /* If size of desired EEPROM requires several Flash sectors, these              */
00015 /* sectors must be a consecutive ones.                                                                  */
00016 /*                                                                      */
00017 /************************************************************************/
00018 
00019 #define EE_SEC_L                14                              //Flash sector where EEPROM begins (see UM for details)
00020 #define EE_SEC_H                14                              //Flash sector where EEPROM ends (see UM for details)
00021 #define EE_ADDR_L               0x00038000              //Must match the EE_SEC_L Flash sector start address
00022 #define EE_ADDR_H               0x0003FFFF              //Must match the EE_SEC_H Flash sector end address
00023 
00024 #define EE_CCLK                 60000                   //system clock cclk expressed in kHz (5*12 MHz)
00025 
00026 /************************************************************************/
00027 /*                                                                      */
00028 /* ee_data structure can be defined differently from this example.              */
00029 /* The only requirement is to have _id field as it is defined here              */
00030 /* since EE_REC_ID character is used to identify a record's presence    */
00031 /* in the EEPROM memory.                                                                                                */
00032 /*                                                                      */
00033 /* ==================================================================== */
00034 /*                                                                      */
00035 /* IMPORTANT ARM memory access considerations:                                                  */
00036 /*                                                                      */
00037 /* char         : byte alligned. Can be accessed at any location in memory.     */
00038 /*                                                                      */
00039 /* short int: occupies 2 consecutive bytes. It can be read/write                */
00040 /*                        accessed only when half-word alligned. Therefore, it is       */
00041 /*                        located at addresses ending with 0x0, 0x2, 0x4, 0x6, 0x8,     */
00042 /*                        0xA, 0xC or 0xE.                                                                                      */
00043 /*                                                                      */
00044 /* int          : occupies 4 consecutive bytes. It can be read/write            */
00045 /*                        accessed only when half-word alligned. Therefore, it is       */
00046 /*                        located at addresses ending with 0x0, 0x4, 0x8 or 0xC.        */
00047 /*                                                                      */
00048 /* ==================================================================== */
00049 /*                                                                      */
00050 /* Due to the LPC2000 Flash memory characteristics, an ee_data                  */
00051 /* structure size (EE_REC_SIZE) is limited to the following set:                */
00052 /*                                                                      */
00053 /* LPC2101/2/3, LPC2131/2/4/6/8, LPC2141/2/4/6/8: 0x10, 0x20, 0x40,     */ 
00054 /*                                                0x80 or 0x100         */
00055 /*                                                                      */
00056 /* LPC2104/5/6, LPC2112/4/9, LPC2124/9, LPC2192/4: 0x10, 0x20, 0x40,    */
00057 /*                                                 0x80, 0x100 or 0x200 */
00058 /*                                                                      */
00059 /* ==================================================================== */
00060 /*                                                                      */
00061 /* example1:                                                            */
00062 /*                                                                      */
00063 /* struct ee_data{                                      //structure starts as word alligned     */
00064 /*      unsigned char   _id;                    //1 byte  - no allignement restr.       */
00065 /*                                  //              3 BYTE GAP!!!!              */              
00066 /*      unsigned int    _rec_count;             //4 bytes - must be word alligned!      */
00067 /*      unsigned char   _cs;                    //1 byte  - no allignement restr.       */
00068 /*};                                                            // next structure will start as         */
00069 /*                                  // word alligned...                 */
00070 /* Structure in example 1 occupies 12 bytes of memory                                   */
00071 /*                                                                      */
00072 /* -------------------------------------------------------------------- */
00073 /*                               
00074                                         */
00075 /* example2:                                                            */
00076 /*                                                                      */
00077 /* struct ee_data{                                      //structure starts as word alligned     */
00078 /*      unsigned char   _id;                    //1 byte  - no allignement restr.       */
00079 /*      unsigned char   _cs;                    //1 byte  - no allignement restr.       */
00080 /*                                  //              2 BYTE GAP!!!!              */              
00081 /*      unsigned int    _rec_count;             //4 bytes - must be word alligned!      */
00082 /*};                                                            // next structure will start as         */
00083 /*                                  // word alligned...                 */
00084 /* Structure in example 2 occupies 8 bytes of memory                                    */
00085 /*                                                                      */
00086 /************************************************************************/
00087 
00088 struct ee_data{
00089         unsigned char   _id;                            //  4 bytes: 1 byte (char) + 3 byte GAP!
00090         
00091         int     acc_mid_x;
00092         int     acc_mid_y;
00093         int     acc_mid_z;
00094         
00095         int     acc_scale_x;
00096         int     acc_scale_y;
00097         int     acc_scale_z;
00098         
00099         int     mag_offset_x;
00100         int     mag_offset_y;
00101         int     mag_offset_z;
00102 
00103         int     mag_scale_x;
00104         int     mag_scale_y;
00105         int     mag_scale_z;
00106         
00107         int     gyro_offset_x;
00108         int     gyro_offset_y;
00109         int     gyro_offset_z;
00110 
00111         int     int_mult;
00112         int     int_div;
00113         
00114         int     used;
00115         
00116 //      int FlightParams[sizeof(struct FLIGHT_PARAMETERS)];
00117         
00118 };                                                                              // 16 bytes total
00119 
00120 struct ee_data2{
00121         unsigned char   _id;                            //  4 bytes: 1 byte (char) + 3 byte GAP!        
00122         int FlightParams[63];
00123 };
00124 
00125 /************************************************************************/
00126 /*                                                                                                                                              */
00127 /*      Disclaimer: all observations presented in example1, example 2 and       */
00128 /*      ee_data structure defined here are based on Keil's ARM compiler.        */
00129 /*      If another compiler is used, memory usage would have to be                      */
00130 /*      re-examined and verified.                                                                                       */
00131 /*                                                                                                                                              */
00132 /************************************************************************/
00133 
00134 
00135 #define EE_REC_SIZE             0x100           //see restrictions from above
00136 
00137 /********************************************************************/
00138 /*                                                                                                                                      */
00139 /*                                              Valid combinations for                                          */
00140 /* EE_REC_SIZE, EE_BUFFER_SIZE, EE_BUFFER_MASK and EE_START_MASK        */
00141 /*                                                                                                                                      */
00142 /* EE_BUFFER_SIZE ! EE_START_MASK ! EE_REC_SIZE ! EE_BUFFER_MASK        */
00143 /* ----------------------------------------------------------------     */
00144 /*      256                     0xFFFFFF00                      0x010                   0xF0            */
00145 /*              256                     0xFFFFFF00                      0x020                   0xE0            */
00146 /*      256                     0xFFFFFF00                      0x040                   0xC0            */
00147 /*              256                     0xFFFFFF00                      0x080                   0x80            */
00148 /*              256                     0xFFFFFF00                      0x100                   0x00            */
00149 /* ---------------------------------------------------------------- */
00150 /*      512                     0xFFFFFE00                      0x010                   0x1F0           */
00151 /*              512                     0xFFFFFE00                      0x020                   0x1E0           */
00152 /*      512                     0xFFFFFE00                      0x040                   0x1C0           */
00153 /*              512                     0xFFFFFE00                      0x080                   0x180           */
00154 /*              512                     0xFFFFFE00                      0x100                   0x100           */
00155 /*              512                     0xFFFFFE00                      0x200                   0x000           */
00156 /********************************************************************/
00157 /*      For LPC2101/2/3, LPC213x and LPC214x EE_BUFFER_SIZE is 256.             */
00158 /*      For all other LPC2000 devices EE_BUFFER_SIZE is always 512.             */
00159 /********************************************************************/
00160 #define EE_BUFFER_SIZE  256
00161 #define EE_START_MASK   0xFFFFFF00
00162 #define EE_BUFFER_MASK  0x00000000
00163 
00164 /********************************************************************/
00172 /********************************************************************/
00173 
00174 #define EE_REC_ID                               0xAA
00175 #define EE_SIZE                                 (EE_ADDR_H+1-EE_ADDR_L)
00176 #define NO_RECORDS_AVAILABLE    500
00177 #define NO_SPACE_IN_EEPROM              501
00178 #define INDEX_OUT_OF_RANGE              502
00179 
00180 #ifndef _EEPROM_
00181         extern const unsigned char eeprom[];
00182         extern void ee_erase(unsigned int , unsigned int []);   //function erases EEPROM
00183         extern void ee_write(unsigned int , unsigned int []);   //function adds a record in EEPROM
00184         extern void ee_read (unsigned int , unsigned int []);   //function reads the latest valid record in EEPROM
00185         extern void ee_readn(unsigned int , unsigned int []);   //function reads n-th record in EEPROM
00186         extern void ee_count(unsigned int , unsigned int []);   //function counts records in EEPROM
00187 #endif


asctec_hl_firmware
Author(s): Markus Achtelik, Michael Achtelik, Stephan Weiss, Laurent Kneip
autogenerated on Tue Jan 7 2014 11:05:19