From 2fc10320697ecaa9c4e0c52d4d047424e41e6336 Mon Sep 17 00:00:00 2001 From: px4dev Date: Tue, 23 Oct 2012 23:38:45 -0700 Subject: Major formatting/whitespace cleanup --- apps/systemcmds/bl_update/bl_update.c | 8 + apps/systemcmds/eeprom/24xxxx_mtd.c | 533 ++++++++++++++++------------------ apps/systemcmds/eeprom/eeprom.c | 11 +- apps/systemcmds/led/led.c | 7 +- apps/systemcmds/mixer/mixer.c | 1 + apps/systemcmds/param/param.c | 13 +- apps/systemcmds/top/top.c | 6 +- 7 files changed, 293 insertions(+), 286 deletions(-) (limited to 'apps/systemcmds') diff --git a/apps/systemcmds/bl_update/bl_update.c b/apps/systemcmds/bl_update/bl_update.c index 752c01986..745f76852 100644 --- a/apps/systemcmds/bl_update/bl_update.c +++ b/apps/systemcmds/bl_update/bl_update.c @@ -67,10 +67,12 @@ bl_update_main(int argc, char *argv[]) setopt(); int fd = open(argv[1], O_RDONLY); + if (fd < 0) err(1, "open %s", argv[1]); struct stat s; + if (stat(argv[1], &s) < 0) err(1, "stat %s", argv[1]); @@ -79,14 +81,17 @@ bl_update_main(int argc, char *argv[]) errx(1, "%s: file too large", argv[1]); uint8_t *buf = malloc(s.st_size); + if (buf == NULL) errx(1, "failed to allocate %u bytes for firmware buffer", s.st_size); if (read(fd, buf, s.st_size) != s.st_size) err(1, "firmware read error"); + close(fd); uint32_t *hdr = (uint32_t *)buf; + if ((hdr[0] < 0x20000000) || /* stack not below RAM */ (hdr[0] > (0x20000000 + (128 * 1024))) || /* stack not above RAM */ (hdr[1] < 0x08000000) || /* entrypoint not below flash */ @@ -123,6 +128,7 @@ bl_update_main(int argc, char *argv[]) /* wait for the operation to complete */ while (*sr & 0x1000) { } + if (*sr & 0xf2) { warnx("WARNING: erase error 0x%02x", *sr); goto flash_end; @@ -148,6 +154,7 @@ bl_update_main(int argc, char *argv[]) /* wait for the operation to complete */ while (*sr & 0x1000) { } + if (*sr & 0xf2) { warnx("WARNING: program error 0x%02x", *sr); goto flash_end; @@ -203,6 +210,7 @@ setopt(void) if ((*optcr & opt_mask) == opt_bits) errx(0, "option bits set"); + errx(1, "option bits setting failed; readback 0x%04x", *optcr); } \ No newline at end of file diff --git a/apps/systemcmds/eeprom/24xxxx_mtd.c b/apps/systemcmds/eeprom/24xxxx_mtd.c index 3cded52fa..79149caa0 100644 --- a/apps/systemcmds/eeprom/24xxxx_mtd.c +++ b/apps/systemcmds/eeprom/24xxxx_mtd.c @@ -135,20 +135,19 @@ * cast between pointers to struct mtd_dev_s and struct at24c_dev_s. */ -struct at24c_dev_s -{ - struct mtd_dev_s mtd; /* MTD interface */ - FAR struct i2c_dev_s *dev; /* Saved I2C interface instance */ - uint8_t addr; /* I2C address */ - uint16_t pagesize; /* 32, 63 */ - uint16_t npages; /* 128, 256, 512, 1024 */ - - perf_counter_t perf_reads; - perf_counter_t perf_writes; - perf_counter_t perf_resets; - perf_counter_t perf_read_retries; - perf_counter_t perf_read_errors; - perf_counter_t perf_write_errors; +struct at24c_dev_s { + struct mtd_dev_s mtd; /* MTD interface */ + FAR struct i2c_dev_s *dev; /* Saved I2C interface instance */ + uint8_t addr; /* I2C address */ + uint16_t pagesize; /* 32, 63 */ + uint16_t npages; /* 128, 256, 512, 1024 */ + + perf_counter_t perf_reads; + perf_counter_t perf_writes; + perf_counter_t perf_resets; + perf_counter_t perf_read_retries; + perf_counter_t perf_read_errors; + perf_counter_t perf_write_errors; }; /************************************************************************************ @@ -159,9 +158,9 @@ struct at24c_dev_s static int at24c_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks); static ssize_t at24c_bread(FAR struct mtd_dev_s *dev, off_t startblock, - size_t nblocks, FAR uint8_t *buf); + size_t nblocks, FAR uint8_t *buf); static ssize_t at24c_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, - size_t nblocks, FAR const uint8_t *buf); + size_t nblocks, FAR const uint8_t *buf); static int at24c_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg); /************************************************************************************ @@ -180,35 +179,32 @@ static struct at24c_dev_s g_at24c; static int at24c_eraseall(FAR struct at24c_dev_s *priv) { - int startblock = 0; - uint8_t buf[AT24XX_PAGESIZE + 2]; - - struct i2c_msg_s msgv[1] = - { - { - .addr = priv->addr, - .flags = 0, - .buffer = &buf[0], - .length = sizeof(buf), - } - }; - - memset(&buf[2],0xff,priv->pagesize); - - for (startblock = 0; startblock < priv->npages; startblock++) - { - uint16_t offset = startblock * priv->pagesize; - buf[1] = offset & 0xff; - buf[0] = (offset >> 8) & 0xff; - - while (I2C_TRANSFER(priv->dev, &msgv[0], 1) < 0) - { - fvdbg("erase stall\n"); - usleep(10000); - } - } - - return OK; + int startblock = 0; + uint8_t buf[AT24XX_PAGESIZE + 2]; + + struct i2c_msg_s msgv[1] = { + { + .addr = priv->addr, + .flags = 0, + .buffer = &buf[0], + .length = sizeof(buf), + } + }; + + memset(&buf[2], 0xff, priv->pagesize); + + for (startblock = 0; startblock < priv->npages; startblock++) { + uint16_t offset = startblock * priv->pagesize; + buf[1] = offset & 0xff; + buf[0] = (offset >> 8) & 0xff; + + while (I2C_TRANSFER(priv->dev, &msgv[0], 1) < 0) { + fvdbg("erase stall\n"); + usleep(10000); + } + } + + return OK; } /************************************************************************************ @@ -217,9 +213,9 @@ static int at24c_eraseall(FAR struct at24c_dev_s *priv) static int at24c_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks) { - /* EEprom need not erase */ + /* EEprom need not erase */ - return (int)nblocks; + return (int)nblocks; } /************************************************************************************ @@ -227,90 +223,86 @@ static int at24c_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nbloc ************************************************************************************/ static ssize_t at24c_bread(FAR struct mtd_dev_s *dev, off_t startblock, - size_t nblocks, FAR uint8_t *buffer) + size_t nblocks, FAR uint8_t *buffer) { - FAR struct at24c_dev_s *priv = (FAR struct at24c_dev_s *)dev; - size_t blocksleft; - uint8_t addr[2]; - int ret; - - struct i2c_msg_s msgv[2] = - { - { - .addr = priv->addr, - .flags = 0, - .buffer = &addr[0], - .length = sizeof(addr), - }, - { - .addr = priv->addr, - .flags = I2C_M_READ, - .buffer = 0, - .length = priv->pagesize, - } - }; + FAR struct at24c_dev_s *priv = (FAR struct at24c_dev_s *)dev; + size_t blocksleft; + uint8_t addr[2]; + int ret; + + struct i2c_msg_s msgv[2] = { + { + .addr = priv->addr, + .flags = 0, + .buffer = &addr[0], + .length = sizeof(addr), + }, + { + .addr = priv->addr, + .flags = I2C_M_READ, + .buffer = 0, + .length = priv->pagesize, + } + }; #if CONFIG_AT24XX_MTD_BLOCKSIZE > AT24XX_PAGESIZE - startblock *= (CONFIG_AT24XX_MTD_BLOCKSIZE / AT24XX_PAGESIZE); - nblocks *= (CONFIG_AT24XX_MTD_BLOCKSIZE / AT24XX_PAGESIZE); + startblock *= (CONFIG_AT24XX_MTD_BLOCKSIZE / AT24XX_PAGESIZE); + nblocks *= (CONFIG_AT24XX_MTD_BLOCKSIZE / AT24XX_PAGESIZE); #endif - blocksleft = nblocks; - - fvdbg("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks); - - if (startblock >= priv->npages) - { - return 0; - } - - if (startblock + nblocks > priv->npages) - { - nblocks = priv->npages - startblock; - } - - while (blocksleft-- > 0) - { - uint16_t offset = startblock * priv->pagesize; - unsigned tries = CONFIG_AT24XX_WRITE_TIMEOUT_MS; - - addr[1] = offset & 0xff; - addr[0] = (offset >> 8) & 0xff; - msgv[1].buffer = buffer; - - for (;;) - { - - perf_begin(priv->perf_reads); - ret = I2C_TRANSFER(priv->dev, &msgv[0], 2); - perf_end(priv->perf_reads); - if (ret >= 0) - break; - - fvdbg("read stall"); - usleep(1000); - - /* We should normally only be here on the first read after - * a write. - * - * XXX maybe do special first-read handling with optional - * bus reset as well? - */ - perf_count(priv->perf_read_retries); - if (--tries == 0) - { - perf_count(priv->perf_read_errors); - return ERROR; - } - } - - startblock++; - buffer += priv->pagesize; - } + blocksleft = nblocks; + + fvdbg("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks); + + if (startblock >= priv->npages) { + return 0; + } + + if (startblock + nblocks > priv->npages) { + nblocks = priv->npages - startblock; + } + + while (blocksleft-- > 0) { + uint16_t offset = startblock * priv->pagesize; + unsigned tries = CONFIG_AT24XX_WRITE_TIMEOUT_MS; + + addr[1] = offset & 0xff; + addr[0] = (offset >> 8) & 0xff; + msgv[1].buffer = buffer; + + for (;;) { + + perf_begin(priv->perf_reads); + ret = I2C_TRANSFER(priv->dev, &msgv[0], 2); + perf_end(priv->perf_reads); + + if (ret >= 0) + break; + + fvdbg("read stall"); + usleep(1000); + + /* We should normally only be here on the first read after + * a write. + * + * XXX maybe do special first-read handling with optional + * bus reset as well? + */ + perf_count(priv->perf_read_retries); + + if (--tries == 0) { + perf_count(priv->perf_read_errors); + return ERROR; + } + } + + startblock++; + buffer += priv->pagesize; + } #if CONFIG_AT24XX_MTD_BLOCKSIZE > AT24XX_PAGESIZE - return nblocks / (CONFIG_AT24XX_MTD_BLOCKSIZE / AT24XX_PAGESIZE); + return nblocks / (CONFIG_AT24XX_MTD_BLOCKSIZE / AT24XX_PAGESIZE); #else - return nblocks; + return nblocks; #endif } @@ -322,81 +314,75 @@ static ssize_t at24c_bread(FAR struct mtd_dev_s *dev, off_t startblock, ************************************************************************************/ static ssize_t at24c_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks, - FAR const uint8_t *buffer) + FAR const uint8_t *buffer) { - FAR struct at24c_dev_s *priv = (FAR struct at24c_dev_s *)dev; - size_t blocksleft; - uint8_t buf[AT24XX_PAGESIZE+2]; - int ret; - - struct i2c_msg_s msgv[1] = - { - { - .addr = priv->addr, - .flags = 0, - .buffer = &buf[0], - .length = sizeof(buf), - } - }; + FAR struct at24c_dev_s *priv = (FAR struct at24c_dev_s *)dev; + size_t blocksleft; + uint8_t buf[AT24XX_PAGESIZE + 2]; + int ret; + + struct i2c_msg_s msgv[1] = { + { + .addr = priv->addr, + .flags = 0, + .buffer = &buf[0], + .length = sizeof(buf), + } + }; #if CONFIG_AT24XX_MTD_BLOCKSIZE > AT24XX_PAGESIZE - startblock *= (CONFIG_AT24XX_MTD_BLOCKSIZE / AT24XX_PAGESIZE); - nblocks *= (CONFIG_AT24XX_MTD_BLOCKSIZE / AT24XX_PAGESIZE); + startblock *= (CONFIG_AT24XX_MTD_BLOCKSIZE / AT24XX_PAGESIZE); + nblocks *= (CONFIG_AT24XX_MTD_BLOCKSIZE / AT24XX_PAGESIZE); #endif - blocksleft = nblocks; + blocksleft = nblocks; - if (startblock >= priv->npages) - { - return 0; - } + if (startblock >= priv->npages) { + return 0; + } - if (startblock + nblocks > priv->npages) - { - nblocks = priv->npages - startblock; - } + if (startblock + nblocks > priv->npages) { + nblocks = priv->npages - startblock; + } - fvdbg("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks); + fvdbg("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks); - while (blocksleft-- > 0) - { - uint16_t offset = startblock * priv->pagesize; - unsigned tries = CONFIG_AT24XX_WRITE_TIMEOUT_MS; + while (blocksleft-- > 0) { + uint16_t offset = startblock * priv->pagesize; + unsigned tries = CONFIG_AT24XX_WRITE_TIMEOUT_MS; - buf[1] = offset & 0xff; - buf[0] = (offset >> 8) & 0xff; - memcpy(&buf[2], buffer, priv->pagesize); + buf[1] = offset & 0xff; + buf[0] = (offset >> 8) & 0xff; + memcpy(&buf[2], buffer, priv->pagesize); - for (;;) - { + for (;;) { - perf_begin(priv->perf_writes); - ret = I2C_TRANSFER(priv->dev, &msgv[0], 1); - perf_end(priv->perf_writes); + perf_begin(priv->perf_writes); + ret = I2C_TRANSFER(priv->dev, &msgv[0], 1); + perf_end(priv->perf_writes); - if (ret >= 0) - break; + if (ret >= 0) + break; - fvdbg("write stall"); - usleep(1000); + fvdbg("write stall"); + usleep(1000); - /* We expect to see a number of retries per write cycle as we - * poll for write completion. - */ - if (--tries == 0) - { - perf_count(priv->perf_write_errors); - return ERROR; - } - } + /* We expect to see a number of retries per write cycle as we + * poll for write completion. + */ + if (--tries == 0) { + perf_count(priv->perf_write_errors); + return ERROR; + } + } - startblock++; - buffer += priv->pagesize; - } + startblock++; + buffer += priv->pagesize; + } #if CONFIG_AT24XX_MTD_BLOCKSIZE > AT24XX_PAGESIZE - return nblocks / (CONFIG_AT24XX_MTD_BLOCKSIZE / AT24XX_PAGESIZE); + return nblocks / (CONFIG_AT24XX_MTD_BLOCKSIZE / AT24XX_PAGESIZE); #else - return nblocks; + return nblocks; #endif } @@ -406,67 +392,65 @@ static ssize_t at24c_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t static int at24c_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg) { - FAR struct at24c_dev_s *priv = (FAR struct at24c_dev_s *)dev; - int ret = -EINVAL; /* Assume good command with bad parameters */ - - fvdbg("cmd: %d \n", cmd); - - switch (cmd) - { - case MTDIOC_GEOMETRY: - { - FAR struct mtd_geometry_s *geo = (FAR struct mtd_geometry_s *)((uintptr_t)arg); - if (geo) - { - /* Populate the geometry structure with information need to know - * the capacity and how to access the device. - * - * NOTE: that the device is treated as though it where just an array - * of fixed size blocks. That is most likely not true, but the client - * will expect the device logic to do whatever is necessary to make it - * appear so. - * - * blocksize: - * May be user defined. The block size for the at24XX devices may be - * larger than the page size in order to better support file systems. - * The read and write functions translate BLOCKS to pages for the - * small flash devices - * erasesize: - * It has to be at least as big as the blocksize, bigger serves no - * purpose. - * neraseblocks - * Note that the device size is in kilobits and must be scaled by - * 1024 / 8 - */ + FAR struct at24c_dev_s *priv = (FAR struct at24c_dev_s *)dev; + int ret = -EINVAL; /* Assume good command with bad parameters */ + + fvdbg("cmd: %d \n", cmd); + + switch (cmd) { + case MTDIOC_GEOMETRY: { + FAR struct mtd_geometry_s *geo = (FAR struct mtd_geometry_s *)((uintptr_t)arg); + + if (geo) { + /* Populate the geometry structure with information need to know + * the capacity and how to access the device. + * + * NOTE: that the device is treated as though it where just an array + * of fixed size blocks. That is most likely not true, but the client + * will expect the device logic to do whatever is necessary to make it + * appear so. + * + * blocksize: + * May be user defined. The block size for the at24XX devices may be + * larger than the page size in order to better support file systems. + * The read and write functions translate BLOCKS to pages for the + * small flash devices + * erasesize: + * It has to be at least as big as the blocksize, bigger serves no + * purpose. + * neraseblocks + * Note that the device size is in kilobits and must be scaled by + * 1024 / 8 + */ #if CONFIG_AT24XX_MTD_BLOCKSIZE > AT24XX_PAGESIZE - geo->blocksize = CONFIG_AT24XX_MTD_BLOCKSIZE; - geo->erasesize = CONFIG_AT24XX_MTD_BLOCKSIZE; - geo->neraseblocks = (CONFIG_AT24XX_SIZE * 1024 / 8) / CONFIG_AT24XX_MTD_BLOCKSIZE; + geo->blocksize = CONFIG_AT24XX_MTD_BLOCKSIZE; + geo->erasesize = CONFIG_AT24XX_MTD_BLOCKSIZE; + geo->neraseblocks = (CONFIG_AT24XX_SIZE * 1024 / 8) / CONFIG_AT24XX_MTD_BLOCKSIZE; #else - geo->blocksize = priv->pagesize; - geo->erasesize = priv->pagesize; - geo->neraseblocks = priv->npages; + geo->blocksize = priv->pagesize; + geo->erasesize = priv->pagesize; + geo->neraseblocks = priv->npages; #endif - ret = OK; + ret = OK; - fvdbg("blocksize: %d erasesize: %d neraseblocks: %d\n", - geo->blocksize, geo->erasesize, geo->neraseblocks); - } - } - break; + fvdbg("blocksize: %d erasesize: %d neraseblocks: %d\n", + geo->blocksize, geo->erasesize, geo->neraseblocks); + } + } + break; - case MTDIOC_BULKERASE: - ret=at24c_eraseall(priv); - break; + case MTDIOC_BULKERASE: + ret = at24c_eraseall(priv); + break; - case MTDIOC_XIPBASE: - default: - ret = -ENOTTY; /* Bad command */ - break; - } + case MTDIOC_XIPBASE: + default: + ret = -ENOTTY; /* Bad command */ + break; + } - return ret; + return ret; } /************************************************************************************ @@ -483,46 +467,45 @@ static int at24c_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg) * ************************************************************************************/ -FAR struct mtd_dev_s *at24c_initialize(FAR struct i2c_dev_s *dev) -{ - FAR struct at24c_dev_s *priv; - - fvdbg("dev: %p\n", dev); - - /* Allocate a state structure (we allocate the structure instead of using - * a fixed, static allocation so that we can handle multiple FLASH devices. - * The current implementation would handle only one FLASH part per I2C - * device (only because of the SPIDEV_FLASH definition) and so would have - * to be extended to handle multiple FLASH parts on the same I2C bus. - */ - - priv = &g_at24c; - if (priv) - { - /* Initialize the allocated structure */ - - priv->addr = CONFIG_AT24XX_ADDR; - priv->pagesize = AT24XX_PAGESIZE; - priv->npages = AT24XX_NPAGES; - - priv->mtd.erase = at24c_erase; - priv->mtd.bread = at24c_bread; - priv->mtd.bwrite = at24c_bwrite; - priv->mtd.ioctl = at24c_ioctl; - priv->dev = dev; - - priv->perf_reads = perf_alloc(PC_ELAPSED, "EEPROM read"); - priv->perf_writes = perf_alloc(PC_ELAPSED, "EEPROM write"); - priv->perf_resets = perf_alloc(PC_COUNT, "EEPROM reset"); - priv->perf_read_retries = perf_alloc(PC_COUNT, "EEPROM read retries"); - priv->perf_read_errors = perf_alloc(PC_COUNT, "EEPROM read errors"); - priv->perf_write_errors = perf_alloc(PC_COUNT, "EEPROM write errors"); - } - - /* Return the implementation-specific state structure as the MTD device */ - - fvdbg("Return %p\n", priv); - return (FAR struct mtd_dev_s *)priv; +FAR struct mtd_dev_s *at24c_initialize(FAR struct i2c_dev_s *dev) { + FAR struct at24c_dev_s *priv; + + fvdbg("dev: %p\n", dev); + + /* Allocate a state structure (we allocate the structure instead of using + * a fixed, static allocation so that we can handle multiple FLASH devices. + * The current implementation would handle only one FLASH part per I2C + * device (only because of the SPIDEV_FLASH definition) and so would have + * to be extended to handle multiple FLASH parts on the same I2C bus. + */ + + priv = &g_at24c; + + if (priv) { + /* Initialize the allocated structure */ + + priv->addr = CONFIG_AT24XX_ADDR; + priv->pagesize = AT24XX_PAGESIZE; + priv->npages = AT24XX_NPAGES; + + priv->mtd.erase = at24c_erase; + priv->mtd.bread = at24c_bread; + priv->mtd.bwrite = at24c_bwrite; + priv->mtd.ioctl = at24c_ioctl; + priv->dev = dev; + + priv->perf_reads = perf_alloc(PC_ELAPSED, "EEPROM read"); + priv->perf_writes = perf_alloc(PC_ELAPSED, "EEPROM write"); + priv->perf_resets = perf_alloc(PC_COUNT, "EEPROM reset"); + priv->perf_read_retries = perf_alloc(PC_COUNT, "EEPROM read retries"); + priv->perf_read_errors = perf_alloc(PC_COUNT, "EEPROM read errors"); + priv->perf_write_errors = perf_alloc(PC_COUNT, "EEPROM write errors"); + } + + /* Return the implementation-specific state structure as the MTD device */ + + fvdbg("Return %p\n", priv); + return (FAR struct mtd_dev_s *)priv; } /* @@ -530,5 +513,5 @@ FAR struct mtd_dev_s *at24c_initialize(FAR struct i2c_dev_s *dev) */ int at24c_nuke(void) { - return at24c_eraseall(&g_at24c); + return at24c_eraseall(&g_at24c); } diff --git a/apps/systemcmds/eeprom/eeprom.c b/apps/systemcmds/eeprom/eeprom.c index fa88fa09e..19a14aa02 100644 --- a/apps/systemcmds/eeprom/eeprom.c +++ b/apps/systemcmds/eeprom/eeprom.c @@ -143,13 +143,13 @@ eeprom_start(void) 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); @@ -165,6 +165,7 @@ eeprom_erase(void) if (at24c_nuke()) errx(1, "erase failed"); + errx(0, "erase done, reboot now"); } @@ -190,7 +191,7 @@ eeprom_save(const char *name) if (!started) errx(1, "must be started first"); - if (!name) + if (!name) err(1, "missing argument for device name, try '/eeprom/parameters'"); warnx("WARNING: 'eeprom save_param' deprecated - use 'param save' instead"); @@ -221,9 +222,9 @@ eeprom_load(const char *name) if (!started) errx(1, "must be started first"); - if (!name) + 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); diff --git a/apps/systemcmds/led/led.c b/apps/systemcmds/led/led.c index 7a1faa618..15d448118 100644 --- a/apps/systemcmds/led/led.c +++ b/apps/systemcmds/led/led.c @@ -121,6 +121,7 @@ usage(const char *reason) { if (reason) fprintf(stderr, "%s\n", reason); + fprintf(stderr, "usage: led {start|stop|status} [-d ]\n\n"); exit(1); } @@ -129,7 +130,7 @@ usage(const char *reason) * The deamon app only briefly exists to start * the background job. The stack size assigned in the * Makefile does only apply to this management task. - * + * * The actual stack size should be set in the call * to task_create(). */ @@ -165,9 +166,11 @@ int led_main(int argc, char *argv[]) if (!strcmp(argv[1], "status")) { if (thread_running) { printf("\tled is running\n"); + } else { printf("\tled not started\n"); } + exit(0); } @@ -187,7 +190,7 @@ int led_thread_main(int argc, char *argv[]) while (!thread_should_exit) { /* swell blue led */ - + /* 200 Hz base loop */ usleep(1000000 / rate); diff --git a/apps/systemcmds/mixer/mixer.c b/apps/systemcmds/mixer/mixer.c index 9d52557e7..3f52bdbf1 100644 --- a/apps/systemcmds/mixer/mixer.c +++ b/apps/systemcmds/mixer/mixer.c @@ -97,6 +97,7 @@ load(const char *devname, const char *fname) /* tell it to load the file */ ret = ioctl(dev, MIXERIOCLOADFILE, (unsigned long)fname); + if (ret != 0) { fprintf(stderr, "failed loading %s\n", fname); } diff --git a/apps/systemcmds/param/param.c b/apps/systemcmds/param/param.c index d70d15da4..68dbd822e 100644 --- a/apps/systemcmds/param/param.c +++ b/apps/systemcmds/param/param.c @@ -70,10 +70,13 @@ param_main(int argc, char *argv[]) if (argc >= 2) { if (!strcmp(argv[1], "save")) do_save(); + if (!strcmp(argv[1], "load")) do_load(); + if (!strcmp(argv[1], "import")) do_import(); + if (!strcmp(argv[1], "show")) do_show(); } @@ -154,8 +157,8 @@ do_show_print(void *arg, param_t param) float f; printf("%c %s: ", - param_value_unsaved(param) ? '*' : (param_value_is_default(param) ? ' ' : '+'), - param_name(param)); + param_value_unsaved(param) ? '*' : (param_value_is_default(param) ? ' ' : '+'), + param_name(param)); /* * This case can be expanded to handle printing common structure types. @@ -167,19 +170,25 @@ do_show_print(void *arg, param_t param) printf("%d\n", i); return; } + break; + case PARAM_TYPE_FLOAT: if (!param_get(param, &f)) { printf("%4.4f\n", (double)f); return; } + break; + case PARAM_TYPE_STRUCT ... PARAM_TYPE_STRUCT_MAX: printf("\n", 0 + param_type(param), param_size(param)); return; + default: printf("\n", 0 + param_type(param)); return; } + printf("\n", param); } diff --git a/apps/systemcmds/top/top.c b/apps/systemcmds/top/top.c index 7a2a993c2..59d2bc8f1 100644 --- a/apps/systemcmds/top/top.c +++ b/apps/systemcmds/top/top.c @@ -190,13 +190,15 @@ int top_main(int argc, char *argv[]) runtime_spaces = ""; } - unsigned stack_size = (uintptr_t)system_load.tasks[i].tcb->adj_stack_ptr - - (uintptr_t)system_load.tasks[i].tcb->stack_alloc_ptr; + unsigned stack_size = (uintptr_t)system_load.tasks[i].tcb->adj_stack_ptr - + (uintptr_t)system_load.tasks[i].tcb->stack_alloc_ptr; unsigned stack_free = 0; uint8_t *stack_sweeper = (uint8_t *)system_load.tasks[i].tcb->stack_alloc_ptr; + while (stack_free < stack_size) { if (*stack_sweeper++ != 0xff) break; + stack_free++; } -- cgit v1.2.3