aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2014-01-13 09:48:27 +0100
committerAnton Babushkin <anton.babushkin@me.com>2014-01-13 09:48:27 +0100
commitd042b6365766b542870d88d845482315bd8459d0 (patch)
tree7b12bd677cc399db365995c6313e0e01ae405b17 /src
parent9b711d6a722fc254bb0d461b9aec66d20fbf59b1 (diff)
parentf595b204eab82679a52ca5f43408797988cfdf42 (diff)
downloadpx4-firmware-d042b6365766b542870d88d845482315bd8459d0.tar.gz
px4-firmware-d042b6365766b542870d88d845482315bd8459d0.tar.bz2
px4-firmware-d042b6365766b542870d88d845482315bd8459d0.zip
Merge branch 'master' into batt_fixes
Diffstat (limited to 'src')
-rw-r--r--src/drivers/boards/px4fmu-v1/board_config.h1
-rw-r--r--src/drivers/boards/px4fmu-v2/board_config.h2
-rw-r--r--src/drivers/boards/px4fmu-v2/px4fmu2_init.c15
-rw-r--r--src/drivers/gps/gps.cpp194
-rw-r--r--src/drivers/hil/hil.cpp9
-rw-r--r--src/drivers/hott/hott_sensors/hott_sensors.cpp2
-rw-r--r--src/drivers/hott/hott_telemetry/hott_telemetry.cpp2
-rw-r--r--src/drivers/px4fmu/fmu.cpp29
-rw-r--r--src/drivers/px4io/px4io.cpp116
-rw-r--r--src/drivers/rgbled/rgbled.cpp12
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c67
-rw-r--r--src/modules/sensors/module.mk2
-rw-r--r--src/modules/sensors/sensor_params.c186
-rw-r--r--src/modules/systemlib/board_serial.c60
-rw-r--r--src/modules/systemlib/board_serial.h49
-rw-r--r--src/modules/systemlib/module.mk5
-rw-r--r--src/modules/systemlib/otp.c224
-rw-r--r--src/modules/systemlib/otp.h151
-rw-r--r--src/systemcmds/mtd/module.mk6
-rw-r--r--src/systemcmds/mtd/mtd.c216
-rw-r--r--src/systemcmds/nshterm/nshterm.c4
-rw-r--r--src/systemcmds/tests/module.mk3
-rw-r--r--src/systemcmds/tests/test_file.c163
-rw-r--r--src/systemcmds/tests/test_mount.c289
-rw-r--r--src/systemcmds/tests/tests.h1
-rw-r--r--src/systemcmds/tests/tests_main.c1
26 files changed, 1551 insertions, 258 deletions
diff --git a/src/drivers/boards/px4fmu-v1/board_config.h b/src/drivers/boards/px4fmu-v1/board_config.h
index 6f7166284..02c26b5c0 100644
--- a/src/drivers/boards/px4fmu-v1/board_config.h
+++ b/src/drivers/boards/px4fmu-v1/board_config.h
@@ -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"
diff --git a/src/drivers/boards/px4fmu-v2/board_config.h b/src/drivers/boards/px4fmu-v2/board_config.h
index a19ed9d24..4972e6914 100644
--- a/src/drivers/boards/px4fmu-v2/board_config.h
+++ b/src/drivers/boards/px4fmu-v2/board_config.h
@@ -52,6 +52,8 @@ __BEGIN_DECLS
/* these headers are not C++ safe */
#include <stm32.h>
#include <arch/board/board.h>
+
+#define UDID_START 0x1FFF7A10
/****************************************************************************************************
* Definitions
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu2_init.c b/src/drivers/boards/px4fmu-v2/px4fmu2_init.c
index 269ec238e..71414d62c 100644
--- a/src/drivers/boards/px4fmu-v2/px4fmu2_init.c
+++ b/src/drivers/boards/px4fmu-v2/px4fmu2_init.c
@@ -282,7 +282,7 @@ __EXPORT int nsh_archinitialize(void)
SPI_SELECT(spi1, PX4_SPIDEV_MPU, false);
up_udelay(20);
- message("[boot] Successfully initialized SPI port 1\n");
+ message("[boot] Initialized SPI port 1 (SENSORS)\n");
/* Get the SPI port for the FRAM */
@@ -294,20 +294,23 @@ __EXPORT int nsh_archinitialize(void)
return -ENODEV;
}
- /* Default SPI2 to 37.5 MHz (F4 max) and de-assert the known chip selects. */
- SPI_SETFREQUENCY(spi2, 375000000);
+ /* Default SPI2 to 37.5 MHz (40 MHz rounded to nearest valid divider, F4 max)
+ * and de-assert the known chip selects. */
+
+ // XXX start with 10.4 MHz in FRAM usage and go up to 37.5 once validated
+ SPI_SETFREQUENCY(spi2, 12 * 1000 * 1000);
SPI_SETBITS(spi2, 8);
SPI_SETMODE(spi2, SPIDEV_MODE3);
SPI_SELECT(spi2, SPIDEV_FLASH, false);
- message("[boot] Successfully initialized SPI port 2\n");
+ message("[boot] Initialized SPI port 2 (RAMTRON FRAM)\n");
#ifdef CONFIG_MMCSD
/* First, get an instance of the SDIO interface */
sdio = sdio_initialize(CONFIG_NSH_MMCSDSLOTNO);
if (!sdio) {
- message("nsh_archinitialize: Failed to initialize SDIO slot %d\n",
+ message("[boot] Failed to initialize SDIO slot %d\n",
CONFIG_NSH_MMCSDSLOTNO);
return -ENODEV;
}
@@ -315,7 +318,7 @@ __EXPORT int nsh_archinitialize(void)
/* Now bind the SDIO interface to the MMC/SD driver */
int ret = mmcsd_slotinitialize(CONFIG_NSH_MMCSDMINOR, sdio);
if (ret != OK) {
- message("nsh_archinitialize: Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
+ message("[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
return ret;
}
diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp
index fc500a9ec..6b72d560f 100644
--- a/src/drivers/gps/gps.cpp
+++ b/src/drivers/gps/gps.cpp
@@ -85,7 +85,7 @@ static const int ERROR = -1;
class GPS : public device::CDev
{
public:
- GPS(const char *uart_path);
+ GPS(const char *uart_path, bool fake_gps);
virtual ~GPS();
virtual int init();
@@ -112,6 +112,7 @@ private:
struct vehicle_gps_position_s _report; ///< uORB topic for gps position
orb_advert_t _report_pub; ///< uORB pub for gps position
float _rate; ///< position update rate
+ bool _fake_gps; ///< fake gps output
/**
@@ -156,7 +157,7 @@ GPS *g_dev;
}
-GPS::GPS(const char *uart_path) :
+GPS::GPS(const char *uart_path, bool fake_gps) :
CDev("gps", GPS_DEVICE_PATH),
_task_should_exit(false),
_healthy(false),
@@ -164,7 +165,8 @@ GPS::GPS(const char *uart_path) :
_mode(GPS_DRIVER_MODE_UBX),
_Helper(nullptr),
_report_pub(-1),
- _rate(0.0f)
+ _rate(0.0f),
+ _fake_gps(fake_gps)
{
/* store port name */
strncpy(_port, uart_path, sizeof(_port));
@@ -264,98 +266,133 @@ GPS::task_main()
/* loop handling received serial bytes and also configuring in between */
while (!_task_should_exit) {
- if (_Helper != nullptr) {
- delete(_Helper);
- /* set to zero to ensure parser is not used while not instantiated */
- _Helper = nullptr;
- }
+ if (_fake_gps) {
+
+ _report.timestamp_position = hrt_absolute_time();
+ _report.lat = (int32_t)47.378301e7f;
+ _report.lon = (int32_t)8.538777e7f;
+ _report.alt = (int32_t)400e3f;
+ _report.timestamp_variance = hrt_absolute_time();
+ _report.s_variance_m_s = 10.0f;
+ _report.p_variance_m = 10.0f;
+ _report.c_variance_rad = 0.1f;
+ _report.fix_type = 3;
+ _report.eph_m = 10.0f;
+ _report.epv_m = 10.0f;
+ _report.timestamp_velocity = hrt_absolute_time();
+ _report.vel_n_m_s = 0.0f;
+ _report.vel_e_m_s = 0.0f;
+ _report.vel_d_m_s = 0.0f;
+ _report.vel_m_s = sqrtf(_report.vel_n_m_s * _report.vel_n_m_s + _report.vel_e_m_s * _report.vel_e_m_s + _report.vel_d_m_s * _report.vel_d_m_s);
+ _report.cog_rad = 0.0f;
+ _report.vel_ned_valid = true;
+
+ //no time and satellite information simulated
+
+ if (_report_pub > 0) {
+ orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report);
+
+ } else {
+ _report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report);
+ }
- switch (_mode) {
- case GPS_DRIVER_MODE_UBX:
- _Helper = new UBX(_serial_fd, &_report);
- break;
+ usleep(2e5);
- case GPS_DRIVER_MODE_MTK:
- _Helper = new MTK(_serial_fd, &_report);
- break;
+ } else {
- default:
- break;
- }
+ if (_Helper != nullptr) {
+ delete(_Helper);
+ /* set to zero to ensure parser is not used while not instantiated */
+ _Helper = nullptr;
+ }
- unlock();
+ switch (_mode) {
+ case GPS_DRIVER_MODE_UBX:
+ _Helper = new UBX(_serial_fd, &_report);
+ break;
+
+ case GPS_DRIVER_MODE_MTK:
+ _Helper = new MTK(_serial_fd, &_report);
+ break;
+
+ default:
+ break;
+ }
- if (_Helper->configure(_baudrate) == 0) {
unlock();
- // GPS is obviously detected successfully, reset statistics
- _Helper->reset_update_rates();
+ if (_Helper->configure(_baudrate) == 0) {
+ unlock();
- while (_Helper->receive(TIMEOUT_5HZ) > 0 && !_task_should_exit) {
-// lock();
- /* opportunistic publishing - else invalid data would end up on the bus */
- if (_report_pub > 0) {
- orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report);
+ // GPS is obviously detected successfully, reset statistics
+ _Helper->reset_update_rates();
- } else {
- _report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report);
- }
+ while (_Helper->receive(TIMEOUT_5HZ) > 0 && !_task_should_exit) {
+ // lock();
+ /* opportunistic publishing - else invalid data would end up on the bus */
+ if (_report_pub > 0) {
+ orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report);
+
+ } else {
+ _report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report);
+ }
- last_rate_count++;
+ last_rate_count++;
- /* measure update rate every 5 seconds */
- if (hrt_absolute_time() - last_rate_measurement > RATE_MEASUREMENT_PERIOD) {
- _rate = last_rate_count / ((float)((hrt_absolute_time() - last_rate_measurement)) / 1000000.0f);
- last_rate_measurement = hrt_absolute_time();
- last_rate_count = 0;
- _Helper->store_update_rates();
- _Helper->reset_update_rates();
- }
+ /* measure update rate every 5 seconds */
+ if (hrt_absolute_time() - last_rate_measurement > RATE_MEASUREMENT_PERIOD) {
+ _rate = last_rate_count / ((float)((hrt_absolute_time() - last_rate_measurement)) / 1000000.0f);
+ last_rate_measurement = hrt_absolute_time();
+ last_rate_count = 0;
+ _Helper->store_update_rates();
+ _Helper->reset_update_rates();
+ }
- if (!_healthy) {
- char *mode_str = "unknown";
+ if (!_healthy) {
+ char *mode_str = "unknown";
- switch (_mode) {
- case GPS_DRIVER_MODE_UBX:
- mode_str = "UBX";
- break;
+ switch (_mode) {
+ case GPS_DRIVER_MODE_UBX:
+ mode_str = "UBX";
+ break;
- case GPS_DRIVER_MODE_MTK:
- mode_str = "MTK";
- break;
+ case GPS_DRIVER_MODE_MTK:
+ mode_str = "MTK";
+ break;
- default:
- break;
+ default:
+ break;
+ }
+
+ warnx("module found: %s", mode_str);
+ _healthy = true;
}
+ }
- warnx("module found: %s", mode_str);
- _healthy = true;
+ if (_healthy) {
+ warnx("module lost");
+ _healthy = false;
+ _rate = 0.0f;
}
- }
- if (_healthy) {
- warnx("module lost");
- _healthy = false;
- _rate = 0.0f;
+ lock();
}
lock();
- }
-
- lock();
- /* select next mode */
- switch (_mode) {
- case GPS_DRIVER_MODE_UBX:
- _mode = GPS_DRIVER_MODE_MTK;
- break;
+ /* select next mode */
+ switch (_mode) {
+ case GPS_DRIVER_MODE_UBX:
+ _mode = GPS_DRIVER_MODE_MTK;
+ break;
- case GPS_DRIVER_MODE_MTK:
- _mode = GPS_DRIVER_MODE_UBX;
- break;
+ case GPS_DRIVER_MODE_MTK:
+ _mode = GPS_DRIVER_MODE_UBX;
+ break;
- default:
- break;
+ default:
+ break;
+ }
}
}
@@ -417,7 +454,7 @@ namespace gps
GPS *g_dev;
-void start(const char *uart_path);
+void start(const char *uart_path, bool fake_gps);
void stop();
void test();
void reset();
@@ -427,7 +464,7 @@ void info();
* Start the driver.
*/
void
-start(const char *uart_path)
+start(const char *uart_path, bool fake_gps)
{
int fd;
@@ -435,7 +472,7 @@ start(const char *uart_path)
errx(1, "already started");
/* create the driver */
- g_dev = new GPS(uart_path);
+ g_dev = new GPS(uart_path, fake_gps);
if (g_dev == nullptr)
goto fail;
@@ -527,6 +564,7 @@ gps_main(int argc, char *argv[])
/* set to default */
char *device_name = GPS_DEFAULT_UART_PORT;
+ bool fake_gps = false;
/*
* Start/load the driver.
@@ -542,7 +580,13 @@ gps_main(int argc, char *argv[])
}
}
- gps::start(device_name);
+ /* Detect fake gps option */
+ for (int i = 2; i < argc; i++) {
+ if (!strcmp(argv[i], "-f"))
+ fake_gps = true;
+ }
+
+ gps::start(device_name, fake_gps);
}
if (!strcmp(argv[1], "stop"))
@@ -567,5 +611,5 @@ gps_main(int argc, char *argv[])
gps::info();
out:
- errx(1, "unrecognized command, try 'start', 'stop', 'test', 'reset' or 'status' [-d /dev/ttyS0-n]");
+ errx(1, "unrecognized command, try 'start', 'stop', 'test', 'reset' or 'status' [-d /dev/ttyS0-n][-f]");
}
diff --git a/src/drivers/hil/hil.cpp b/src/drivers/hil/hil.cpp
index c1d73dd87..0a047f38f 100644
--- a/src/drivers/hil/hil.cpp
+++ b/src/drivers/hil/hil.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 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
@@ -193,9 +193,10 @@ HIL::~HIL()
} while (_task != -1);
}
- /* clean up the alternate device node */
- if (_primary_pwm_device)
- unregister_driver(PWM_OUTPUT_DEVICE_PATH);
+ // XXX already claimed with CDEV
+ // /* clean up the alternate device node */
+ // if (_primary_pwm_device)
+ // unregister_driver(PWM_OUTPUT_DEVICE_PATH);
g_hil = nullptr;
}
diff --git a/src/drivers/hott/hott_sensors/hott_sensors.cpp b/src/drivers/hott/hott_sensors/hott_sensors.cpp
index e322c6349..a3d3a3933 100644
--- a/src/drivers/hott/hott_sensors/hott_sensors.cpp
+++ b/src/drivers/hott/hott_sensors/hott_sensors.cpp
@@ -211,7 +211,7 @@ hott_sensors_main(int argc, char *argv[])
thread_should_exit = false;
deamon_task = task_spawn_cmd(daemon_name,
SCHED_DEFAULT,
- SCHED_PRIORITY_MAX - 40,
+ SCHED_PRIORITY_DEFAULT,
1024,
hott_sensors_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
diff --git a/src/drivers/hott/hott_telemetry/hott_telemetry.cpp b/src/drivers/hott/hott_telemetry/hott_telemetry.cpp
index 042d9f816..d293f9954 100644
--- a/src/drivers/hott/hott_telemetry/hott_telemetry.cpp
+++ b/src/drivers/hott/hott_telemetry/hott_telemetry.cpp
@@ -237,7 +237,7 @@ hott_telemetry_main(int argc, char *argv[])
thread_should_exit = false;
deamon_task = task_spawn_cmd(daemon_name,
SCHED_DEFAULT,
- SCHED_PRIORITY_MAX - 40,
+ SCHED_PRIORITY_DEFAULT,
2048,
hott_telemetry_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp
index b878d29bc..b28d318d7 100644
--- a/src/drivers/px4fmu/fmu.cpp
+++ b/src/drivers/px4fmu/fmu.cpp
@@ -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() :
_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()
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)
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)
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)
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)
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[])
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[])
sensor_reset(0);
warnx("resettet default time");
}
+
exit(0);
}
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index cbdd5acc4..0ca35d2f2 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -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 @@
* @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)
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");
@@ -2420,6 +2423,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[])
{
int pulses;
@@ -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[])
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") ||
diff --git a/src/drivers/rgbled/rgbled.cpp b/src/drivers/rgbled/rgbled.cpp
index 727c86e02..4f58891ed 100644
--- a/src/drivers/rgbled/rgbled.cpp
+++ b/src/drivers/rgbled/rgbled.cpp
@@ -559,7 +559,7 @@ RGBLED::get(bool &on, bool &powersave, uint8_t &r, uint8_t &g, uint8_t &b)
void
rgbled_usage()
{
- warnx("missing command: try 'start', 'test', 'info', 'off', 'rgb 30 40 50'");
+ warnx("missing command: try 'start', 'test', 'info', 'off', 'stop', 'rgb 30 40 50'");
warnx("options:");
warnx(" -b i2cbus (%d)", PX4_I2C_BUS_LED);
warnx(" -a addr (0x%x)", ADDR);
@@ -643,7 +643,7 @@ rgbled_main(int argc, char *argv[])
if (g_rgbled == nullptr) {
warnx("not started");
rgbled_usage();
- exit(0);
+ exit(1);
}
if (!strcmp(verb, "test")) {
@@ -669,7 +669,7 @@ rgbled_main(int argc, char *argv[])
exit(0);
}
- if (!strcmp(verb, "off")) {
+ if (!strcmp(verb, "off") || !strcmp(verb, "stop")) {
fd = open(RGBLED_DEVICE_PATH, 0);
if (fd == -1) {
@@ -681,6 +681,12 @@ rgbled_main(int argc, char *argv[])
exit(ret);
}
+ if (!strcmp(verb, "stop")) {
+ delete g_rgbled;
+ g_rgbled = nullptr;
+ exit(0);
+ }
+
if (!strcmp(verb, "rgb")) {
if (argc < 5) {
errx(1, "Usage: rgbled rgb <red> <green> <blue>");
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
index 3bb872405..31a9cdefa 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: Lorenz Meier <lm@inf.ethz.ch>
+ * Copyright (c) 2013, 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
@@ -49,21 +48,75 @@
*
*/
+/**
+ * L1 period
+ *
+ * This is the L1 distance and defines the tracking
+ * point ahead of the aircraft its following.
+ * A value of 25 meters works for most aircraft. Shorten
+ * slowly during tuning until response is sharp without oscillation.
+ *
+ * @min 1.0
+ * @max 100.0
+ * @group L1 Control
+ */
PARAM_DEFINE_FLOAT(FW_L1_PERIOD, 25.0f);
-
+/**
+ * L1 damping
+ *
+ * Damping factor for L1 control.
+ *
+ * @min 0.6
+ * @max 0.9
+ * @group L1 Control
+ */
PARAM_DEFINE_FLOAT(FW_L1_DAMPING, 0.75f);
-
+/**
+ * Default Loiter Radius
+ *
+ * This radius is used when no other loiter radius is set.
+ *
+ * @min 10.0
+ * @max 100.0
+ * @group L1 Control
+ */
PARAM_DEFINE_FLOAT(FW_LOITER_R, 50.0f);
-
+/**
+ * Cruise throttle
+ *
+ * This is the throttle setting required to achieve the desired cruise speed. Most airframes have a value of 0.5-0.7.
+ *
+ * @min 0.0
+ * @max 1.0
+ * @group L1 Control
+ */
PARAM_DEFINE_FLOAT(FW_THR_CRUISE, 0.7f);
-
+/**
+ * Negative pitch limit
+ *
+ * The minimum negative pitch the controller will output.
+ *
+ * @unit degrees
+ * @min -60.0
+ * @max 0.0
+ * @group L1 Control
+ */
PARAM_DEFINE_FLOAT(FW_P_LIM_MIN, -45.0f);
-
+/**
+ * Positive pitch limit
+ *
+ * The maximum positive pitch the controller will output.
+ *
+ * @unit degrees
+ * @min 0.0
+ * @max 60.0
+ * @group L1 Control
+ */
PARAM_DEFINE_FLOAT(FW_P_LIM_MAX, 45.0f);
diff --git a/src/modules/sensors/module.mk b/src/modules/sensors/module.mk
index ebbc580e1..aa538fd6b 100644
--- a/src/modules/sensors/module.mk
+++ b/src/modules/sensors/module.mk
@@ -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
diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c
index 241c5b99b..3b3e56c88 100644
--- a/src/modules/sensors/sensor_params.c
+++ b/src/modules/sensors/sensor_params.c
@@ -1,9 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Lorenz Meier <lm@inf.ethz.ch>
- * @author Thomas Gubler <thomasgubler@student.ethz.ch>
- * @author Julian Oes <joes@student.ethz.ch>
+ * 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
@@ -38,6 +35,10 @@
* @file sensor_params.c
*
* Parameters defined by the sensors task.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
*/
#include <nuttx/config.h>
@@ -45,41 +46,98 @@
#include <systemlib/param/param.h>
/**
- * Gyro X offset FIXME
+ * Gyro X offset
*
- * This is an X-axis offset for the gyro.
- * Adjust it according to the calibration data.
+ * This is an X-axis offset for the gyro. Adjust it according to the calibration data.
*
* @min -10.0
* @max 10.0
- * @group Gyro Config
+ * @group Sensor Calibration
*/
PARAM_DEFINE_FLOAT(SENS_GYRO_XOFF, 0.0f);
/**
- * Gyro Y offset FIXME with dot.
+ * Gyro Y offset
*
* @min -10.0
* @max 10.0
- * @group Gyro Config
+ * @group Sensor Calibration
*/
PARAM_DEFINE_FLOAT(SENS_GYRO_YOFF, 0.0f);
/**
- * Gyro Z offset FIXME
+ * Gyro Z offset
*
* @min -5.0
* @max 5.0
- * @group Gyro Config
+ * @group Sensor Calibration
*/
PARAM_DEFINE_FLOAT(SENS_GYRO_ZOFF, 0.0f);
+/**
+ * Gyro X scaling
+ *
+ * X-axis scaling.
+ *
+ * @min -1.5
+ * @max 1.5
+ * @group Sensor Calibration
+ */
PARAM_DEFINE_FLOAT(SENS_GYRO_XSCALE, 1.0f);
+
+/**
+ * Gyro Y scaling
+ *
+ * Y-axis scaling.
+ *
+ * @min -1.5
+ * @max 1.5
+ * @group Sensor Calibration
+ */
PARAM_DEFINE_FLOAT(SENS_GYRO_YSCALE, 1.0f);
+
+/**
+ * Gyro Z scaling
+ *
+ * Z-axis scaling.
+ *
+ * @min -1.5
+ * @max 1.5
+ * @group Sensor Calibration
+ */
PARAM_DEFINE_FLOAT(SENS_GYRO_ZSCALE, 1.0f);
+/**
+ * Magnetometer X offset
+ *
+ * This is an X-axis offset for the magnetometer.
+ *
+ * @min -500.0
+ * @max 500.0
+ * @group Sensor Calibration
+ */
PARAM_DEFINE_FLOAT(SENS_MAG_XOFF, 0.0f);
+
+/**
+ * Magnetometer Y offset
+ *
+ * This is an Y-axis offset for the magnetometer.
+ *
+ * @min -500.0
+ * @max 500.0
+ * @group Sensor Calibration
+ */
PARAM_DEFINE_FLOAT(SENS_MAG_YOFF, 0.0f);
+
+/**
+ * Magnetometer Z offset
+ *
+ * This is an Z-axis offset for the magnetometer.
+ *
+ * @min -500.0
+ * @max 500.0
+ * @group Sensor Calibration
+ */
PARAM_DEFINE_FLOAT(SENS_MAG_ZOFF, 0.0f);
PARAM_DEFINE_FLOAT(SENS_MAG_XSCALE, 1.0f);
@@ -100,16 +158,114 @@ PARAM_DEFINE_INT32(SENS_DPRES_ANA, 0);
PARAM_DEFINE_INT32(SENS_BOARD_ROT, 0);
PARAM_DEFINE_INT32(SENS_EXT_MAG_ROT, 0);
+/**
+ * RC Channel 1 Minimum
+ *
+ * Minimum value for RC channel 1
+ *
+ * @min 800.0
+ * @max 1500.0
+ * @group Radio Calibration
+ */
PARAM_DEFINE_FLOAT(RC1_MIN, 1000.0f);
+
+/**
+ * RC Channel 1 Trim
+ *
+ * Mid point value (same as min for throttle)
+ *
+ * @min 800.0
+ * @max 2200.0
+ * @group Radio Calibration
+ */
PARAM_DEFINE_FLOAT(RC1_TRIM, 1500.0f);
+
+/**
+ * RC Channel 1 Maximum
+ *
+ * Maximum value for RC channel 1
+ *
+ * @min 1500.0
+ * @max 2200.0
+ * @group Radio Calibration
+ */
PARAM_DEFINE_FLOAT(RC1_MAX, 2000.0f);
+
+/**
+ * RC Channel 1 Reverse
+ *
+ * Set to -1 to reverse channel.
+ *
+ * @min -1.0
+ * @max 1.0
+ * @group Radio Calibration
+ */
PARAM_DEFINE_FLOAT(RC1_REV, 1.0f);
+
+/**
+ * RC Channel 1 dead zone
+ *
+ * The +- range of this value around the trim value will be considered as zero.
+ *
+ * @min 0.0
+ * @max 100.0
+ * @group Radio Calibration
+ */
PARAM_DEFINE_FLOAT(RC1_DZ, 10.0f);
-PARAM_DEFINE_FLOAT(RC2_MIN, 1000);
-PARAM_DEFINE_FLOAT(RC2_TRIM, 1500);
-PARAM_DEFINE_FLOAT(RC2_MAX, 2000);
+/**
+ * RC Channel 2 Minimum
+ *
+ * Minimum value for RC channel 2
+ *
+ * @min 800.0
+ * @max 1500.0
+ * @group Radio Calibration
+ */
+PARAM_DEFINE_FLOAT(RC2_MIN, 1000.0f);
+
+/**
+ * RC Channel 2 Trim
+ *
+ * Mid point value (same as min for throttle)
+ *
+ * @min 800.0
+ * @max 2200.0
+ * @group Radio Calibration
+ */
+PARAM_DEFINE_FLOAT(RC2_TRIM, 1500.0f);
+
+/**
+ * RC Channel 2 Maximum
+ *
+ * Maximum value for RC channel 2
+ *
+ * @min 1500.0
+ * @max 2200.0
+ * @group Radio Calibration
+ */
+PARAM_DEFINE_FLOAT(RC2_MAX, 2000.0f);
+
+/**
+ * RC Channel 2 Reverse
+ *
+ * Set to -1 to reverse channel.
+ *
+ * @min -1.0
+ * @max 1.0
+ * @group Radio Calibration
+ */
PARAM_DEFINE_FLOAT(RC2_REV, 1.0f);
+
+/**
+ * RC Channel 2 dead zone
+ *
+ * The +- range of this value around the trim value will be considered as zero.
+ *
+ * @min 0.0
+ * @max 100.0
+ * @group Radio Calibration
+ */
PARAM_DEFINE_FLOAT(RC2_DZ, 10.0f);
PARAM_DEFINE_FLOAT(RC3_MIN, 1000);
diff --git a/src/modules/systemlib/board_serial.c b/src/modules/systemlib/board_serial.c
new file mode 100644
index 000000000..ad8c2bf83
--- /dev/null
+++ b/src/modules/systemlib/board_serial.c
@@ -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;
+} \ No newline at end of file
diff --git a/src/modules/systemlib/board_serial.h b/src/modules/systemlib/board_serial.h
new file mode 100644
index 000000000..b14bb4376
--- /dev/null
+++ b/src/modules/systemlib/board_serial.h
@@ -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
diff --git a/src/modules/systemlib/module.mk b/src/modules/systemlib/module.mk
index 843cda722..8c6c300d6 100644
--- a/src/modules/systemlib/module.mk
+++ b/src/modules/systemlib/module.mk
@@ -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
+
diff --git a/src/modules/systemlib/otp.c b/src/modules/systemlib/otp.c
new file mode 100644
index 000000000..695574fdc
--- /dev/null
+++ b/src/modules/systemlib/otp.c
@@ -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);
+}
+
+
+
diff --git a/src/modules/systemlib/otp.h b/src/modules/systemlib/otp.h
new file mode 100644
index 000000000..f10e129d8
--- /dev/null
+++ b/src/modules/systemlib/otp.h
@@ -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
diff --git a/src/systemcmds/mtd/module.mk b/src/systemcmds/mtd/module.mk
new file mode 100644
index 000000000..686656597
--- /dev/null
+++ b/src/systemcmds/mtd/module.mk
@@ -0,0 +1,6 @@
+#
+# RAMTRON file system driver
+#
+
+MODULE_COMMAND = mtd
+SRCS = mtd.c
diff --git a/src/systemcmds/mtd/mtd.c b/src/systemcmds/mtd/mtd.c
new file mode 100644
index 000000000..43e42c951
--- /dev/null
+++ b/src/systemcmds/mtd/mtd.c
@@ -0,0 +1,216 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013-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 mtd.c
+ *
+ * mtd service and utility app.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ */
+
+#include <nuttx/config.h>
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <stdbool.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <sys/mount.h>
+#include <sys/ioctl.h>
+#include <sys/stat.h>
+
+#include <nuttx/spi.h>
+#include <nuttx/mtd.h>
+#include <nuttx/fs/nxffs.h>
+#include <nuttx/fs/ioctl.h>
+
+#include <arch/board/board.h>
+
+#include "systemlib/systemlib.h"
+#include "systemlib/param/param.h"
+#include "systemlib/err.h"
+
+__EXPORT int mtd_main(int argc, char *argv[]);
+
+#ifndef CONFIG_MTD_RAMTRON
+
+/* create a fake command with decent message to not confuse users */
+int mtd_main(int argc, char *argv[])
+{
+ errx(1, "RAMTRON not enabled, skipping.");
+}
+
+#else
+
+static void mtd_attach(void);
+static void mtd_start(void);
+static void mtd_erase(void);
+static void mtd_ioctl(unsigned operation);
+static void mtd_save(const char *name);
+static void mtd_load(const char *name);
+static void mtd_test(void);
+
+static bool attached = false;
+static bool started = false;
+static struct mtd_dev_s *mtd_dev;
+static char *_mtdname = "/dev/mtd_params";
+static char *_wpname = "/dev/mtd_waypoints";
+
+int mtd_main(int argc, char *argv[])
+{
+ if (argc >= 2) {
+ if (!strcmp(argv[1], "start"))
+ mtd_start();
+
+ if (!strcmp(argv[1], "test"))
+ mtd_test();
+ }
+
+ errx(1, "expected a command, try 'start' or 'test'");
+}
+
+struct mtd_dev_s *ramtron_initialize(FAR struct spi_dev_s *dev);
+
+
+static void
+mtd_attach(void)
+{
+ /* find the right spi */
+ struct spi_dev_s *spi = up_spiinitialize(2);
+ /* this resets the spi bus, set correct bus speed again */
+ SPI_SETFREQUENCY(spi, 40 * 1000 * 1000);
+ SPI_SETBITS(spi, 8);
+ SPI_SETMODE(spi, SPIDEV_MODE3);
+ SPI_SELECT(spi, SPIDEV_FLASH, false);
+
+ if (spi == NULL)
+ errx(1, "failed to locate spi bus");
+
+ /* start the MTD driver, attempt 5 times */
+ for (int i = 0; i < 5; i++) {
+ mtd_dev = ramtron_initialize(spi);
+
+ if (mtd_dev) {
+ /* abort on first valid result */
+ if (i > 0) {
+ warnx("warning: mtd needed %d attempts to attach", i + 1);
+ }
+
+ break;
+ }
+ }
+
+ /* if last attempt is still unsuccessful, abort */
+ if (mtd_dev == NULL)
+ errx(1, "failed to initialize mtd driver");
+
+ attached = true;
+}
+
+static void
+mtd_start(void)
+{
+ int ret;
+
+ if (started)
+ errx(1, "mtd already mounted");
+
+ if (!attached)
+ mtd_attach();
+
+ if (!mtd_dev) {
+ warnx("ERROR: Failed to create RAMTRON FRAM MTD instance\n");
+ exit(1);
+ }
+
+ /* Initialize to provide an FTL block driver on the MTD FLASH interface.
+ *
+ * NOTE: We could just skip all of this FTL and BCH stuff. We could
+ * instead just use the MTD drivers bwrite and bread to perform this
+ * test. Creating the character drivers, however, makes this test more
+ * interesting.
+ */
+
+ ret = ftl_initialize(0, mtd_dev);
+
+ if (ret < 0) {
+ warnx("Creating /dev/mtdblock0 failed: %d\n", ret);
+ exit(2);
+ }
+
+ /* Now create a character device on the block device */
+
+ ret = bchdev_register("/dev/mtdblock0", _mtdname, false);
+
+ if (ret < 0) {
+ warnx("ERROR: bchdev_register %s failed: %d\n", _mtdname, ret);
+ exit(3);
+ }
+
+ /* mount the mtd */
+ ret = mount(NULL, "/mtd", "nxffs", 0, NULL);
+
+ if (ret < 0)
+ errx(1, "failed to mount /mtd - erase mtd to reformat");
+
+ started = true;
+ warnx("mounted mtd at /mtd");
+ exit(0);
+}
+
+static void
+mtd_ioctl(unsigned operation)
+{
+ int fd;
+
+ fd = open("/mtd/.", 0);
+
+ if (fd < 0)
+ err(1, "open /mtd");
+
+ if (ioctl(fd, operation, 0) < 0)
+ err(1, "ioctl");
+
+ exit(0);
+}
+
+static void
+mtd_test(void)
+{
+// at24c_test();
+ exit(0);
+}
+
+#endif
diff --git a/src/systemcmds/nshterm/nshterm.c b/src/systemcmds/nshterm/nshterm.c
index 458bb2259..7d9484d3e 100644
--- a/src/systemcmds/nshterm/nshterm.c
+++ b/src/systemcmds/nshterm/nshterm.c
@@ -62,7 +62,9 @@ nshterm_main(int argc, char *argv[])
}
uint8_t retries = 0;
int fd = -1;
- while (retries < 50) {
+
+ /* try the first 30 seconds */
+ while (retries < 300) {
/* the retries are to cope with the behaviour of /dev/ttyACM0 */
/* which may not be ready immediately. */
fd = open(argv[1], O_RDWR);
diff --git a/src/systemcmds/tests/module.mk b/src/systemcmds/tests/module.mk
index 68a080c77..28e214a6c 100644
--- a/src/systemcmds/tests/module.mk
+++ b/src/systemcmds/tests/module.mk
@@ -28,4 +28,5 @@ SRCS = test_adc.c \
tests_main.c \
test_param.c \
test_ppm_loopback.c \
- test_rc.c
+ test_rc.c \
+ test_mount.c
diff --git a/src/systemcmds/tests/test_file.c b/src/systemcmds/tests/test_file.c
index 798724cf1..83d09dd5e 100644
--- a/src/systemcmds/tests/test_file.c
+++ b/src/systemcmds/tests/test_file.c
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 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,9 +35,12 @@
* @file test_file.c
*
* File write test.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
*/
#include <sys/stat.h>
+#include <poll.h>
#include <dirent.h>
#include <stdio.h>
#include <stddef.h>
@@ -51,6 +54,40 @@
#include "tests.h"
+int check_user_abort(int fd);
+
+int check_user_abort(int fd) {
+ /* 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.");
+ fsync(fd);
+ close(fd);
+ return OK;
+ /* not reached */
+ }
+ }
+ }
+
+ return 1;
+}
+
int
test_file(int argc, char *argv[])
{
@@ -86,7 +123,6 @@ test_file(int argc, char *argv[])
uint8_t read_buf[chunk_sizes[c] + alignments] __attribute__((aligned(64)));
hrt_abstime start, end;
- //perf_counter_t wperf = perf_alloc(PC_ELAPSED, "SD writes (aligned)");
int fd = open("/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT);
@@ -94,28 +130,25 @@ test_file(int argc, char *argv[])
start = hrt_absolute_time();
for (unsigned i = 0; i < iterations; i++) {
- //perf_begin(wperf);
int wret = write(fd, write_buf + a, chunk_sizes[c]);
if (wret != chunk_sizes[c]) {
warn("WRITE ERROR!");
if ((0x3 & (uintptr_t)(write_buf + a)))
- errx(1, "memory is unaligned, align shift: %d", a);
+ warnx("memory is unaligned, align shift: %d", a);
+ return 1;
}
fsync(fd);
- //perf_end(wperf);
+
+ if (!check_user_abort(fd))
+ return OK;
}
end = hrt_absolute_time();
- //warnx("%dKiB in %llu microseconds", iterations / 2, end - start);
-
- //perf_print_counter(wperf);
- //perf_free(wperf);
-
close(fd);
fd = open("/fs/microsd/testfile", O_RDONLY);
@@ -124,7 +157,8 @@ test_file(int argc, char *argv[])
int rret = read(fd, read_buf, chunk_sizes[c]);
if (rret != chunk_sizes[c]) {
- errx(1, "READ ERROR!");
+ warnx("READ ERROR!");
+ return 1;
}
/* compare value */
@@ -139,9 +173,13 @@ test_file(int argc, char *argv[])
}
if (!compare_ok) {
- errx(1, "ABORTING FURTHER COMPARISON DUE TO ERROR");
+ warnx("ABORTING FURTHER COMPARISON DUE TO ERROR");
+ return 1;
}
+ if (!check_user_abort(fd))
+ return OK;
+
}
/*
@@ -152,16 +190,20 @@ 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++) {
int wret = write(fd, write_buf, chunk_sizes[c]);
if (wret != chunk_sizes[c]) {
- err(1, "WRITE ERROR!");
+ warnx("WRITE ERROR!");
+ return 1;
}
+ if (!check_user_abort(fd))
+ return OK;
+
}
fsync(fd);
@@ -178,7 +220,8 @@ test_file(int argc, char *argv[])
int rret = read(fd, read_buf, chunk_sizes[c]);
if (rret != chunk_sizes[c]) {
- err(1, "READ ERROR!");
+ warnx("READ ERROR!");
+ return 1;
}
/* compare value */
@@ -190,10 +233,14 @@ test_file(int argc, char *argv[])
align_read_ok = false;
break;
}
+
+ if (!check_user_abort(fd))
+ return OK;
}
if (!align_read_ok) {
- errx(1, "ABORTING FURTHER COMPARISON DUE TO ERROR");
+ warnx("ABORTING FURTHER COMPARISON DUE TO ERROR");
+ return 1;
}
}
@@ -215,7 +262,8 @@ test_file(int argc, char *argv[])
int rret = read(fd, read_buf + a, chunk_sizes[c]);
if (rret != chunk_sizes[c]) {
- err(1, "READ ERROR!");
+ warnx("READ ERROR!");
+ return 1;
}
for (int j = 0; j < chunk_sizes[c]; j++) {
@@ -228,10 +276,14 @@ test_file(int argc, char *argv[])
if (unalign_read_err_count > 10)
break;
}
+
+ if (!check_user_abort(fd))
+ return OK;
}
if (!unalign_read_ok) {
- errx(1, "ABORTING FURTHER COMPARISON DUE TO ERROR");
+ warnx("ABORTING FURTHER COMPARISON DUE TO ERROR");
+ return 1;
}
}
@@ -239,9 +291,10 @@ test_file(int argc, char *argv[])
ret = unlink("/fs/microsd/testfile");
close(fd);
- if (ret)
- err(1, "UNLINKING FILE FAILED");
-
+ if (ret) {
+ warnx("UNLINKING FILE FAILED");
+ return 1;
+ }
}
}
@@ -261,75 +314,9 @@ test_file(int argc, char *argv[])
} else {
/* failed opening dir */
- err(1, "FAILED LISTING MICROSD ROOT DIRECTORY");
- }
-
- return 0;
-}
-#if 0
-int
-test_file(int argc, char *argv[])
-{
- const iterations = 1024;
-
- /* check if microSD card is mounted */
- struct stat buffer;
- if (stat("/fs/microsd/", &buffer)) {
- warnx("no microSD card mounted, aborting file test");
+ warnx("FAILED LISTING MICROSD ROOT DIRECTORY");
return 1;
}
- uint8_t buf[512];
- hrt_abstime start, end;
- perf_counter_t wperf = perf_alloc(PC_ELAPSED, "SD writes");
-
- int fd = open("/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT);
- memset(buf, 0, sizeof(buf));
-
- start = hrt_absolute_time();
- for (unsigned i = 0; i < iterations; i++) {
- perf_begin(wperf);
- write(fd, buf, sizeof(buf));
- perf_end(wperf);
- }
- end = hrt_absolute_time();
-
- close(fd);
-
- unlink("/fs/microsd/testfile");
-
- warnx("%dKiB in %llu microseconds", iterations / 2, end - start);
- perf_print_counter(wperf);
- perf_free(wperf);
-
- warnx("running unlink test");
-
- /* ensure that common commands do not run against file count limits */
- for (unsigned i = 0; i < 64; i++) {
-
- warnx("unlink iteration #%u", i);
-
- int fd = open("/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT);
- if (fd < 0)
- errx(1, "failed opening test file before unlink()");
- int ret = write(fd, buf, sizeof(buf));
- if (ret < 0)
- errx(1, "failed writing test file before unlink()");
- close(fd);
-
- ret = unlink("/fs/microsd/testfile");
- if (ret != OK)
- errx(1, "failed unlinking test file");
-
- fd = open("/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT);
- if (fd < 0)
- errx(1, "failed opening test file after unlink()");
- ret = write(fd, buf, sizeof(buf));
- if (ret < 0)
- errx(1, "failed writing test file after unlink()");
- close(fd);
- }
-
return 0;
}
-#endif
diff --git a/src/systemcmds/tests/test_mount.c b/src/systemcmds/tests/test_mount.c
new file mode 100644
index 000000000..44e34d9ef
--- /dev/null
+++ b/src/systemcmds/tests/test_mount.c
@@ -0,0 +1,289 @@
+/****************************************************************************
+ *
+ * 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 test_mount.c
+ *
+ * Device mount / unmount stress test
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ */
+
+#include <sys/stat.h>
+#include <dirent.h>
+#include <stdio.h>
+#include <stddef.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <systemlib/err.h>
+#include <systemlib/systemlib.h>
+#include <systemlib/perf_counter.h>
+#include <string.h>
+
+#include <drivers/drv_hrt.h>
+
+#include "tests.h"
+
+const int fsync_tries = 1;
+const int abort_tries = 10;
+
+int
+test_mount(int argc, char *argv[])
+{
+ const unsigned iterations = 2000;
+ const unsigned alignments = 10;
+
+ const char* cmd_filename = "/fs/microsd/mount_test_cmds.txt";
+
+
+ /* check if microSD card is mounted */
+ struct stat buffer;
+ if (stat("/fs/microsd/", &buffer)) {
+ warnx("no microSD card mounted, aborting file test");
+ return 1;
+ }
+
+ /* list directory */
+ DIR *d;
+ struct dirent *dir;
+ d = opendir("/fs/microsd");
+ if (d) {
+
+ while ((dir = readdir(d)) != NULL) {
+ //printf("%s\n", dir->d_name);
+ }
+
+ closedir(d);
+
+ warnx("directory listing ok (FS mounted and readable)");
+
+ } else {
+ /* failed opening dir */
+ warnx("FAILED LISTING MICROSD ROOT DIRECTORY");
+
+ if (stat(cmd_filename, &buffer) == OK) {
+ (void)unlink(cmd_filename);
+ }
+
+ return 1;
+ }
+
+ /* read current test status from file, write test instructions for next round */
+
+ /* initial values */
+ int it_left_fsync = fsync_tries;
+ int it_left_abort = abort_tries;
+
+ int cmd_fd;
+ if (stat(cmd_filename, &buffer) == OK) {
+
+ /* command file exists, read off state */
+ cmd_fd = open(cmd_filename, O_RDWR | O_NONBLOCK);
+ char buf[64];
+ int ret = read(cmd_fd, buf, sizeof(buf));
+
+ if (ret > 0) {
+ int count = 0;
+ ret = sscanf(buf, "TEST: %u %u %n", &it_left_fsync, &it_left_abort, &count);
+ } else {
+ buf[0] = '\0';
+ }
+
+ if (it_left_fsync > fsync_tries)
+ it_left_fsync = fsync_tries;
+
+ if (it_left_abort > abort_tries)
+ it_left_abort = abort_tries;
+
+ warnx("Iterations left: #%d / #%d of %d / %d\n(%s)", it_left_fsync, it_left_abort,
+ fsync_tries, abort_tries, buf);
+
+ int it_left_fsync_prev = it_left_fsync;
+
+ /* now write again what to do next */
+ if (it_left_fsync > 0)
+ it_left_fsync--;
+
+ if (it_left_fsync == 0 && it_left_abort > 0) {
+
+ it_left_abort--;
+
+ /* announce mode switch */
+ if (it_left_fsync_prev != it_left_fsync && it_left_fsync == 0) {
+ warnx("\n SUCCESSFULLY PASSED FSYNC'ED WRITES, CONTINUTING WITHOUT FSYNC");
+ fsync(stdout);
+ fsync(stderr);
+ usleep(20000);
+ }
+
+ }
+
+ if (it_left_abort == 0) {
+ (void)unlink(cmd_filename);
+ return 0;
+ }
+
+ } else {
+
+ /* this must be the first iteration, do something */
+ cmd_fd = open(cmd_filename, O_TRUNC | O_WRONLY | O_CREAT);
+
+ warnx("First iteration of file test\n");
+ }
+
+ char buf[64];
+ int wret = sprintf(buf, "TEST: %d %d ", it_left_fsync, it_left_abort);
+ lseek(cmd_fd, 0, SEEK_SET);
+ write(cmd_fd, buf, strlen(buf) + 1);
+ fsync(cmd_fd);
+
+ /* perform tests for a range of chunk sizes */
+ unsigned chunk_sizes[] = {32, 64, 128, 256, 512, 600, 1200};
+
+ for (unsigned c = 0; c < (sizeof(chunk_sizes) / sizeof(chunk_sizes[0])); c++) {
+
+ printf("\n\n====== FILE TEST: %u bytes chunks (%s) ======\n", chunk_sizes[c], (it_left_fsync > 0) ? "FSYNC" : "NO FSYNC");
+ printf("unpower the system immediately (within 0.5s) when the hash (#) sign appears\n");
+ fsync(stdout);
+ fsync(stderr);
+ usleep(50000);
+
+ for (unsigned a = 0; a < alignments; a++) {
+
+ printf(".");
+
+ uint8_t write_buf[chunk_sizes[c] + alignments] __attribute__((aligned(64)));
+
+ /* fill write buffer with known values */
+ for (int i = 0; i < sizeof(write_buf); i++) {
+ /* this will wrap, but we just need a known value with spacing */
+ write_buf[i] = i+11;
+ }
+
+ uint8_t read_buf[chunk_sizes[c] + alignments] __attribute__((aligned(64)));
+ hrt_abstime start, end;
+
+ int fd = open("/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT);
+
+ start = hrt_absolute_time();
+ for (unsigned i = 0; i < iterations; i++) {
+
+ int wret = write(fd, write_buf + a, chunk_sizes[c]);
+
+ if (wret != chunk_sizes[c]) {
+ warn("WRITE ERROR!");
+
+ if ((0x3 & (uintptr_t)(write_buf + a)))
+ warnx("memory is unaligned, align shift: %d", a);
+
+ return 1;
+
+ }
+
+ if (it_left_fsync > 0) {
+ fsync(fd);
+ } else {
+ printf("#");
+ fsync(stdout);
+ fsync(stderr);
+ }
+ }
+
+ if (it_left_fsync > 0) {
+ printf("#");
+ }
+
+ printf(".");
+ fsync(stdout);
+ fsync(stderr);
+ usleep(200000);
+
+ end = hrt_absolute_time();
+
+ close(fd);
+ fd = open("/fs/microsd/testfile", O_RDONLY);
+
+ /* read back data for validation */
+ for (unsigned i = 0; i < iterations; i++) {
+ int rret = read(fd, read_buf, chunk_sizes[c]);
+
+ if (rret != chunk_sizes[c]) {
+ warnx("READ ERROR!");
+ return 1;
+ }
+
+ /* compare value */
+ bool compare_ok = true;
+
+ for (int j = 0; j < chunk_sizes[c]; j++) {
+ if (read_buf[j] != write_buf[j + a]) {
+ warnx("COMPARISON ERROR: byte %d, align shift: %d", j, a);
+ compare_ok = false;
+ break;
+ }
+ }
+
+ if (!compare_ok) {
+ warnx("ABORTING FURTHER COMPARISON DUE TO ERROR");
+ return 1;
+ }
+
+ }
+
+ int ret = unlink("/fs/microsd/testfile");
+ close(fd);
+
+ if (ret) {
+ warnx("UNLINKING FILE FAILED");
+ return 1;
+ }
+
+ }
+ }
+
+ fsync(stdout);
+ fsync(stderr);
+ usleep(20000);
+
+
+
+ /* we always reboot for the next test if we get here */
+ warnx("Iteration done, rebooting..");
+ fsync(stdout);
+ fsync(stderr);
+ usleep(50000);
+ systemreset(false);
+
+ /* never going to get here */
+ return 0;
+}
diff --git a/src/systemcmds/tests/tests.h b/src/systemcmds/tests/tests.h
index a57d04be3..bec13bd30 100644
--- a/src/systemcmds/tests/tests.h
+++ b/src/systemcmds/tests/tests.h
@@ -109,6 +109,7 @@ extern int test_bson(int argc, char *argv[]);
extern int test_file(int argc, char *argv[]);
extern int test_mixer(int argc, char *argv[]);
extern int test_rc(int argc, char *argv[]);
+extern int test_mount(int argc, char *argv[]);
__END_DECLS
diff --git a/src/systemcmds/tests/tests_main.c b/src/systemcmds/tests/tests_main.c
index 1088a4407..84535126f 100644
--- a/src/systemcmds/tests/tests_main.c
+++ b/src/systemcmds/tests/tests_main.c
@@ -106,6 +106,7 @@ const struct {
{"file", test_file, 0},
{"mixer", test_mixer, OPT_NOJIGTEST | OPT_NOALLTEST},
{"rc", test_rc, OPT_NOJIGTEST | OPT_NOALLTEST},
+ {"mount", test_mount, OPT_NOJIGTEST | OPT_NOALLTEST},
{"help", test_help, OPT_NOALLTEST | OPT_NOHELP | OPT_NOJIGTEST},
{NULL, NULL, 0}
};