Browse Source

Merge branch 'checkcrc_nostart' into autostart_cleanup

sbg
Anton Babushkin 11 years ago
parent
commit
891cb3f8c2
  1. 2
      nuttx-configs/px4fmu-v2/nsh/defconfig
  2. 1
      src/drivers/boards/px4fmu-v1/board_config.h
  3. 2
      src/drivers/boards/px4fmu-v2/board_config.h
  4. 29
      src/drivers/px4fmu/fmu.cpp
  5. 116
      src/drivers/px4io/px4io.cpp
  6. 60
      src/modules/systemlib/board_serial.c
  7. 49
      src/modules/systemlib/board_serial.h
  8. 5
      src/modules/systemlib/module.mk
  9. 224
      src/modules/systemlib/otp.c
  10. 151
      src/modules/systemlib/otp.h
  11. 50
      src/systemcmds/tests/test_file.c

2
nuttx-configs/px4fmu-v2/nsh/defconfig

@ -302,7 +302,7 @@ CONFIG_USART2_RXDMA=y @@ -302,7 +302,7 @@ CONFIG_USART2_RXDMA=y
CONFIG_USART3_RXDMA=y
# CONFIG_UART4_RS485 is not set
CONFIG_UART4_RXDMA=y
# CONFIG_UART5_RXDMA is not set
CONFIG_UART5_RXDMA=y
# CONFIG_USART6_RS485 is not set
CONFIG_USART6_RXDMA=y
# CONFIG_UART7_RS485 is not set

1
src/drivers/boards/px4fmu-v1/board_config.h

@ -60,6 +60,7 @@ __BEGIN_DECLS @@ -60,6 +60,7 @@ __BEGIN_DECLS
/* PX4IO connection configuration */
#define PX4IO_SERIAL_DEVICE "/dev/ttyS2"
#define UDID_START 0x1FFF7A10
//#ifdef CONFIG_STM32_SPI2
//# error "SPI2 is not supported on this board"

2
src/drivers/boards/px4fmu-v2/board_config.h

@ -53,6 +53,8 @@ __BEGIN_DECLS @@ -53,6 +53,8 @@ __BEGIN_DECLS
#include <stm32.h>
#include <arch/board/board.h>
#define UDID_START 0x1FFF7A10
/****************************************************************************************************
* Definitions
****************************************************************************************************/

29
src/drivers/px4fmu/fmu.cpp

@ -65,6 +65,7 @@ @@ -65,6 +65,7 @@
#include <systemlib/err.h>
#include <systemlib/mixer/mixer.h>
#include <systemlib/pwm_limit/pwm_limit.h>
#include <systemlib/board_serial.h>
#include <drivers/drv_mixer.h>
#include <drivers/drv_rc_input.h>
@ -224,10 +225,10 @@ PX4FMU::PX4FMU() : @@ -224,10 +225,10 @@ PX4FMU::PX4FMU() :
_armed(false),
_pwm_on(false),
_mixers(nullptr),
_failsafe_pwm( {0}),
_disarmed_pwm( {0}),
_num_failsafe_set(0),
_num_disarmed_set(0)
_failsafe_pwm({0}),
_disarmed_pwm({0}),
_num_failsafe_set(0),
_num_disarmed_set(0)
{
for (unsigned i = 0; i < _max_actuators; i++) {
_min_pwm[i] = PWM_DEFAULT_MIN;
@ -575,7 +576,7 @@ PX4FMU::task_main() @@ -575,7 +576,7 @@ PX4FMU::task_main()
if (i >= outputs.noutputs ||
!isfinite(outputs.output[i]) ||
outputs.output[i] < -1.0f ||
outputs.output[i] > 1.0f) {
outputs.output[i] > 1.0f) {
/*
* Value is NaN, INF or out of band - set to the minimum value.
* This will be clearly visible on the servo status and will limit the risk of accidentally
@ -933,7 +934,7 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg) @@ -933,7 +934,7 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
break;
}
/* FALLTHROUGH */
/* FALLTHROUGH */
case PWM_SERVO_SET(3):
case PWM_SERVO_SET(2):
if (_mode < MODE_4PWM) {
@ -941,7 +942,7 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg) @@ -941,7 +942,7 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
break;
}
/* FALLTHROUGH */
/* FALLTHROUGH */
case PWM_SERVO_SET(1):
case PWM_SERVO_SET(0):
if (arg <= 2100) {
@ -960,7 +961,7 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg) @@ -960,7 +961,7 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
break;
}
/* FALLTHROUGH */
/* FALLTHROUGH */
case PWM_SERVO_GET(3):
case PWM_SERVO_GET(2):
if (_mode < MODE_4PWM) {
@ -968,7 +969,7 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg) @@ -968,7 +969,7 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
break;
}
/* FALLTHROUGH */
/* FALLTHROUGH */
case PWM_SERVO_GET(1):
case PWM_SERVO_GET(0):
*(servo_position_t *)arg = up_pwm_servo_get(cmd - PWM_SERVO_GET(0));
@ -1591,6 +1592,15 @@ fmu_main(int argc, char *argv[]) @@ -1591,6 +1592,15 @@ fmu_main(int argc, char *argv[])
errx(0, "FMU driver stopped");
}
if (!strcmp(verb, "id")) {
char id[12];
(void)get_board_serial(id);
errx(0, "Board serial:\n %02X%02X%02X%02X %02X%02X%02X%02X %02X%02X%02X%02X",
(unsigned)id[0], (unsigned)id[1], (unsigned)id[2], (unsigned)id[3], (unsigned)id[4], (unsigned)id[5],
(unsigned)id[6], (unsigned)id[7], (unsigned)id[8], (unsigned)id[9], (unsigned)id[10], (unsigned)id[11]);
}
if (fmu_start() != OK)
errx(1, "failed to start the FMU driver");
@ -1647,6 +1657,7 @@ fmu_main(int argc, char *argv[]) @@ -1647,6 +1657,7 @@ fmu_main(int argc, char *argv[])
sensor_reset(0);
warnx("resettet default time");
}
exit(0);
}

116
src/drivers/px4io/px4io.cpp

@ -1,6 +1,6 @@ @@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
* 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
@ -35,7 +35,7 @@ @@ -35,7 +35,7 @@
* @file px4io.cpp
* Driver for the PX4IO board.
*
* PX4IO is connected via I2C.
* PX4IO is connected via I2C or DMA enabled high-speed UART.
*/
#include <nuttx/config.h>
@ -1690,6 +1690,9 @@ PX4IO::mixer_send(const char *buf, unsigned buflen, unsigned retries) @@ -1690,6 +1690,9 @@ PX4IO::mixer_send(const char *buf, unsigned buflen, unsigned retries)
int ret = io_reg_set(PX4IO_PAGE_MIXERLOAD, 0, (uint16_t *)frame, (sizeof(px4io_mixdata) + 2) / 2);
if (ret)
return ret;
retries--;
log("mixer sent");
@ -2419,6 +2422,69 @@ detect(int argc, char *argv[]) @@ -2419,6 +2422,69 @@ detect(int argc, char *argv[])
}
}
void
checkcrc(int argc, char *argv[])
{
bool keep_running = false;
if (g_dev == nullptr) {
/* allocate the interface */
device::Device *interface = get_interface();
/* create the driver - it will set g_dev */
(void)new PX4IO(interface);
if (g_dev == nullptr)
errx(1, "driver alloc failed");
} else {
/* its already running, don't kill the driver */
keep_running = true;
}
/*
check IO CRC against CRC of a file
*/
if (argc < 2) {
printf("usage: px4io checkcrc filename\n");
exit(1);
}
int fd = open(argv[1], O_RDONLY);
if (fd == -1) {
printf("open of %s failed - %d\n", argv[1], errno);
exit(1);
}
const uint32_t app_size_max = 0xf000;
uint32_t fw_crc = 0;
uint32_t nbytes = 0;
while (true) {
uint8_t buf[16];
int n = read(fd, buf, sizeof(buf));
if (n <= 0) break;
fw_crc = crc32part(buf, n, fw_crc);
nbytes += n;
}
close(fd);
while (nbytes < app_size_max) {
uint8_t b = 0xff;
fw_crc = crc32part(&b, 1, fw_crc);
nbytes++;
}
int ret = g_dev->ioctl(nullptr, PX4IO_CHECK_CRC, fw_crc);
if (!keep_running) {
delete g_dev;
g_dev = nullptr;
}
if (ret != OK) {
printf("check CRC failed - %d\n", ret);
exit(1);
}
printf("CRCs match\n");
exit(0);
}
void
bind(int argc, char *argv[])
{
@ -2613,6 +2679,9 @@ px4io_main(int argc, char *argv[]) @@ -2613,6 +2679,9 @@ px4io_main(int argc, char *argv[])
if (!strcmp(argv[1], "detect"))
detect(argc - 1, argv + 1);
if (!strcmp(argv[1], "checkcrc"))
checkcrc(argc - 1, argv + 1);
if (!strcmp(argv[1], "update")) {
if (g_dev != nullptr) {
@ -2798,49 +2867,6 @@ px4io_main(int argc, char *argv[]) @@ -2798,49 +2867,6 @@ px4io_main(int argc, char *argv[])
exit(0);
}
if (!strcmp(argv[1], "checkcrc")) {
/*
check IO CRC against CRC of a file
*/
if (argc <= 2) {
printf("usage: px4io checkcrc filename\n");
exit(1);
}
if (g_dev == nullptr) {
printf("px4io is not started\n");
exit(1);
}
int fd = open(argv[2], O_RDONLY);
if (fd == -1) {
printf("open of %s failed - %d\n", argv[2], errno);
exit(1);
}
const uint32_t app_size_max = 0xf000;
uint32_t fw_crc = 0;
uint32_t nbytes = 0;
while (true) {
uint8_t buf[16];
int n = read(fd, buf, sizeof(buf));
if (n <= 0) break;
fw_crc = crc32part(buf, n, fw_crc);
nbytes += n;
}
close(fd);
while (nbytes < app_size_max) {
uint8_t b = 0xff;
fw_crc = crc32part(&b, 1, fw_crc);
nbytes++;
}
int ret = g_dev->ioctl(nullptr, PX4IO_CHECK_CRC, fw_crc);
if (ret != OK) {
printf("check CRC failed - %d\n", ret);
exit(1);
}
printf("CRCs match\n");
exit(0);
}
if (!strcmp(argv[1], "rx_dsm") ||
!strcmp(argv[1], "rx_dsm_10bit") ||
!strcmp(argv[1], "rx_dsm_11bit") ||

60
src/modules/systemlib/board_serial.c

@ -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;
}

49
src/modules/systemlib/board_serial.h

@ -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

5
src/modules/systemlib/module.mk

@ -49,4 +49,7 @@ SRCS = err.c \ @@ -49,4 +49,7 @@ SRCS = err.c \
airspeed.c \
system_params.c \
mavlink_log.c \
rc_check.c
rc_check.c \
otp.c \
board_serial.c

224
src/modules/systemlib/otp.c

@ -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);
}

151
src/modules/systemlib/otp.h

@ -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

50
src/systemcmds/tests/test_file.c

@ -38,6 +38,7 @@ @@ -38,6 +38,7 @@
*/
#include <sys/stat.h>
#include <poll.h>
#include <dirent.h>
#include <stdio.h>
#include <stddef.h>
@ -51,6 +52,38 @@ @@ -51,6 +52,38 @@
#include "tests.h"
int check_user_abort();
int check_user_abort() {
/* check if user wants to abort */
char c;
struct pollfd fds;
int ret;
fds.fd = 0; /* stdin */
fds.events = POLLIN;
ret = poll(&fds, 1, 0);
if (ret > 0) {
read(0, &c, 1);
switch (c) {
case 0x03: // ctrl-c
case 0x1b: // esc
case 'c':
case 'q':
{
warnx("Test aborted.");
return OK;
/* not reached */
}
}
}
return 1;
}
int
test_file(int argc, char *argv[])
{
@ -108,6 +141,9 @@ test_file(int argc, char *argv[]) @@ -108,6 +141,9 @@ test_file(int argc, char *argv[])
fsync(fd);
//perf_end(wperf);
if (!check_user_abort())
return OK;
}
end = hrt_absolute_time();
@ -142,6 +178,9 @@ test_file(int argc, char *argv[]) @@ -142,6 +178,9 @@ test_file(int argc, char *argv[])
errx(1, "ABORTING FURTHER COMPARISON DUE TO ERROR");
}
if (!check_user_abort())
return OK;
}
/*
@ -152,7 +191,7 @@ test_file(int argc, char *argv[]) @@ -152,7 +191,7 @@ test_file(int argc, char *argv[])
int ret = unlink("/fs/microsd/testfile");
fd = open("/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT);
warnx("testing aligned writes - please wait..");
warnx("testing aligned writes - please wait.. (CTRL^C to abort)");
start = hrt_absolute_time();
for (unsigned i = 0; i < iterations; i++) {
@ -162,6 +201,9 @@ test_file(int argc, char *argv[]) @@ -162,6 +201,9 @@ test_file(int argc, char *argv[])
err(1, "WRITE ERROR!");
}
if (!check_user_abort())
return OK;
}
fsync(fd);
@ -190,6 +232,9 @@ test_file(int argc, char *argv[]) @@ -190,6 +232,9 @@ test_file(int argc, char *argv[])
align_read_ok = false;
break;
}
if (!check_user_abort())
return OK;
}
if (!align_read_ok) {
@ -228,6 +273,9 @@ test_file(int argc, char *argv[]) @@ -228,6 +273,9 @@ test_file(int argc, char *argv[])
if (unalign_read_err_count > 10)
break;
}
if (!check_user_abort())
return OK;
}
if (!unalign_read_ok) {

Loading…
Cancel
Save