PX4 Firmware
PX4 Autopilot Software http://px4.io
otp.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 /**
35  * @file otp.h
36  * One TIme Programmable ( OTP ) Flash routine/s.
37  *
38  * @author Lorenz Meier <lm@inf.ethz.ch>
39  * @author David "Buzz" Bussenschutt <davidbuzz@gmail.com>
40  *
41  */
42 
43 #ifndef OTP_H_
44 #define OTP_H_
45 
46 #define ADDR_OTP_START 0x1FFF7800
47 #define ADDR_OTP_LOCK_START 0x1FFF7A00
48 
49 #define OTP_LOCK_LOCKED 0x00
50 #define OTP_LOCK_UNLOCKED 0xFF
51 
52 
53 
54 #include <unistd.h>
55 #include <stdint.h>
56 #include <stdio.h>
57 
58 // possible flash statuses
59 #define F_BUSY 1
60 #define F_ERROR_WRP 2
61 #define F_ERROR_PROGRAM 3
62 #define F_ERROR_OPERATION 4
63 #define F_COMPLETE 5
64 
65 typedef struct {
66  volatile unsigned long accesscontrol; // 0x00
67  volatile unsigned long key; // 0x04
68  volatile unsigned long optionkey; // 0x08
69  volatile unsigned long status; // 0x0C
70  volatile unsigned long control; // 0x10
71  volatile unsigned long optioncontrol; //0x14
73 
74 #define PERIPH_BASE ((unsigned long)0x40000000) //Peripheral base address
75 #define AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000)
76 #define F_R_BASE (AHB1PERIPH_BASE + 0x3C00)
77 #define FLASH ((flash_registers *) F_R_BASE)
78 
79 #define F_BSY ((unsigned long)0x00010000) //FLASH Busy flag bit
80 #define F_OPERR ((unsigned long)0x00000002) //FLASH operation Error flag bit
81 #define F_WRPERR ((unsigned long)0x00000010) //FLASH Write protected error flag bit
82 #define CR_PSIZE_MASK ((unsigned long)0xFFFFFCFF)
83 #define F_PSIZE_WORD ((unsigned long)0x00000200)
84 #define F_PSIZE_BYTE ((unsigned long)0x00000000)
85 #define F_CR_PG ((unsigned long)0x00000001) // a bit in the F_CR register
86 #define F_CR_LOCK ((unsigned long)0x80000000) // also another bit.
87 
88 #define F_KEY1 ((unsigned long)0x45670123)
89 #define F_KEY2 ((unsigned long)0xCDEF89AB)
90 #define IS_F_ADDRESS(ADDRESS) ((((ADDRESS) >= 0x08000000) && ((ADDRESS) < 0x080FFFFF)) || (((ADDRESS) >= 0x1FFF7800) && ((ADDRESS) < 0x1FFF7A0F)))
91 
92 
93 
94 #pragma pack(push, 1)
95 
96 /*
97  * The OTP area is divided into 16 OTP data blocks of 32 bytes and one lock OTP block of 16 bytes.
98  * The OTP data and lock blocks cannot be erased. The lock block contains 16 bytes LOCKBi (0 ≤ i ≤ 15)
99  * to lock the corresponding OTP data block (blocks 0 to 15). Each OTP data block can be programmed
100  * until the value 0x00 is programmed in the corresponding OTP lock byte. The lock bytes must only
101  * contain 0x00 and 0xFF values, otherwise the OTP bytes might not be taken into account correctly.
102  */
103 
104 struct otp {
105  // first 32 bytes = the '0' Block
106  char id[4]; ///4 bytes < 'P' 'X' '4' '\n'
107  uint8_t id_type; ///1 byte < 0 for USB VID, 1 for generic VID
108  uint32_t vid; ///4 bytes
109  uint32_t pid; ///4 bytes
110  char unused[19]; ///19 bytes
111  // Cert-of-Auth is next 4 blocks ie 1-4 ( where zero is first block )
112  char signature[128];
113  // insert extras here
114  uint32_t lock_bytes[4];
115 };
116 
117 struct otp_lock {
118  uint8_t lock_bytes[16];
119 };
120 #pragma pack(pop)
121 
122 #define ADDR_F_SIZE 0x1FFF7A22
123 
124 #pragma pack(push, 1)
125 union udid {
126  uint32_t serial[3];
127  uint8_t data[12];
128 };
129 #pragma pack(pop)
130 
132 
133 __EXPORT void F_unlock(void);
134 __EXPORT void F_lock(void);
135 __EXPORT int val_read(void *dest, volatile const void *src, int bytes);
136 __EXPORT int val_write(volatile void *dest, const void *src, int bytes);
137 __EXPORT int write_otp(uint8_t id_type, uint32_t vid, uint32_t pid, char *signature);
138 __EXPORT int lock_otp(void);
139 
140 
141 __EXPORT int F_write_byte(unsigned long Address, uint8_t Data);
142 __EXPORT int F_write_word(unsigned long Address, uint32_t Data);
143 
145 
146 #endif
volatile unsigned long optioncontrol
Definition: otp.h:71
Definition: otp.h:104
#define __END_DECLS
Definition: visibility.h:59
uint32_t pid
4 bytes
Definition: otp.h:109
Definition: I2C.hpp:51
__EXPORT int lock_otp(void)
Definition: otp.c:121
Definition: otp.h:125
__BEGIN_DECLS __EXPORT void F_unlock(void)
Definition: otp.c:173
volatile unsigned long control
Definition: otp.h:70
uint32_t lock_bytes[4]
Definition: otp.h:114
uint8_t * data
Definition: dataman.cpp:149
#define __BEGIN_DECLS
Definition: visibility.h:58
__EXPORT int F_write_word(unsigned long Address, uint32_t Data)
Definition: otp.c:188
uint32_t vid
1 byte < 0 for USB VID, 1 for generic VID
Definition: otp.h:108
volatile unsigned long status
Definition: otp.h:69
volatile unsigned long key
Definition: otp.h:67
__EXPORT int write_otp(uint8_t id_type, uint32_t vid, uint32_t pid, char *signature)
Definition: otp.c:71
__EXPORT int val_write(volatile void *dest, const void *src, int bytes)
char unused[19]
4 bytes
Definition: otp.h:110
__EXPORT void F_lock(void)
Definition: otp.c:182
uint8_t id_type
4 bytes < &#39;P&#39; &#39;X&#39; &#39;4&#39; &#39; &#39;
Definition: otp.h:107
__EXPORT int val_read(void *dest, volatile const void *src, int bytes)
Definition: otp.c:58
volatile unsigned long accesscontrol
Definition: otp.h:66
Definition: otp.h:117
volatile unsigned long optionkey
Definition: otp.h:68
__EXPORT int F_write_byte(unsigned long Address, uint8_t Data)
Definition: otp.c:203
char signature[128]
19 bytes
Definition: otp.h:112