PX4 Firmware
PX4 Autopilot Software http://px4.io
otp.c
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (C) 2012-2013 PX4 Development Team. All rights reserved.
4  * Authors:
5  * Lorenz Meier <lm@inf.ethz.ch>
6  * David "Buzz" Bussenschutt <davidbuzz@gmail.com>
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * 1. Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * 2. Redistributions in binary form must reproduce the above copyright
15  * notice, this list of conditions and the following disclaimer in
16  * the documentation and/or other materials provided with the
17  * distribution.
18  * 3. Neither the name PX4 nor the names of its contributors may be
19  * used to endorse or promote products derived from this software
20  * without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
29  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
30  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  ****************************************************************************/
36 
37 /**
38  * @file otp.c
39  * otp estimation
40  *
41  * @author Lorenz Meier <lm@inf.ethz.ch>
42  * @author David "Buzz" Bussenschutt <davidbuzz@gmail.com>
43  *
44  */
45 
46 #include <px4_platform_common/px4_config.h>
47 #include <board_config.h>
48 #include <stdio.h>
49 #include <math.h>
50 #include <unistd.h>
51 #include <string.h> // memset
52 #include "conversions.h"
53 #include "otp.h"
54 #include "err.h" // warnx
55 #include <assert.h>
56 
57 
58 int val_read(void *dest, volatile const void *src, int bytes)
59 {
60 
61  int i;
62 
63  for (i = 0; i < bytes / 4; i++) {
64  *(((volatile unsigned *)dest) + i) = *(((volatile unsigned *)src) + i);
65  }
66 
67  return i * 4;
68 }
69 
70 
71 int write_otp(uint8_t id_type, uint32_t vid, uint32_t pid, char *signature)
72 {
73 
74  warnx("write_otp: PX4 / %02X / %02lX / %02lX / ... etc \n", id_type, (unsigned long)vid, (unsigned long)pid);
75 
76  int errors = 0;
77 
78  // descriptor
79  if (F_write_byte(ADDR_OTP_START, 'P')) {
80  errors++;
81  }
82 
83  // write the 'P' from PX4. to first byte in OTP
84  if (F_write_byte(ADDR_OTP_START + 1, 'X')) {
85  errors++; // write the 'P' from PX4. to first byte in OTP
86  }
87 
88  if (F_write_byte(ADDR_OTP_START + 2, '4')) {
89  errors++;
90  }
91 
92  if (F_write_byte(ADDR_OTP_START + 3, '\0')) {
93  errors++;
94  }
95 
96  //id_type
97  if (F_write_byte(ADDR_OTP_START + 4, id_type)) {
98  errors++;
99  }
100 
101  // vid and pid are 4 bytes each
102  if (F_write_word(ADDR_OTP_START + 5, vid)) {
103  errors++;
104  }
105 
106  if (F_write_word(ADDR_OTP_START + 9, pid)) {
107  errors++;
108  }
109 
110  // leave some 19 bytes of space, and go to the next block...
111  // then the auth sig starts
112  for (int i = 0 ; i < 128 ; i++) {
113  if (F_write_byte(ADDR_OTP_START + 32 + i, signature[i])) {
114  errors++;
115  }
116  }
117 
118  return errors;
119 }
120 
121 int lock_otp(void)
122 {
123  //determine the required locking size - can only write full lock bytes */
124 // int size = sizeof(struct otp) / 32;
125 //
126 // struct otp_lock otp_lock_mem;
127 //
128 // memset(&otp_lock_mem, OTP_LOCK_UNLOCKED, sizeof(otp_lock_mem));
129 // for (int i = 0; i < sizeof(otp_lock_mem) / sizeof(otp_lock_mem.lock_bytes[0]); i++)
130 // otp_lock_mem.lock_bytes[i] = OTP_LOCK_LOCKED;
131  //XXX add the actual call here to write the OTP_LOCK bytes only at final stage
132  // val_copy(lock_ptr, &otp_lock_mem, sizeof(otp_lock_mem));
133 
134  int locksize = 5;
135 
136  int errors = 0;
137 
138  // or just realise it's exctly 5x 32byte blocks we need to lock. 1 block for ID,type,vid,pid, and 4 blocks for certificate, which is 128 bytes.
139  for (int i = 0 ; i < locksize ; i++) {
141  errors++;
142  }
143  }
144 
145  return errors;
146 }
147 
148 
149 
150 // COMPLETE, BUSY, or other flash error?
151 static int F_GetStatus(void)
152 {
153  int fs = F_COMPLETE;
154 
155  if ((FLASH->status & F_BSY) == F_BSY) { fs = F_BUSY; } else {
156 
157  if ((FLASH->status & F_WRPERR) != (uint32_t)0x00) { fs = F_ERROR_WRP; } else {
158 
159  if ((FLASH->status & (uint32_t)0xEF) != (uint32_t)0x00) { fs = F_ERROR_PROGRAM; } else {
160 
161  if ((FLASH->status & F_OPERR) != (uint32_t)0x00) { fs = F_ERROR_OPERATION; } else {
162  fs = F_COMPLETE;
163  }
164  }
165  }
166  }
167 
168  return fs;
169 }
170 
171 
172 // enable FLASH Registers
173 void F_unlock(void)
174 {
175  if ((FLASH->control & F_CR_LOCK) != 0) {
176  FLASH->key = F_KEY1;
177  FLASH->key = F_KEY2;
178  }
179 }
180 
181 // lock the FLASH Registers
182 void F_lock(void)
183 {
184  FLASH->control |= F_CR_LOCK;
185 }
186 
187 // flash write word.
188 int F_write_word(unsigned long Address, uint32_t Data)
189 {
190  unsigned char octet[4] = {0, 0, 0, 0};
191 
192  int ret = 0;
193 
194  for (int i = 0; i < 4; i++) {
195  octet[i] = (Data >> (i * 8)) & 0xFF;
196  ret = F_write_byte(Address + i, octet[i]);
197  }
198 
199  return ret;
200 }
201 
202 // flash write byte
203 int F_write_byte(unsigned long Address, uint8_t Data)
204 {
205  volatile int status = F_COMPLETE;
206 
207  //warnx("F_write_byte: %08X %02d", Address , Data ) ;
208 
209  //Check the parameters
210  assert(IS_F_ADDRESS(Address));
211 
212  //Wait for FLASH operation to complete by polling on BUSY flag.
213  status = F_GetStatus();
214 
215  while (status == F_BUSY) { status = F_GetStatus();}
216 
217  if (status == F_COMPLETE) {
218  //if the previous operation is completed, proceed to program the new data
219  FLASH->control &= CR_PSIZE_MASK;
220  FLASH->control |= F_PSIZE_BYTE;
221  FLASH->control |= F_CR_PG;
222 
223  *(volatile uint8_t *)Address = Data;
224 
225  //Wait for FLASH operation to complete by polling on BUSY flag.
226  status = F_GetStatus();
227 
228  while (status == F_BUSY) { status = F_GetStatus();}
229 
230  //if the program operation is completed, disable the PG Bit
231  FLASH->control &= (~F_CR_PG);
232  }
233 
234  //Return the Program Status
235  return !(status == F_COMPLETE);
236 }
237 
238 
239 
#define F_CR_PG
Definition: otp.h:85
static struct vehicle_status_s status
Definition: Commander.cpp:138
#define F_WRPERR
Definition: otp.h:81
#define F_KEY2
Definition: otp.h:89
void F_unlock(void)
Definition: otp.c:173
#define ADDR_OTP_LOCK_START
Definition: otp.h:47
#define F_BUSY
Definition: otp.h:59
#define F_BSY
Definition: otp.h:79
int lock_otp(void)
Definition: otp.c:121
int val_read(void *dest, volatile const void *src, int bytes)
Definition: otp.c:58
int F_write_word(unsigned long Address, uint32_t Data)
Definition: otp.c:188
#define F_COMPLETE
Definition: otp.h:63
#define IS_F_ADDRESS(ADDRESS)
Definition: otp.h:90
#define F_ERROR_PROGRAM
Definition: otp.h:61
void F_lock(void)
Definition: otp.c:182
#define F_OPERR
Definition: otp.h:80
#define F_CR_LOCK
Definition: otp.h:86
int write_otp(uint8_t id_type, uint32_t vid, uint32_t pid, char *signature)
Definition: otp.c:71
Definition of commonly used conversions.
#define warnx(...)
Definition: err.h:95
Simple error/warning functions, heavily inspired by the BSD functions of the same names...
static int F_GetStatus(void)
Definition: otp.c:151
#define ADDR_OTP_START
Definition: otp.h:46
#define F_ERROR_OPERATION
Definition: otp.h:62
#define F_ERROR_WRP
Definition: otp.h:60
#define F_PSIZE_BYTE
Definition: otp.h:84
#define F_KEY1
Definition: otp.h:88
#define CR_PSIZE_MASK
Definition: otp.h:82
#define OTP_LOCK_LOCKED
Definition: otp.h:49
#define FLASH
Definition: otp.h:77
int F_write_byte(unsigned long Address, uint8_t Data)
Definition: otp.c:203
One TIme Programmable ( OTP ) Flash routine/s.