forked from Archive/PX4-Autopilot
OTP return value cleanup
This commit is contained in:
parent
4ef7817d96
commit
0ef85c133b
|
@ -43,6 +43,8 @@
|
|||
*
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <board_config.h>
|
||||
#include <stdio.h>
|
||||
#include <math.h>
|
||||
#include <unistd.h>
|
||||
|
@ -53,39 +55,53 @@
|
|||
#include <assert.h>
|
||||
|
||||
|
||||
int val_read(void* dest, volatile const void* src, int bytes)
|
||||
int val_read(void *dest, volatile const void *src, int bytes)
|
||||
{
|
||||
|
||||
int i;
|
||||
|
||||
for (i = 0; i < bytes / 4; i++) {
|
||||
*(((volatile uint32_t *)dest) + i) = *(((volatile uint32_t *)src) + i);
|
||||
*(((volatile unsigned *)dest) + i) = *(((volatile unsigned *)src) + i);
|
||||
}
|
||||
return i*4;
|
||||
|
||||
return i * 4;
|
||||
}
|
||||
|
||||
|
||||
int write_otp(uint8_t id_type, uint32_t vid, uint32_t pid, char* signature)
|
||||
int write_otp(uint8_t id_type, uint32_t vid, uint32_t pid, char *signature)
|
||||
{
|
||||
|
||||
warnx("write_otp: PX4 / %02X / %02X / %02X / ... etc \n",id_type, vid, pid);
|
||||
warnx("write_otp: PX4 / %02X / %02X / %02X / ... etc \n", id_type, vid, pid);
|
||||
|
||||
int errors = 0;
|
||||
|
||||
// descriptor
|
||||
F_write_byte( ADDR_OTP_START, 'P'); // write the 'P' from PX4. to first byte in OTP
|
||||
F_write_byte( ADDR_OTP_START+1, 'X'); // write the 'P' from PX4. to first byte in OTP
|
||||
F_write_byte( ADDR_OTP_START+2, '4');
|
||||
F_write_byte( ADDR_OTP_START+3, '\0');
|
||||
if (F_write_byte(ADDR_OTP_START, 'P'))
|
||||
errors++;
|
||||
// write the 'P' from PX4. to first byte in OTP
|
||||
if (F_write_byte(ADDR_OTP_START + 1, 'X'))
|
||||
errors++; // write the 'P' from PX4. to first byte in OTP
|
||||
if (F_write_byte(ADDR_OTP_START + 2, '4'))
|
||||
errors++;
|
||||
if (F_write_byte(ADDR_OTP_START + 3, '\0'))
|
||||
errors++;
|
||||
//id_type
|
||||
F_write_byte( ADDR_OTP_START+4, id_type);
|
||||
if (F_write_byte(ADDR_OTP_START + 4, id_type))
|
||||
errors++;
|
||||
// vid and pid are 4 bytes each
|
||||
F_write_word( ADDR_OTP_START+5, vid);
|
||||
F_write_word( ADDR_OTP_START+9, pid);
|
||||
if (F_write_word(ADDR_OTP_START + 5, vid))
|
||||
errors++;
|
||||
if (F_write_word(ADDR_OTP_START + 9, pid))
|
||||
errors++;
|
||||
|
||||
// leave some 19 bytes of space, and go to the next block...
|
||||
// then the auth sig starts
|
||||
for ( int i = 0 ; i < 128 ; i++ ) {
|
||||
F_write_byte( ADDR_OTP_START+32+i, signature[i]);
|
||||
for (int i = 0 ; i < 128 ; i++) {
|
||||
if (F_write_byte(ADDR_OTP_START + 32 + i, signature[i]))
|
||||
errors++;
|
||||
}
|
||||
|
||||
|
||||
return errors;
|
||||
}
|
||||
|
||||
int lock_otp(void)
|
||||
|
@ -102,23 +118,38 @@ int lock_otp(void)
|
|||
// val_copy(lock_ptr, &otp_lock_mem, sizeof(otp_lock_mem));
|
||||
|
||||
int locksize = 5;
|
||||
|
||||
int errors = 0;
|
||||
|
||||
// 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.
|
||||
for ( int i = 0 ; i < locksize ; i++ ) {
|
||||
F_write_byte( ADDR_OTP_LOCK_START+i, OTP_LOCK_LOCKED);
|
||||
for (int i = 0 ; i < locksize ; i++) {
|
||||
if (F_write_byte(ADDR_OTP_LOCK_START + i, OTP_LOCK_LOCKED))
|
||||
errors++;
|
||||
}
|
||||
|
||||
return errors;
|
||||
}
|
||||
|
||||
|
||||
|
||||
// COMPLETE, BUSY, or other flash error?
|
||||
uint8_t F_GetStatus(void) {
|
||||
uint8_t fs = F_COMPLETE;
|
||||
if((FLASH->status & F_BSY) == F_BSY) { fs = F_BUSY; } else {
|
||||
if((FLASH->status & F_WRPERR) != (uint32_t)0x00) { fs = F_ERROR_WRP; } else {
|
||||
if((FLASH->status & (uint32_t)0xEF) != (uint32_t)0x00) { fs = F_ERROR_PROGRAM; } else {
|
||||
if((FLASH->status & F_OPERR) != (uint32_t)0x00) { fs = F_ERROR_OPERATION; } else {
|
||||
fs = F_COMPLETE; } } } }
|
||||
int F_GetStatus(void)
|
||||
{
|
||||
int fs = F_COMPLETE;
|
||||
|
||||
if ((FLASH->status & F_BSY) == F_BSY) { fs = F_BUSY; } else {
|
||||
|
||||
if ((FLASH->status & F_WRPERR) != (uint32_t)0x00) { fs = F_ERROR_WRP; } else {
|
||||
|
||||
if ((FLASH->status & (uint32_t)0xEF) != (uint32_t)0x00) { fs = F_ERROR_PROGRAM; } else {
|
||||
|
||||
if ((FLASH->status & F_OPERR) != (uint32_t)0x00) { fs = F_ERROR_OPERATION; } else {
|
||||
fs = F_COMPLETE;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return fs;
|
||||
}
|
||||
|
||||
|
@ -126,8 +157,7 @@ uint8_t F_GetStatus(void) {
|
|||
// enable FLASH Registers
|
||||
void F_unlock(void)
|
||||
{
|
||||
if((FLASH->control & F_CR_LOCK) != 0)
|
||||
{
|
||||
if ((FLASH->control & F_CR_LOCK) != 0) {
|
||||
FLASH->key = F_KEY1;
|
||||
FLASH->key = F_KEY2;
|
||||
}
|
||||
|
@ -140,21 +170,24 @@ void F_lock(void)
|
|||
}
|
||||
|
||||
// flash write word.
|
||||
uint8_t F_write_word(uint32_t Address, uint32_t Data)
|
||||
int F_write_word(uint32_t Address, uint32_t Data)
|
||||
{
|
||||
unsigned char octet[4] = {0,0,0,0};
|
||||
for (int i=0; i<4; i++)
|
||||
{
|
||||
octet[i] = ( Data >> (i*8) ) & 0xFF;
|
||||
F_write_byte(Address+i,octet[i]);
|
||||
unsigned char octet[4] = {0, 0, 0, 0};
|
||||
|
||||
int ret = 0;
|
||||
|
||||
for (int i = 0; i < 4; i++) {
|
||||
octet[i] = (Data >> (i * 8)) & 0xFF;
|
||||
ret = F_write_byte(Address + i, octet[i]);
|
||||
}
|
||||
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
// flash write byte
|
||||
uint8_t F_write_byte(uint32_t Address, uint8_t Data)
|
||||
int F_write_byte(uint32_t Address, uint8_t Data)
|
||||
{
|
||||
volatile uint8_t status = F_COMPLETE;
|
||||
volatile int status = F_COMPLETE;
|
||||
|
||||
//warnx("F_write_byte: %08X %02d", Address , Data ) ;
|
||||
|
||||
|
@ -163,29 +196,29 @@ uint8_t F_write_byte(uint32_t Address, uint8_t Data)
|
|||
|
||||
//Wait for FLASH operation to complete by polling on BUSY flag.
|
||||
status = F_GetStatus();
|
||||
while(status == F_BUSY){ status = F_GetStatus();}
|
||||
|
||||
if(status == F_COMPLETE)
|
||||
{
|
||||
while (status == F_BUSY) { status = F_GetStatus();}
|
||||
|
||||
if (status == F_COMPLETE) {
|
||||
//if the previous operation is completed, proceed to program the new data
|
||||
FLASH->control &= CR_PSIZE_MASK;
|
||||
FLASH->control |= F_PSIZE_BYTE;
|
||||
FLASH->control |= F_CR_PG;
|
||||
|
||||
*(volatile uint8_t*)Address = Data;
|
||||
*(volatile uint8_t *)Address = Data;
|
||||
|
||||
//Wait for FLASH operation to complete by polling on BUSY flag.
|
||||
status = F_GetStatus();
|
||||
while(status == F_BUSY){ status = F_GetStatus();}
|
||||
|
||||
while (status == F_BUSY) { status = F_GetStatus();}
|
||||
|
||||
//if the program operation is completed, disable the PG Bit
|
||||
FLASH->control &= (~F_CR_PG);
|
||||
}
|
||||
|
||||
//Return the Program Status
|
||||
return status;
|
||||
return !(status == F_COMPLETE);
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
|
@ -1,9 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012-2013 PX4 Development Team. All rights reserved.
|
||||
* Authors:
|
||||
* Lorenz Meier <lm@inf.ethz.ch>
|
||||
* David "Buzz" Bussenschutt <davidbuzz@gmail.com>
|
||||
* Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
@ -46,7 +43,7 @@
|
|||
#ifndef OTP_H_
|
||||
#define OTP_H_
|
||||
|
||||
__BEGIN_DECLS
|
||||
__BEGIN_DECLS
|
||||
|
||||
#define ADDR_OTP_START 0x1FFF7800
|
||||
#define ADDR_OTP_LOCK_START 0x1FFF7A00
|
||||
|
@ -66,8 +63,7 @@
|
|||
#define F_ERROR_OPERATION 4
|
||||
#define F_COMPLETE 5
|
||||
|
||||
typedef struct
|
||||
{
|
||||
typedef struct {
|
||||
volatile uint32_t accesscontrol; // 0x00
|
||||
volatile uint32_t key; // 0x04
|
||||
volatile uint32_t optionkey; // 0x08
|
||||
|
@ -96,7 +92,7 @@ typedef struct
|
|||
|
||||
|
||||
|
||||
#pragma pack(push, 1)
|
||||
#pragma pack(push, 1)
|
||||
|
||||
/*
|
||||
* The OTP area is divided into 16 OTP data blocks of 32 bytes and one lock OTP block of 16 bytes.
|
||||
|
@ -106,7 +102,7 @@ typedef struct
|
|||
* contain 0x00 and 0xFF values, otherwise the OTP bytes might not be taken into account correctly.
|
||||
*/
|
||||
|
||||
struct otp {
|
||||
struct otp {
|
||||
// first 32 bytes = the '0' Block
|
||||
char id[4]; ///4 bytes < 'P' 'X' '4' '\n'
|
||||
uint8_t id_type; ///1 byte < 0 for USB VID, 1 for generic VID
|
||||
|
@ -117,39 +113,38 @@ typedef struct
|
|||
char signature[128];
|
||||
// insert extras here
|
||||
uint32_t lock_bytes[4];
|
||||
};
|
||||
};
|
||||
|
||||
struct otp_lock {
|
||||
struct otp_lock {
|
||||
uint8_t lock_bytes[16];
|
||||
};
|
||||
};
|
||||
#pragma pack(pop)
|
||||
|
||||
#define UDID_START 0x1FFF7A10
|
||||
#define ADDR_F_SIZE 0x1FFF7A22
|
||||
|
||||
#pragma pack(push, 1)
|
||||
union udid {
|
||||
union udid {
|
||||
uint32_t serial[3];
|
||||
char data[12];
|
||||
};
|
||||
};
|
||||
#pragma pack(pop)
|
||||
|
||||
|
||||
/**
|
||||
/**
|
||||
* s
|
||||
*/
|
||||
//__EXPORT float calc_indicated_airspeed(float differential_pressure);
|
||||
//__EXPORT float calc_indicated_airspeed(float differential_pressure);
|
||||
|
||||
__EXPORT void F_unlock(void);
|
||||
__EXPORT void F_lock(void);
|
||||
__EXPORT int val_read(void* dest, volatile const void* src, int bytes);
|
||||
__EXPORT int val_write(volatile void* dest, const void* src, int bytes);
|
||||
__EXPORT int write_otp(uint8_t id_type, uint32_t vid, uint32_t pid, char* signature);
|
||||
__EXPORT int lock_otp(void);
|
||||
__EXPORT void F_unlock(void);
|
||||
__EXPORT void F_lock(void);
|
||||
__EXPORT int val_read(void *dest, volatile const void *src, int bytes);
|
||||
__EXPORT int val_write(volatile void *dest, const void *src, int bytes);
|
||||
__EXPORT int write_otp(uint8_t id_type, uint32_t vid, uint32_t pid, char *signature);
|
||||
__EXPORT int lock_otp(void);
|
||||
|
||||
|
||||
__EXPORT uint8_t F_write_byte(uint32_t Address, uint8_t Data);
|
||||
__EXPORT uint8_t F_write_word(uint32_t Address, uint32_t Data);
|
||||
__EXPORT int F_write_byte(uint32_t Address, uint8_t Data);
|
||||
__EXPORT int F_write_word(uint32_t Address, uint32_t Data);
|
||||
|
||||
__END_DECLS
|
||||
|
||||
|
|
Loading…
Reference in New Issue