PX4 Firmware
PX4 Autopilot Software http://px4.io
|
One TIme Programmable ( OTP ) Flash routine/s. More...
#include <unistd.h>
#include <stdint.h>
#include <stdio.h>
Go to the source code of this file.
Classes | |
struct | flash_registers |
struct | otp |
struct | otp_lock |
union | udid |
Macros | |
#define | ADDR_OTP_START 0x1FFF7800 |
#define | ADDR_OTP_LOCK_START 0x1FFF7A00 |
#define | OTP_LOCK_LOCKED 0x00 |
#define | OTP_LOCK_UNLOCKED 0xFF |
#define | F_BUSY 1 |
#define | F_ERROR_WRP 2 |
#define | F_ERROR_PROGRAM 3 |
#define | F_ERROR_OPERATION 4 |
#define | F_COMPLETE 5 |
#define | PERIPH_BASE ((unsigned long)0x40000000) |
#define | AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000) |
#define | F_R_BASE (AHB1PERIPH_BASE + 0x3C00) |
#define | FLASH ((flash_registers *) F_R_BASE) |
#define | F_BSY ((unsigned long)0x00010000) |
#define | F_OPERR ((unsigned long)0x00000002) |
#define | F_WRPERR ((unsigned long)0x00000010) |
#define | CR_PSIZE_MASK ((unsigned long)0xFFFFFCFF) |
#define | F_PSIZE_WORD ((unsigned long)0x00000200) |
#define | F_PSIZE_BYTE ((unsigned long)0x00000000) |
#define | F_CR_PG ((unsigned long)0x00000001) |
#define | F_CR_LOCK ((unsigned long)0x80000000) |
#define | F_KEY1 ((unsigned long)0x45670123) |
#define | F_KEY2 ((unsigned long)0xCDEF89AB) |
#define | IS_F_ADDRESS(ADDRESS) ((((ADDRESS) >= 0x08000000) && ((ADDRESS) < 0x080FFFFF)) || (((ADDRESS) >= 0x1FFF7800) && ((ADDRESS) < 0x1FFF7A0F))) |
#define | ADDR_F_SIZE 0x1FFF7A22 |
Functions | |
__BEGIN_DECLS __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 (unsigned long Address, uint8_t Data) |
__EXPORT int | F_write_word (unsigned long Address, uint32_t Data) |
One TIme Programmable ( OTP ) Flash routine/s.
Definition in file otp.h.
#define ADDR_OTP_LOCK_START 0x1FFF7A00 |
Definition at line 47 of file otp.h.
Referenced by lock_otp().
#define ADDR_OTP_START 0x1FFF7800 |
Definition at line 46 of file otp.h.
Referenced by write_otp().
#define AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000) |
#define CR_PSIZE_MASK ((unsigned long)0xFFFFFCFF) |
Definition at line 82 of file otp.h.
Referenced by F_write_byte().
#define F_BSY ((unsigned long)0x00010000) |
Definition at line 79 of file otp.h.
Referenced by F_GetStatus().
#define F_BUSY 1 |
Definition at line 59 of file otp.h.
Referenced by F_GetStatus(), and F_write_byte().
#define F_COMPLETE 5 |
Definition at line 63 of file otp.h.
Referenced by F_GetStatus(), and F_write_byte().
#define F_CR_LOCK ((unsigned long)0x80000000) |
Definition at line 86 of file otp.h.
Referenced by F_lock(), and F_unlock().
#define F_CR_PG ((unsigned long)0x00000001) |
Definition at line 85 of file otp.h.
Referenced by F_write_byte().
#define F_ERROR_OPERATION 4 |
Definition at line 62 of file otp.h.
Referenced by F_GetStatus().
#define F_ERROR_PROGRAM 3 |
Definition at line 61 of file otp.h.
Referenced by F_GetStatus().
#define F_ERROR_WRP 2 |
Definition at line 60 of file otp.h.
Referenced by F_GetStatus().
#define F_KEY1 ((unsigned long)0x45670123) |
Definition at line 88 of file otp.h.
Referenced by F_unlock().
#define F_KEY2 ((unsigned long)0xCDEF89AB) |
Definition at line 89 of file otp.h.
Referenced by F_unlock().
#define F_OPERR ((unsigned long)0x00000002) |
Definition at line 80 of file otp.h.
Referenced by F_GetStatus().
#define F_PSIZE_BYTE ((unsigned long)0x00000000) |
Definition at line 84 of file otp.h.
Referenced by F_write_byte().
#define F_R_BASE (AHB1PERIPH_BASE + 0x3C00) |
#define F_WRPERR ((unsigned long)0x00000010) |
Definition at line 81 of file otp.h.
Referenced by F_GetStatus().
#define FLASH ((flash_registers *) F_R_BASE) |
Definition at line 77 of file otp.h.
Referenced by F_GetStatus(), F_lock(), F_unlock(), and F_write_byte().
#define IS_F_ADDRESS | ( | ADDRESS | ) | ((((ADDRESS) >= 0x08000000) && ((ADDRESS) < 0x080FFFFF)) || (((ADDRESS) >= 0x1FFF7800) && ((ADDRESS) < 0x1FFF7A0F))) |
Definition at line 90 of file otp.h.
Referenced by F_write_byte().
#define OTP_LOCK_LOCKED 0x00 |
Definition at line 49 of file otp.h.
Referenced by lock_otp().
__EXPORT void F_lock | ( | void | ) |
__BEGIN_DECLS __EXPORT void F_unlock | ( | void | ) |
__EXPORT int F_write_byte | ( | unsigned long | Address, |
uint8_t | Data | ||
) |
Definition at line 203 of file otp.c.
References CR_PSIZE_MASK, F_BUSY, F_COMPLETE, F_CR_PG, F_GetStatus(), F_PSIZE_BYTE, FLASH, IS_F_ADDRESS, and status.
Referenced by F_write_word(), lock_otp(), and write_otp().
__EXPORT int F_write_word | ( | unsigned long | Address, |
uint32_t | Data | ||
) |
Definition at line 188 of file otp.c.
References F_write_byte().
Referenced by write_otp().
__EXPORT int lock_otp | ( | void | ) |
Definition at line 121 of file otp.c.
References ADDR_OTP_LOCK_START, F_write_byte(), and OTP_LOCK_LOCKED.
__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 | ||
) |
Definition at line 71 of file otp.c.
References ADDR_OTP_START, F_write_byte(), F_write_word(), and warnx.