11 changed files with 632 additions and 57 deletions
@ -0,0 +1,60 @@
@@ -0,0 +1,60 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* 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 |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file board_serial.h |
||||
* Read off the board serial |
||||
* |
||||
* @author Lorenz Meier <lm@inf.ethz.ch> |
||||
* @author David "Buzz" Bussenschutt <davidbuzz@gmail.com> |
||||
* |
||||
*/ |
||||
|
||||
#include "otp.h" |
||||
#include "board_config.h" |
||||
#include "board_serial.h" |
||||
|
||||
int get_board_serial(char *serialid) |
||||
{ |
||||
const volatile unsigned *udid_ptr = (const unsigned *)UDID_START; |
||||
union udid id; |
||||
val_read((unsigned *)&id, udid_ptr, sizeof(id)); |
||||
|
||||
|
||||
/* Copy the serial from the chips non-write memory and swap endianess */ |
||||
serialid[0] = id.data[3]; serialid[1] = id.data[2]; serialid[2] = id.data[1]; serialid[3] = id.data[0]; |
||||
serialid[4] = id.data[7]; serialid[5] = id.data[6]; serialid[6] = id.data[5]; serialid[7] = id.data[4]; |
||||
serialid[8] = id.data[11]; serialid[9] = id.data[10]; serialid[10] = id.data[9]; serialid[11] = id.data[8]; |
||||
|
||||
return 0; |
||||
} |
@ -0,0 +1,49 @@
@@ -0,0 +1,49 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* 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 |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file board_serial.h |
||||
* Read off the board serial |
||||
* |
||||
* @author Lorenz Meier <lm@inf.ethz.ch> |
||||
* @author David "Buzz" Bussenschutt <davidbuzz@gmail.com> |
||||
* |
||||
*/ |
||||
|
||||
#pragma once |
||||
|
||||
__BEGIN_DECLS |
||||
|
||||
__EXPORT int get_board_serial(char *serialid); |
||||
|
||||
__END_DECLS |
@ -0,0 +1,224 @@
@@ -0,0 +1,224 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2012-2013 PX4 Development Team. All rights reserved. |
||||
* Authors: |
||||
* Lorenz Meier <lm@inf.ethz.ch> |
||||
* David "Buzz" Bussenschutt <davidbuzz@gmail.com> |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file otp.c |
||||
* otp estimation |
||||
* |
||||
* @author Lorenz Meier <lm@inf.ethz.ch> |
||||
* @author David "Buzz" Bussenschutt <davidbuzz@gmail.com> |
||||
* |
||||
*/ |
||||
|
||||
#include <nuttx/config.h> |
||||
#include <board_config.h> |
||||
#include <stdio.h> |
||||
#include <math.h> |
||||
#include <unistd.h> |
||||
#include <string.h> // memset |
||||
#include "conversions.h" |
||||
#include "otp.h" |
||||
#include "err.h" // warnx |
||||
#include <assert.h> |
||||
|
||||
|
||||
int val_read(void *dest, volatile const void *src, int bytes) |
||||
{ |
||||
|
||||
int i; |
||||
|
||||
for (i = 0; i < bytes / 4; i++) { |
||||
*(((volatile unsigned *)dest) + i) = *(((volatile unsigned *)src) + i); |
||||
} |
||||
|
||||
return i * 4; |
||||
} |
||||
|
||||
|
||||
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); |
||||
|
||||
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
|
||||
// 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++) { |
||||
if (F_write_byte(ADDR_OTP_LOCK_START + i, OTP_LOCK_LOCKED)) |
||||
errors++; |
||||
} |
||||
|
||||
return errors; |
||||
} |
||||
|
||||
|
||||
|
||||
// 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
|
||||
void F_unlock(void) |
||||
{ |
||||
if ((FLASH->control & F_CR_LOCK) != 0) { |
||||
FLASH->key = F_KEY1; |
||||
FLASH->key = F_KEY2; |
||||
} |
||||
} |
||||
|
||||
// lock the FLASH Registers
|
||||
void F_lock(void) |
||||
{ |
||||
FLASH->control |= F_CR_LOCK; |
||||
} |
||||
|
||||
// flash write word.
|
||||
int F_write_word(uint32_t Address, uint32_t Data) |
||||
{ |
||||
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
|
||||
int F_write_byte(uint32_t Address, uint8_t Data) |
||||
{ |
||||
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); |
||||
} |
||||
|
||||
|
||||
|
@ -0,0 +1,151 @@
@@ -0,0 +1,151 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* 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 |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file otp.h |
||||
* One TIme Programmable ( OTP ) Flash routine/s. |
||||
* |
||||
* @author Lorenz Meier <lm@inf.ethz.ch> |
||||
* @author David "Buzz" Bussenschutt <davidbuzz@gmail.com> |
||||
* |
||||
*/ |
||||
|
||||
#ifndef OTP_H_ |
||||
#define OTP_H_ |
||||
|
||||
__BEGIN_DECLS |
||||
|
||||
#define ADDR_OTP_START 0x1FFF7800 |
||||
#define ADDR_OTP_LOCK_START 0x1FFF7A00 |
||||
|
||||
#define OTP_LOCK_LOCKED 0x00 |
||||
#define OTP_LOCK_UNLOCKED 0xFF |
||||
|
||||
|
||||
|
||||
#include <unistd.h> |
||||
#include <stdio.h> |
||||
|
||||
// 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
|
||||
} flash_registers; |
||||
|
||||
#define PERIPH_BASE ((uint32_t)0x40000000) //Peripheral base address
|
||||
#define AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000) |
||||
#define F_R_BASE (AHB1PERIPH_BASE + 0x3C00) |
||||
#define FLASH ((flash_registers *) F_R_BASE) |
||||
|
||||
#define F_BSY ((uint32_t)0x00010000) //FLASH Busy flag bit
|
||||
#define F_OPERR ((uint32_t)0x00000002) //FLASH operation Error flag bit
|
||||
#define F_WRPERR ((uint32_t)0x00000010) //FLASH Write protected error flag bit
|
||||
#define CR_PSIZE_MASK ((uint32_t)0xFFFFFCFF) |
||||
#define F_PSIZE_WORD ((uint32_t)0x00000200) |
||||
#define F_PSIZE_BYTE ((uint32_t)0x00000000) |
||||
#define F_CR_PG ((uint32_t)0x00000001) // a bit in the F_CR register
|
||||
#define F_CR_LOCK ((uint32_t)0x80000000) // also another bit.
|
||||
|
||||
#define F_KEY1 ((uint32_t)0x45670123) |
||||
#define F_KEY2 ((uint32_t)0xCDEF89AB) |
||||
#define IS_F_ADDRESS(ADDRESS) ((((ADDRESS) >= 0x08000000) && ((ADDRESS) < 0x080FFFFF)) || (((ADDRESS) >= 0x1FFF7800) && ((ADDRESS) < 0x1FFF7A0F))) |
||||
|
||||
|
||||
|
||||
#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. |
||||
* The OTP data and lock blocks cannot be erased. The lock block contains 16 bytes LOCKBi (0 ≤ i ≤ 15) |
||||
* to lock the corresponding OTP data block (blocks 0 to 15). Each OTP data block can be programmed |
||||
* until the value 0x00 is programmed in the corresponding OTP lock byte. The lock bytes must only |
||||
* 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]; |
||||
}; |
||||
#pragma pack(pop) |
||||
|
||||
#define ADDR_F_SIZE 0x1FFF7A22 |
||||
|
||||
#pragma pack(push, 1) |
||||
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 int F_write_byte(uint32_t Address, uint8_t Data); |
||||
__EXPORT int F_write_word(uint32_t Address, uint32_t Data); |
||||
|
||||
__END_DECLS |
||||
|
||||
#endif |
Loading…
Reference in new issue