From 0ef85c133b387f5d5aab26e00985922c9f05c7e0 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 7 Jan 2014 21:41:07 +0100 Subject: OTP return value cleanup --- src/modules/systemlib/otp.c | 223 +++++++++++++++++++++++++------------------- src/modules/systemlib/otp.h | 107 ++++++++++----------- 2 files changed, 179 insertions(+), 151 deletions(-) (limited to 'src/modules') diff --git a/src/modules/systemlib/otp.c b/src/modules/systemlib/otp.c index 7968637de..695574fdc 100644 --- a/src/modules/systemlib/otp.c +++ b/src/modules/systemlib/otp.c @@ -1,9 +1,9 @@ /**************************************************************************** * * Copyright (C) 2012-2013 PX4 Development Team. All rights reserved. - * Authors: + * Authors: * Lorenz Meier - * David "Buzz" Bussenschutt + * David "Buzz" Bussenschutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -43,6 +43,8 @@ * */ +#include +#include #include #include #include @@ -53,139 +55,170 @@ #include -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); - - // 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'); - //id_type - F_write_byte( ADDR_OTP_START+4, id_type); - // vid and pid are 4 bytes each - F_write_word( ADDR_OTP_START+5, vid); - F_write_word( ADDR_OTP_START+9, pid); - // 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]); - } - - + + warnx("write_otp: PX4 / %02X / %02X / %02X / ... etc \n", id_type, vid, pid); + + int errors = 0; + + // descriptor + 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 + if (F_write_byte(ADDR_OTP_START + 4, id_type)) + errors++; + // vid and pid are 4 bytes each + 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++) { + if (F_write_byte(ADDR_OTP_START + 32 + i, signature[i])) + errors++; + } + + return errors; } int lock_otp(void) { //determine the required locking size - can only write full lock bytes */ // int size = sizeof(struct otp) / 32; -// +// // struct otp_lock otp_lock_mem; // // memset(&otp_lock_mem, OTP_LOCK_UNLOCKED, sizeof(otp_lock_mem)); // for (int i = 0; i < sizeof(otp_lock_mem) / sizeof(otp_lock_mem.lock_bytes[0]); i++) // otp_lock_mem.lock_bytes[i] = OTP_LOCK_LOCKED; - //XXX add the actual call here to write the OTP_LOCK bytes only at final stage + //XXX add the actual call here to write the OTP_LOCK bytes only at final stage // val_copy(lock_ptr, &otp_lock_mem, sizeof(otp_lock_mem)); - - int locksize = 5; - // 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); - } + 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++) { + 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; } } } } - return fs; -} +// COMPLETE, BUSY, or other flash error? +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; +} -// enable FLASH Registers +// enable FLASH Registers void F_unlock(void) { - if((FLASH->control & F_CR_LOCK) != 0) - { - FLASH->key = F_KEY1; - FLASH->key = F_KEY2; - } + if ((FLASH->control & F_CR_LOCK) != 0) { + FLASH->key = F_KEY1; + FLASH->key = F_KEY2; + } } -// lock the FLASH Registers +// lock the FLASH Registers void F_lock(void) { - FLASH->control |= F_CR_LOCK; + FLASH->control |= F_CR_LOCK; } -// flash write word. -uint8_t F_write_word(uint32_t Address, uint32_t Data) +// flash write word. +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; - - //warnx("F_write_byte: %08X %02d", Address , Data ) ; - - //Check the parameters - assert(IS_F_ADDRESS(Address)); - - //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) - { - //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; - - //Wait for FLASH operation to complete by polling on BUSY flag. - 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; + volatile int status = F_COMPLETE; + + //warnx("F_write_byte: %08X %02d", Address , Data ) ; + + //Check the parameters + assert(IS_F_ADDRESS(Address)); + + //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) { + //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; + + //Wait for FLASH operation to complete by polling on BUSY flag. + 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 == F_COMPLETE); } - \ No newline at end of file diff --git a/src/modules/systemlib/otp.h b/src/modules/systemlib/otp.h index e80ca9afb..f10e129d8 100644 --- a/src/modules/systemlib/otp.h +++ b/src/modules/systemlib/otp.h @@ -1,9 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2012-2013 PX4 Development Team. All rights reserved. - * Authors: - * Lorenz Meier - * David "Buzz" Bussenschutt + * 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 @@ -36,7 +33,7 @@ /** * @file otp.h - * One TIme Programmable ( OTP ) Flash routine/s. + * One TIme Programmable ( OTP ) Flash routine/s. * * @author Lorenz Meier * @author David "Buzz" Bussenschutt @@ -46,8 +43,8 @@ #ifndef OTP_H_ #define OTP_H_ - __BEGIN_DECLS - +__BEGIN_DECLS + #define ADDR_OTP_START 0x1FFF7800 #define ADDR_OTP_LOCK_START 0x1FFF7A00 @@ -58,22 +55,21 @@ #include #include - -// possible flash statuses + +// possible flash statuses #define F_BUSY 1 #define F_ERROR_WRP 2 #define F_ERROR_PROGRAM 3 #define F_ERROR_OPERATION 4 #define F_COMPLETE 5 -typedef struct -{ - volatile uint32_t accesscontrol; // 0x00 - volatile uint32_t key; // 0x04 - volatile uint32_t optionkey; // 0x08 - volatile uint32_t status; // 0x0C - volatile uint32_t control; // 0x10 - volatile uint32_t optioncontrol; //0x14 +typedef struct { + volatile uint32_t accesscontrol; // 0x00 + volatile uint32_t key; // 0x04 + volatile uint32_t optionkey; // 0x08 + volatile uint32_t status; // 0x0C + volatile uint32_t control; // 0x10 + volatile uint32_t optioncontrol; //0x14 } flash_registers; #define PERIPH_BASE ((uint32_t)0x40000000) //Peripheral base address @@ -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,51 +102,50 @@ typedef struct * contain 0x00 and 0xFF values, otherwise the OTP bytes might not be taken into account correctly. */ - 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 - uint32_t vid; ///4 bytes - uint32_t pid; ///4 bytes - char unused[19]; ///19 bytes - // Cert-of-Auth is next 4 blocks ie 1-4 ( where zero is first block ) - char signature[128]; - // insert extras here - uint32_t lock_bytes[4]; - }; - - struct otp_lock { - uint8_t lock_bytes[16]; - }; +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 + uint32_t vid; ///4 bytes + uint32_t pid; ///4 bytes + char unused[19]; ///19 bytes + // Cert-of-Auth is next 4 blocks ie 1-4 ( where zero is first block ) + char signature[128]; + // insert extras here + uint32_t lock_bytes[4]; +}; + +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 { - uint32_t serial[3]; - char data[12]; - }; +union udid { + uint32_t serial[3]; + char data[12]; +}; #pragma pack(pop) - - /** - * s - */ - //__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 uint8_t F_write_byte(uint32_t Address, uint8_t Data); - __EXPORT uint8_t F_write_word(uint32_t Address, uint32_t Data); - + +/** + * s + */ +//__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 int F_write_byte(uint32_t Address, uint8_t Data); +__EXPORT int F_write_word(uint32_t Address, uint32_t Data); + __END_DECLS #endif -- cgit v1.2.3