forked from Archive/PX4-Autopilot
Merge pull request #593 from PX4/mtd_eeprom
EEPROM supported in MTD interface
This commit is contained in:
commit
cd72f564ef
|
@ -38,8 +38,7 @@ MODULES += modules/sensors
|
||||||
#
|
#
|
||||||
# System commands
|
# System commands
|
||||||
#
|
#
|
||||||
MODULES += systemcmds/eeprom
|
MODULES += systemcmds/mtd
|
||||||
MODULES += systemcmds/ramtron
|
|
||||||
MODULES += systemcmds/bl_update
|
MODULES += systemcmds/bl_update
|
||||||
MODULES += systemcmds/boardinfo
|
MODULES += systemcmds/boardinfo
|
||||||
MODULES += systemcmds/i2c
|
MODULES += systemcmds/i2c
|
||||||
|
|
|
@ -42,8 +42,7 @@ MODULES += modules/sensors
|
||||||
#
|
#
|
||||||
# System commands
|
# System commands
|
||||||
#
|
#
|
||||||
MODULES += systemcmds/eeprom
|
MODULES += systemcmds/mtd
|
||||||
MODULES += systemcmds/ramtron
|
|
||||||
MODULES += systemcmds/bl_update
|
MODULES += systemcmds/bl_update
|
||||||
MODULES += systemcmds/boardinfo
|
MODULES += systemcmds/boardinfo
|
||||||
MODULES += systemcmds/i2c
|
MODULES += systemcmds/i2c
|
||||||
|
|
|
@ -22,6 +22,7 @@ MODULES += systemcmds/perf
|
||||||
MODULES += systemcmds/reboot
|
MODULES += systemcmds/reboot
|
||||||
MODULES += systemcmds/tests
|
MODULES += systemcmds/tests
|
||||||
MODULES += systemcmds/nshterm
|
MODULES += systemcmds/nshterm
|
||||||
|
MODULES += systemcmds/mtd
|
||||||
|
|
||||||
#
|
#
|
||||||
# Library modules
|
# Library modules
|
||||||
|
|
|
@ -46,7 +46,6 @@ MODULES += modules/sensors
|
||||||
#
|
#
|
||||||
# System commands
|
# System commands
|
||||||
#
|
#
|
||||||
MODULES += systemcmds/ramtron
|
|
||||||
MODULES += systemcmds/bl_update
|
MODULES += systemcmds/bl_update
|
||||||
MODULES += systemcmds/boardinfo
|
MODULES += systemcmds/boardinfo
|
||||||
MODULES += systemcmds/mixer
|
MODULES += systemcmds/mixer
|
||||||
|
|
|
@ -87,7 +87,7 @@ __BEGIN_DECLS
|
||||||
#define GPIO_GYRO_DRDY_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTB|GPIO_PIN0)
|
#define GPIO_GYRO_DRDY_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTB|GPIO_PIN0)
|
||||||
#define GPIO_MAG_DRDY_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTB|GPIO_PIN1)
|
#define GPIO_MAG_DRDY_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTB|GPIO_PIN1)
|
||||||
#define GPIO_ACCEL_DRDY_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTB|GPIO_PIN4)
|
#define GPIO_ACCEL_DRDY_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTB|GPIO_PIN4)
|
||||||
#define GPIO_EXTI_MPU_DRDY (GPIO_INPUT|GPIO_PULLDOWN|GPIO_EXTI|GPIO_PORTD|GPIO_PIN15)
|
#define GPIO_EXTI_MPU_DRDY_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_EXTI|GPIO_PORTD|GPIO_PIN15)
|
||||||
|
|
||||||
/* SPI1 off */
|
/* SPI1 off */
|
||||||
#define GPIO_SPI1_SCK_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTA|GPIO_PIN5)
|
#define GPIO_SPI1_SCK_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTA|GPIO_PIN5)
|
||||||
|
@ -98,7 +98,7 @@ __BEGIN_DECLS
|
||||||
#define GPIO_SPI_CS_GYRO_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTC|GPIO_PIN13)
|
#define GPIO_SPI_CS_GYRO_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTC|GPIO_PIN13)
|
||||||
#define GPIO_SPI_CS_ACCEL_MAG_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTC|GPIO_PIN15)
|
#define GPIO_SPI_CS_ACCEL_MAG_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTC|GPIO_PIN15)
|
||||||
#define GPIO_SPI_CS_BARO_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTD|GPIO_PIN7)
|
#define GPIO_SPI_CS_BARO_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTD|GPIO_PIN7)
|
||||||
#define GPIO_SPI_CS_MPU (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTC|GPIO_PIN2)
|
#define GPIO_SPI_CS_MPU_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTC|GPIO_PIN2)
|
||||||
|
|
||||||
/* SPI chip selects */
|
/* SPI chip selects */
|
||||||
#define GPIO_SPI_CS_GYRO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN13)
|
#define GPIO_SPI_CS_GYRO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN13)
|
||||||
|
|
|
@ -1108,10 +1108,12 @@ PX4FMU::sensor_reset(int ms)
|
||||||
stm32_configgpio(GPIO_SPI_CS_GYRO_OFF);
|
stm32_configgpio(GPIO_SPI_CS_GYRO_OFF);
|
||||||
stm32_configgpio(GPIO_SPI_CS_ACCEL_MAG_OFF);
|
stm32_configgpio(GPIO_SPI_CS_ACCEL_MAG_OFF);
|
||||||
stm32_configgpio(GPIO_SPI_CS_BARO_OFF);
|
stm32_configgpio(GPIO_SPI_CS_BARO_OFF);
|
||||||
|
stm32_configgpio(GPIO_SPI_CS_MPU_OFF);
|
||||||
|
|
||||||
stm32_gpiowrite(GPIO_SPI_CS_GYRO_OFF, 0);
|
stm32_gpiowrite(GPIO_SPI_CS_GYRO_OFF, 0);
|
||||||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG_OFF, 0);
|
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG_OFF, 0);
|
||||||
stm32_gpiowrite(GPIO_SPI_CS_BARO_OFF, 0);
|
stm32_gpiowrite(GPIO_SPI_CS_BARO_OFF, 0);
|
||||||
|
stm32_gpiowrite(GPIO_SPI_CS_MPU_OFF, 0);
|
||||||
|
|
||||||
stm32_configgpio(GPIO_SPI1_SCK_OFF);
|
stm32_configgpio(GPIO_SPI1_SCK_OFF);
|
||||||
stm32_configgpio(GPIO_SPI1_MISO_OFF);
|
stm32_configgpio(GPIO_SPI1_MISO_OFF);
|
||||||
|
@ -1124,10 +1126,12 @@ PX4FMU::sensor_reset(int ms)
|
||||||
stm32_configgpio(GPIO_GYRO_DRDY_OFF);
|
stm32_configgpio(GPIO_GYRO_DRDY_OFF);
|
||||||
stm32_configgpio(GPIO_MAG_DRDY_OFF);
|
stm32_configgpio(GPIO_MAG_DRDY_OFF);
|
||||||
stm32_configgpio(GPIO_ACCEL_DRDY_OFF);
|
stm32_configgpio(GPIO_ACCEL_DRDY_OFF);
|
||||||
|
stm32_configgpio(GPIO_EXTI_MPU_DRDY_OFF);
|
||||||
|
|
||||||
stm32_gpiowrite(GPIO_GYRO_DRDY_OFF, 0);
|
stm32_gpiowrite(GPIO_GYRO_DRDY_OFF, 0);
|
||||||
stm32_gpiowrite(GPIO_MAG_DRDY_OFF, 0);
|
stm32_gpiowrite(GPIO_MAG_DRDY_OFF, 0);
|
||||||
stm32_gpiowrite(GPIO_ACCEL_DRDY_OFF, 0);
|
stm32_gpiowrite(GPIO_ACCEL_DRDY_OFF, 0);
|
||||||
|
stm32_gpiowrite(GPIO_EXTI_MPU_DRDY_OFF, 0);
|
||||||
|
|
||||||
/* set the sensor rail off */
|
/* set the sensor rail off */
|
||||||
stm32_configgpio(GPIO_VDD_3V3_SENSORS_EN);
|
stm32_configgpio(GPIO_VDD_3V3_SENSORS_EN);
|
||||||
|
@ -1160,6 +1164,13 @@ PX4FMU::sensor_reset(int ms)
|
||||||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
|
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
|
||||||
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
|
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
|
||||||
stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
|
stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
|
||||||
|
|
||||||
|
// // XXX bring up the EXTI pins again
|
||||||
|
// stm32_configgpio(GPIO_GYRO_DRDY);
|
||||||
|
// stm32_configgpio(GPIO_MAG_DRDY);
|
||||||
|
// stm32_configgpio(GPIO_ACCEL_DRDY);
|
||||||
|
// stm32_configgpio(GPIO_EXTI_MPU_DRDY);
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
|
@ -1,265 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
*
|
|
||||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
|
||||||
* Author: Lorenz Meier <lm@inf.ethz.ch>
|
|
||||||
*
|
|
||||||
* 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 eeprom.c
|
|
||||||
*
|
|
||||||
* EEPROM service and utility app.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#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/i2c.h>
|
|
||||||
#include <nuttx/mtd.h>
|
|
||||||
#include <nuttx/fs/nxffs.h>
|
|
||||||
#include <nuttx/fs/ioctl.h>
|
|
||||||
|
|
||||||
#include <board_config.h>
|
|
||||||
|
|
||||||
#include "systemlib/systemlib.h"
|
|
||||||
#include "systemlib/param/param.h"
|
|
||||||
#include "systemlib/err.h"
|
|
||||||
|
|
||||||
#ifndef PX4_I2C_BUS_ONBOARD
|
|
||||||
# error PX4_I2C_BUS_ONBOARD not defined, cannot locate onboard EEPROM
|
|
||||||
#endif
|
|
||||||
|
|
||||||
__EXPORT int eeprom_main(int argc, char *argv[]);
|
|
||||||
|
|
||||||
static void eeprom_attach(void);
|
|
||||||
static void eeprom_start(void);
|
|
||||||
static void eeprom_erase(void);
|
|
||||||
static void eeprom_ioctl(unsigned operation);
|
|
||||||
static void eeprom_save(const char *name);
|
|
||||||
static void eeprom_load(const char *name);
|
|
||||||
static void eeprom_test(void);
|
|
||||||
|
|
||||||
static bool attached = false;
|
|
||||||
static bool started = false;
|
|
||||||
static struct mtd_dev_s *eeprom_mtd;
|
|
||||||
|
|
||||||
int eeprom_main(int argc, char *argv[])
|
|
||||||
{
|
|
||||||
if (argc >= 2) {
|
|
||||||
if (!strcmp(argv[1], "start"))
|
|
||||||
eeprom_start();
|
|
||||||
|
|
||||||
if (!strcmp(argv[1], "save_param"))
|
|
||||||
eeprom_save(argv[2]);
|
|
||||||
|
|
||||||
if (!strcmp(argv[1], "load_param"))
|
|
||||||
eeprom_load(argv[2]);
|
|
||||||
|
|
||||||
if (!strcmp(argv[1], "erase"))
|
|
||||||
eeprom_erase();
|
|
||||||
|
|
||||||
if (!strcmp(argv[1], "test"))
|
|
||||||
eeprom_test();
|
|
||||||
|
|
||||||
if (0) { /* these actually require a file on the filesystem... */
|
|
||||||
|
|
||||||
if (!strcmp(argv[1], "reformat"))
|
|
||||||
eeprom_ioctl(FIOC_REFORMAT);
|
|
||||||
|
|
||||||
if (!strcmp(argv[1], "repack"))
|
|
||||||
eeprom_ioctl(FIOC_OPTIMIZE);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
errx(1, "expected a command, try 'start'\n\t'save_param /eeprom/parameters'\n\t'load_param /eeprom/parameters'\n\t'erase'\n");
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
static void
|
|
||||||
eeprom_attach(void)
|
|
||||||
{
|
|
||||||
/* find the right I2C */
|
|
||||||
struct i2c_dev_s *i2c = up_i2cinitialize(PX4_I2C_BUS_ONBOARD);
|
|
||||||
/* this resets the I2C bus, set correct bus speed again */
|
|
||||||
I2C_SETFREQUENCY(i2c, 400000);
|
|
||||||
|
|
||||||
if (i2c == NULL)
|
|
||||||
errx(1, "failed to locate I2C bus");
|
|
||||||
|
|
||||||
/* start the MTD driver, attempt 5 times */
|
|
||||||
for (int i = 0; i < 5; i++) {
|
|
||||||
eeprom_mtd = at24c_initialize(i2c);
|
|
||||||
if (eeprom_mtd) {
|
|
||||||
/* abort on first valid result */
|
|
||||||
if (i > 0) {
|
|
||||||
warnx("warning: EEPROM needed %d attempts to attach", i+1);
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/* if last attempt is still unsuccessful, abort */
|
|
||||||
if (eeprom_mtd == NULL)
|
|
||||||
errx(1, "failed to initialize EEPROM driver");
|
|
||||||
|
|
||||||
attached = true;
|
|
||||||
}
|
|
||||||
|
|
||||||
static void
|
|
||||||
eeprom_start(void)
|
|
||||||
{
|
|
||||||
int ret;
|
|
||||||
|
|
||||||
if (started)
|
|
||||||
errx(1, "EEPROM already mounted");
|
|
||||||
|
|
||||||
if (!attached)
|
|
||||||
eeprom_attach();
|
|
||||||
|
|
||||||
/* start NXFFS */
|
|
||||||
ret = nxffs_initialize(eeprom_mtd);
|
|
||||||
|
|
||||||
if (ret < 0)
|
|
||||||
errx(1, "failed to initialize NXFFS - erase EEPROM to reformat");
|
|
||||||
|
|
||||||
/* mount the EEPROM */
|
|
||||||
ret = mount(NULL, "/eeprom", "nxffs", 0, NULL);
|
|
||||||
|
|
||||||
if (ret < 0)
|
|
||||||
errx(1, "failed to mount /eeprom - erase EEPROM to reformat");
|
|
||||||
|
|
||||||
started = true;
|
|
||||||
warnx("mounted EEPROM at /eeprom");
|
|
||||||
exit(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
extern int at24c_nuke(void);
|
|
||||||
|
|
||||||
static void
|
|
||||||
eeprom_erase(void)
|
|
||||||
{
|
|
||||||
if (!attached)
|
|
||||||
eeprom_attach();
|
|
||||||
|
|
||||||
if (at24c_nuke())
|
|
||||||
errx(1, "erase failed");
|
|
||||||
|
|
||||||
errx(0, "erase done, reboot now");
|
|
||||||
}
|
|
||||||
|
|
||||||
static void
|
|
||||||
eeprom_ioctl(unsigned operation)
|
|
||||||
{
|
|
||||||
int fd;
|
|
||||||
|
|
||||||
fd = open("/eeprom/.", 0);
|
|
||||||
|
|
||||||
if (fd < 0)
|
|
||||||
err(1, "open /eeprom");
|
|
||||||
|
|
||||||
if (ioctl(fd, operation, 0) < 0)
|
|
||||||
err(1, "ioctl");
|
|
||||||
|
|
||||||
exit(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
static void
|
|
||||||
eeprom_save(const char *name)
|
|
||||||
{
|
|
||||||
if (!started)
|
|
||||||
errx(1, "must be started first");
|
|
||||||
|
|
||||||
if (!name)
|
|
||||||
err(1, "missing argument for device name, try '/eeprom/parameters'");
|
|
||||||
|
|
||||||
warnx("WARNING: 'eeprom save_param' deprecated - use 'param save' instead");
|
|
||||||
|
|
||||||
/* delete the file in case it exists */
|
|
||||||
unlink(name);
|
|
||||||
|
|
||||||
/* create the file */
|
|
||||||
int fd = open(name, O_WRONLY | O_CREAT | O_EXCL);
|
|
||||||
|
|
||||||
if (fd < 0)
|
|
||||||
err(1, "opening '%s' failed", name);
|
|
||||||
|
|
||||||
int result = param_export(fd, false);
|
|
||||||
close(fd);
|
|
||||||
|
|
||||||
if (result < 0) {
|
|
||||||
unlink(name);
|
|
||||||
errx(1, "error exporting to '%s'", name);
|
|
||||||
}
|
|
||||||
|
|
||||||
exit(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
static void
|
|
||||||
eeprom_load(const char *name)
|
|
||||||
{
|
|
||||||
if (!started)
|
|
||||||
errx(1, "must be started first");
|
|
||||||
|
|
||||||
if (!name)
|
|
||||||
err(1, "missing argument for device name, try '/eeprom/parameters'");
|
|
||||||
|
|
||||||
warnx("WARNING: 'eeprom load_param' deprecated - use 'param load' instead");
|
|
||||||
|
|
||||||
int fd = open(name, O_RDONLY);
|
|
||||||
|
|
||||||
if (fd < 0)
|
|
||||||
err(1, "open '%s'", name);
|
|
||||||
|
|
||||||
int result = param_load(fd);
|
|
||||||
close(fd);
|
|
||||||
|
|
||||||
if (result < 0)
|
|
||||||
errx(1, "error importing from '%s'", name);
|
|
||||||
|
|
||||||
exit(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
extern void at24c_test(void);
|
|
||||||
|
|
||||||
static void
|
|
||||||
eeprom_test(void)
|
|
||||||
{
|
|
||||||
at24c_test();
|
|
||||||
exit(0);
|
|
||||||
}
|
|
|
@ -1,39 +0,0 @@
|
||||||
############################################################################
|
|
||||||
#
|
|
||||||
# Copyright (c) 2012, 2013 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.
|
|
||||||
#
|
|
||||||
############################################################################
|
|
||||||
|
|
||||||
#
|
|
||||||
# EEPROM file system driver
|
|
||||||
#
|
|
||||||
|
|
||||||
MODULE_COMMAND = eeprom
|
|
||||||
SRCS = 24xxxx_mtd.c eeprom.c
|
|
|
@ -3,4 +3,4 @@
|
||||||
#
|
#
|
||||||
|
|
||||||
MODULE_COMMAND = mtd
|
MODULE_COMMAND = mtd
|
||||||
SRCS = mtd.c
|
SRCS = mtd.c 24xxxx_mtd.c
|
||||||
|
|
|
@ -62,26 +62,41 @@
|
||||||
#include "systemlib/param/param.h"
|
#include "systemlib/param/param.h"
|
||||||
#include "systemlib/err.h"
|
#include "systemlib/err.h"
|
||||||
|
|
||||||
|
#include <board_config.h>
|
||||||
|
|
||||||
__EXPORT int mtd_main(int argc, char *argv[]);
|
__EXPORT int mtd_main(int argc, char *argv[]);
|
||||||
|
|
||||||
#ifndef CONFIG_MTD_RAMTRON
|
#ifndef CONFIG_MTD
|
||||||
|
|
||||||
/* create a fake command with decent warnx to not confuse users */
|
/* create a fake command with decent warnx to not confuse users */
|
||||||
int mtd_main(int argc, char *argv[])
|
int mtd_main(int argc, char *argv[])
|
||||||
{
|
{
|
||||||
errx(1, "RAMTRON not enabled, skipping.");
|
errx(1, "MTD not enabled, skipping.");
|
||||||
}
|
}
|
||||||
|
|
||||||
#else
|
#else
|
||||||
|
|
||||||
static void mtd_attach(void);
|
#ifdef CONFIG_MTD_RAMTRON
|
||||||
|
static void ramtron_attach(void);
|
||||||
|
#else
|
||||||
|
|
||||||
|
#ifndef PX4_I2C_BUS_ONBOARD
|
||||||
|
# error PX4_I2C_BUS_ONBOARD not defined, cannot locate onboard EEPROM
|
||||||
|
#endif
|
||||||
|
|
||||||
|
static void at24xxx_attach(void);
|
||||||
|
#endif
|
||||||
static void mtd_start(char *partition_names[], unsigned n_partitions);
|
static void mtd_start(char *partition_names[], unsigned n_partitions);
|
||||||
static void mtd_test(void);
|
static void mtd_test(void);
|
||||||
static void mtd_erase(char *partition_names[], unsigned n_partitions);
|
static void mtd_erase(char *partition_names[], unsigned n_partitions);
|
||||||
|
static void mtd_print_info();
|
||||||
|
static int mtd_get_geometry(unsigned long *blocksize, unsigned long *erasesize, unsigned long *neraseblocks,
|
||||||
|
unsigned *blkpererase, unsigned *nblocks, unsigned *partsize, unsigned n_partitions);
|
||||||
|
|
||||||
static bool attached = false;
|
static bool attached = false;
|
||||||
static bool started = false;
|
static bool started = false;
|
||||||
static struct mtd_dev_s *mtd_dev;
|
static struct mtd_dev_s *mtd_dev;
|
||||||
|
static unsigned n_partitions_current = 0;
|
||||||
|
|
||||||
/* note, these will be equally sized */
|
/* note, these will be equally sized */
|
||||||
static char *partition_names_default[] = {"/fs/mtd_params", "/fs/mtd_waypoints"};
|
static char *partition_names_default[] = {"/fs/mtd_params", "/fs/mtd_waypoints"};
|
||||||
|
@ -104,6 +119,9 @@ int mtd_main(int argc, char *argv[])
|
||||||
if (!strcmp(argv[1], "test"))
|
if (!strcmp(argv[1], "test"))
|
||||||
mtd_test();
|
mtd_test();
|
||||||
|
|
||||||
|
if (!strcmp(argv[1], "status"))
|
||||||
|
mtd_status();
|
||||||
|
|
||||||
if (!strcmp(argv[1], "erase")) {
|
if (!strcmp(argv[1], "erase")) {
|
||||||
if (argc < 3) {
|
if (argc < 3) {
|
||||||
errx(1, "usage: mtd erase <PARTITION_PATH..>");
|
errx(1, "usage: mtd erase <PARTITION_PATH..>");
|
||||||
|
@ -119,8 +137,9 @@ struct mtd_dev_s *ramtron_initialize(FAR struct spi_dev_s *dev);
|
||||||
struct mtd_dev_s *mtd_partition(FAR struct mtd_dev_s *mtd,
|
struct mtd_dev_s *mtd_partition(FAR struct mtd_dev_s *mtd,
|
||||||
off_t firstblock, off_t nblocks);
|
off_t firstblock, off_t nblocks);
|
||||||
|
|
||||||
|
#ifdef CONFIG_MTD_RAMTRON
|
||||||
static void
|
static void
|
||||||
mtd_attach(void)
|
ramtron_attach(void)
|
||||||
{
|
{
|
||||||
/* find the right spi */
|
/* find the right spi */
|
||||||
struct spi_dev_s *spi = up_spiinitialize(2);
|
struct spi_dev_s *spi = up_spiinitialize(2);
|
||||||
|
@ -133,7 +152,7 @@ mtd_attach(void)
|
||||||
if (spi == NULL)
|
if (spi == NULL)
|
||||||
errx(1, "failed to locate spi bus");
|
errx(1, "failed to locate spi bus");
|
||||||
|
|
||||||
/* start the MTD driver, attempt 5 times */
|
/* start the RAMTRON driver, attempt 5 times */
|
||||||
for (int i = 0; i < 5; i++) {
|
for (int i = 0; i < 5; i++) {
|
||||||
mtd_dev = ramtron_initialize(spi);
|
mtd_dev = ramtron_initialize(spi);
|
||||||
|
|
||||||
|
@ -153,6 +172,38 @@ mtd_attach(void)
|
||||||
|
|
||||||
attached = true;
|
attached = true;
|
||||||
}
|
}
|
||||||
|
#else
|
||||||
|
|
||||||
|
static void
|
||||||
|
at24xxx_attach(void)
|
||||||
|
{
|
||||||
|
/* find the right I2C */
|
||||||
|
struct i2c_dev_s *i2c = up_i2cinitialize(PX4_I2C_BUS_ONBOARD);
|
||||||
|
/* this resets the I2C bus, set correct bus speed again */
|
||||||
|
I2C_SETFREQUENCY(i2c, 400000);
|
||||||
|
|
||||||
|
if (i2c == NULL)
|
||||||
|
errx(1, "failed to locate I2C bus");
|
||||||
|
|
||||||
|
/* start the MTD driver, attempt 5 times */
|
||||||
|
for (int i = 0; i < 5; i++) {
|
||||||
|
mtd_dev = at24c_initialize(i2c);
|
||||||
|
if (mtd_dev) {
|
||||||
|
/* abort on first valid result */
|
||||||
|
if (i > 0) {
|
||||||
|
warnx("warning: EEPROM needed %d attempts to attach", i+1);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* if last attempt is still unsuccessful, abort */
|
||||||
|
if (mtd_dev == NULL)
|
||||||
|
errx(1, "failed to initialize EEPROM driver");
|
||||||
|
|
||||||
|
attached = true;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
static void
|
static void
|
||||||
mtd_start(char *partition_names[], unsigned n_partitions)
|
mtd_start(char *partition_names[], unsigned n_partitions)
|
||||||
|
@ -162,42 +213,25 @@ mtd_start(char *partition_names[], unsigned n_partitions)
|
||||||
if (started)
|
if (started)
|
||||||
errx(1, "mtd already mounted");
|
errx(1, "mtd already mounted");
|
||||||
|
|
||||||
if (!attached)
|
if (!attached) {
|
||||||
mtd_attach();
|
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
|
||||||
|
at24xxx_attach();
|
||||||
|
#else
|
||||||
|
ramtron_attach();
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
if (!mtd_dev) {
|
if (!mtd_dev) {
|
||||||
warnx("ERROR: Failed to create RAMTRON FRAM MTD instance");
|
warnx("ERROR: Failed to create RAMTRON FRAM MTD instance");
|
||||||
exit(1);
|
exit(1);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
unsigned long blocksize, erasesize, neraseblocks;
|
||||||
|
unsigned blkpererase, nblocks, partsize;
|
||||||
|
|
||||||
/* Get the geometry of the FLASH device */
|
ret = mtd_get_geometry(&blocksize, &erasesize, &neraseblocks, &blkpererase, &nblocks, &partsize, n_partitions);
|
||||||
|
if (ret)
|
||||||
FAR struct mtd_geometry_s geo;
|
|
||||||
|
|
||||||
ret = mtd_dev->ioctl(mtd_dev, MTDIOC_GEOMETRY, (unsigned long)((uintptr_t)&geo));
|
|
||||||
|
|
||||||
if (ret < 0) {
|
|
||||||
warnx("ERROR: mtd->ioctl failed: %d", ret);
|
|
||||||
exit(3);
|
exit(3);
|
||||||
}
|
|
||||||
|
|
||||||
warnx("Flash Geometry:");
|
|
||||||
warnx(" blocksize: %lu", (unsigned long)geo.blocksize);
|
|
||||||
warnx(" erasesize: %lu", (unsigned long)geo.erasesize);
|
|
||||||
warnx(" neraseblocks: %lu", (unsigned long)geo.neraseblocks);
|
|
||||||
|
|
||||||
/* Determine the size of each partition. Make each partition an even
|
|
||||||
* multiple of the erase block size (perhaps not using some space at the
|
|
||||||
* end of the FLASH).
|
|
||||||
*/
|
|
||||||
|
|
||||||
unsigned blkpererase = geo.erasesize / geo.blocksize;
|
|
||||||
unsigned nblocks = (geo.neraseblocks / n_partitions) * blkpererase;
|
|
||||||
unsigned partsize = nblocks * geo.blocksize;
|
|
||||||
|
|
||||||
warnx(" No. partitions: %u", n_partitions);
|
|
||||||
warnx(" Partition size: %lu Blocks (%lu bytes)", (unsigned long)nblocks, (unsigned long)partsize);
|
|
||||||
|
|
||||||
/* Now create MTD FLASH partitions */
|
/* Now create MTD FLASH partitions */
|
||||||
|
|
||||||
|
@ -244,18 +278,83 @@ mtd_start(char *partition_names[], unsigned n_partitions)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
n_partitions_current = n_partitions;
|
||||||
|
|
||||||
started = true;
|
started = true;
|
||||||
exit(0);
|
exit(0);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void
|
int mtd_get_geometry(unsigned long *blocksize, unsigned long *erasesize, unsigned long *neraseblocks,
|
||||||
|
unsigned *blkpererase, unsigned *nblocks, unsigned *partsize, unsigned n_partitions)
|
||||||
|
{
|
||||||
|
/* Get the geometry of the FLASH device */
|
||||||
|
|
||||||
|
FAR struct mtd_geometry_s geo;
|
||||||
|
|
||||||
|
int ret = mtd_dev->ioctl(mtd_dev, MTDIOC_GEOMETRY, (unsigned long)((uintptr_t)&geo));
|
||||||
|
|
||||||
|
if (ret < 0) {
|
||||||
|
warnx("ERROR: mtd->ioctl failed: %d", ret);
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
*blocksize = geo.blocksize;
|
||||||
|
*erasesize = geo.blocksize;
|
||||||
|
*neraseblocks = geo.neraseblocks;
|
||||||
|
|
||||||
|
/* Determine the size of each partition. Make each partition an even
|
||||||
|
* multiple of the erase block size (perhaps not using some space at the
|
||||||
|
* end of the FLASH).
|
||||||
|
*/
|
||||||
|
|
||||||
|
*blkpererase = geo.erasesize / geo.blocksize;
|
||||||
|
*nblocks = (geo.neraseblocks / n_partitions) * *blkpererase;
|
||||||
|
*partsize = *nblocks * geo.blocksize;
|
||||||
|
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
void mtd_print_info()
|
||||||
|
{
|
||||||
|
if (!attached)
|
||||||
|
exit(1);
|
||||||
|
|
||||||
|
unsigned long blocksize, erasesize, neraseblocks;
|
||||||
|
unsigned blkpererase, nblocks, partsize;
|
||||||
|
|
||||||
|
int ret = mtd_get_geometry(&blocksize, &erasesize, &neraseblocks, &blkpererase, &nblocks, &partsize, n_partitions_current);
|
||||||
|
if (ret)
|
||||||
|
exit(3);
|
||||||
|
|
||||||
|
warnx("Flash Geometry:");
|
||||||
|
|
||||||
|
printf(" blocksize: %lu\n", blocksize);
|
||||||
|
printf(" erasesize: %lu\n", erasesize);
|
||||||
|
printf(" neraseblocks: %lu\n", neraseblocks);
|
||||||
|
printf(" No. partitions: %u\n", n_partitions_current);
|
||||||
|
printf(" Partition size: %u Blocks (%u bytes)\n", nblocks, partsize);
|
||||||
|
printf(" TOTAL SIZE: %u KiB\n", neraseblocks * erasesize / 1024);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
mtd_test(void)
|
mtd_test(void)
|
||||||
{
|
{
|
||||||
warnx("This test routine does not test anything yet!");
|
warnx("This test routine does not test anything yet!");
|
||||||
exit(1);
|
exit(1);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void
|
void
|
||||||
|
mtd_status(void)
|
||||||
|
{
|
||||||
|
if (!attached)
|
||||||
|
errx(1, "MTD driver not started");
|
||||||
|
|
||||||
|
mtd_print_info();
|
||||||
|
exit(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
mtd_erase(char *partition_names[], unsigned n_partitions)
|
mtd_erase(char *partition_names[], unsigned n_partitions)
|
||||||
{
|
{
|
||||||
uint8_t v[64];
|
uint8_t v[64];
|
||||||
|
|
|
@ -1,6 +0,0 @@
|
||||||
#
|
|
||||||
# RAMTRON file system driver
|
|
||||||
#
|
|
||||||
|
|
||||||
MODULE_COMMAND = ramtron
|
|
||||||
SRCS = ramtron.c
|
|
|
@ -1,279 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
*
|
|
||||||
* Copyright (C) 2013 PX4 Development Team. All rights reserved.
|
|
||||||
* Author: Lorenz Meier <lm@inf.ethz.ch>
|
|
||||||
*
|
|
||||||
* 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 ramtron.c
|
|
||||||
*
|
|
||||||
* ramtron service and utility app.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#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 ramtron_main(int argc, char *argv[]);
|
|
||||||
|
|
||||||
#ifndef CONFIG_MTD_RAMTRON
|
|
||||||
|
|
||||||
/* create a fake command with decent message to not confuse users */
|
|
||||||
int ramtron_main(int argc, char *argv[])
|
|
||||||
{
|
|
||||||
errx(1, "RAMTRON not enabled, skipping.");
|
|
||||||
}
|
|
||||||
#else
|
|
||||||
|
|
||||||
static void ramtron_attach(void);
|
|
||||||
static void ramtron_start(void);
|
|
||||||
static void ramtron_erase(void);
|
|
||||||
static void ramtron_ioctl(unsigned operation);
|
|
||||||
static void ramtron_save(const char *name);
|
|
||||||
static void ramtron_load(const char *name);
|
|
||||||
static void ramtron_test(void);
|
|
||||||
|
|
||||||
static bool attached = false;
|
|
||||||
static bool started = false;
|
|
||||||
static struct mtd_dev_s *ramtron_mtd;
|
|
||||||
|
|
||||||
int ramtron_main(int argc, char *argv[])
|
|
||||||
{
|
|
||||||
if (argc >= 2) {
|
|
||||||
if (!strcmp(argv[1], "start"))
|
|
||||||
ramtron_start();
|
|
||||||
|
|
||||||
if (!strcmp(argv[1], "save_param"))
|
|
||||||
ramtron_save(argv[2]);
|
|
||||||
|
|
||||||
if (!strcmp(argv[1], "load_param"))
|
|
||||||
ramtron_load(argv[2]);
|
|
||||||
|
|
||||||
if (!strcmp(argv[1], "erase"))
|
|
||||||
ramtron_erase();
|
|
||||||
|
|
||||||
if (!strcmp(argv[1], "test"))
|
|
||||||
ramtron_test();
|
|
||||||
|
|
||||||
if (0) { /* these actually require a file on the filesystem... */
|
|
||||||
|
|
||||||
if (!strcmp(argv[1], "reformat"))
|
|
||||||
ramtron_ioctl(FIOC_REFORMAT);
|
|
||||||
|
|
||||||
if (!strcmp(argv[1], "repack"))
|
|
||||||
ramtron_ioctl(FIOC_OPTIMIZE);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
errx(1, "expected a command, try 'start'\n\t'save_param /ramtron/parameters'\n\t'load_param /ramtron/parameters'\n\t'erase'\n");
|
|
||||||
}
|
|
||||||
|
|
||||||
struct mtd_dev_s *ramtron_initialize(FAR struct spi_dev_s *dev);
|
|
||||||
|
|
||||||
|
|
||||||
static void
|
|
||||||
ramtron_attach(void)
|
|
||||||
{
|
|
||||||
/* find the right spi */
|
|
||||||
struct spi_dev_s *spi = up_spiinitialize(2);
|
|
||||||
/* this resets the spi bus, set correct bus speed again */
|
|
||||||
// xxx set in ramtron driver, leave this out
|
|
||||||
// SPI_SETFREQUENCY(spi, 4000000);
|
|
||||||
SPI_SETFREQUENCY(spi, 375000000);
|
|
||||||
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++) {
|
|
||||||
ramtron_mtd = ramtron_initialize(spi);
|
|
||||||
if (ramtron_mtd) {
|
|
||||||
/* abort on first valid result */
|
|
||||||
if (i > 0) {
|
|
||||||
warnx("warning: ramtron needed %d attempts to attach", i+1);
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/* if last attempt is still unsuccessful, abort */
|
|
||||||
if (ramtron_mtd == NULL)
|
|
||||||
errx(1, "failed to initialize ramtron driver");
|
|
||||||
|
|
||||||
attached = true;
|
|
||||||
}
|
|
||||||
|
|
||||||
static void
|
|
||||||
ramtron_start(void)
|
|
||||||
{
|
|
||||||
int ret;
|
|
||||||
|
|
||||||
if (started)
|
|
||||||
errx(1, "ramtron already mounted");
|
|
||||||
|
|
||||||
if (!attached)
|
|
||||||
ramtron_attach();
|
|
||||||
|
|
||||||
/* start NXFFS */
|
|
||||||
ret = nxffs_initialize(ramtron_mtd);
|
|
||||||
|
|
||||||
if (ret < 0)
|
|
||||||
errx(1, "failed to initialize NXFFS - erase ramtron to reformat");
|
|
||||||
|
|
||||||
/* mount the ramtron */
|
|
||||||
ret = mount(NULL, "/ramtron", "nxffs", 0, NULL);
|
|
||||||
|
|
||||||
if (ret < 0)
|
|
||||||
errx(1, "failed to mount /ramtron - erase ramtron to reformat");
|
|
||||||
|
|
||||||
started = true;
|
|
||||||
warnx("mounted ramtron at /ramtron");
|
|
||||||
exit(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
//extern int at24c_nuke(void);
|
|
||||||
|
|
||||||
static void
|
|
||||||
ramtron_erase(void)
|
|
||||||
{
|
|
||||||
if (!attached)
|
|
||||||
ramtron_attach();
|
|
||||||
|
|
||||||
// if (at24c_nuke())
|
|
||||||
errx(1, "erase failed");
|
|
||||||
|
|
||||||
errx(0, "erase done, reboot now");
|
|
||||||
}
|
|
||||||
|
|
||||||
static void
|
|
||||||
ramtron_ioctl(unsigned operation)
|
|
||||||
{
|
|
||||||
int fd;
|
|
||||||
|
|
||||||
fd = open("/ramtron/.", 0);
|
|
||||||
|
|
||||||
if (fd < 0)
|
|
||||||
err(1, "open /ramtron");
|
|
||||||
|
|
||||||
if (ioctl(fd, operation, 0) < 0)
|
|
||||||
err(1, "ioctl");
|
|
||||||
|
|
||||||
exit(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
static void
|
|
||||||
ramtron_save(const char *name)
|
|
||||||
{
|
|
||||||
if (!started)
|
|
||||||
errx(1, "must be started first");
|
|
||||||
|
|
||||||
if (!name)
|
|
||||||
err(1, "missing argument for device name, try '/ramtron/parameters'");
|
|
||||||
|
|
||||||
warnx("WARNING: 'ramtron save_param' deprecated - use 'param save' instead");
|
|
||||||
|
|
||||||
/* delete the file in case it exists */
|
|
||||||
unlink(name);
|
|
||||||
|
|
||||||
/* create the file */
|
|
||||||
int fd = open(name, O_WRONLY | O_CREAT | O_EXCL);
|
|
||||||
|
|
||||||
if (fd < 0)
|
|
||||||
err(1, "opening '%s' failed", name);
|
|
||||||
|
|
||||||
int result = param_export(fd, false);
|
|
||||||
close(fd);
|
|
||||||
|
|
||||||
if (result < 0) {
|
|
||||||
unlink(name);
|
|
||||||
errx(1, "error exporting to '%s'", name);
|
|
||||||
}
|
|
||||||
|
|
||||||
exit(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
static void
|
|
||||||
ramtron_load(const char *name)
|
|
||||||
{
|
|
||||||
if (!started)
|
|
||||||
errx(1, "must be started first");
|
|
||||||
|
|
||||||
if (!name)
|
|
||||||
err(1, "missing argument for device name, try '/ramtron/parameters'");
|
|
||||||
|
|
||||||
warnx("WARNING: 'ramtron load_param' deprecated - use 'param load' instead");
|
|
||||||
|
|
||||||
int fd = open(name, O_RDONLY);
|
|
||||||
|
|
||||||
if (fd < 0)
|
|
||||||
err(1, "open '%s'", name);
|
|
||||||
|
|
||||||
int result = param_load(fd);
|
|
||||||
close(fd);
|
|
||||||
|
|
||||||
if (result < 0)
|
|
||||||
errx(1, "error importing from '%s'", name);
|
|
||||||
|
|
||||||
exit(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
//extern void at24c_test(void);
|
|
||||||
|
|
||||||
static void
|
|
||||||
ramtron_test(void)
|
|
||||||
{
|
|
||||||
// at24c_test();
|
|
||||||
exit(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif
|
|
Loading…
Reference in New Issue