summaryrefslogtreecommitdiff
path: root/nuttx/drivers
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/drivers')
-rw-r--r--nuttx/drivers/bch/bchlib_setup.c9
-rw-r--r--nuttx/drivers/bch/bchlib_teardown.c7
-rw-r--r--nuttx/drivers/i2c/st_lis331dl.c7
-rw-r--r--nuttx/drivers/loop.c9
-rw-r--r--nuttx/drivers/mmcsd/mmcsd_sdio.c7
-rw-r--r--nuttx/drivers/mtd/at45db.c7
-rwxr-xr-xnuttx/drivers/mtd/ftl.c13
-rw-r--r--nuttx/drivers/mtd/m25px.c7
-rwxr-xr-xnuttx/drivers/mtd/ramtron.c5
-rw-r--r--nuttx/drivers/net/slip.c2
-rw-r--r--nuttx/drivers/pipes/pipe_common.c9
-rw-r--r--nuttx/drivers/ramdisk.c7
-rw-r--r--nuttx/drivers/rwbuffer.c15
-rw-r--r--nuttx/drivers/usbdev/usbdev_serial.c11
-rw-r--r--nuttx/drivers/usbdev/usbdev_storage.c19
-rw-r--r--nuttx/drivers/usbhost/usbhost_hidkbd.c9
-rw-r--r--nuttx/drivers/usbhost/usbhost_skeleton.c9
-rw-r--r--nuttx/drivers/usbhost/usbhost_storage.c11
18 files changed, 89 insertions, 74 deletions
diff --git a/nuttx/drivers/bch/bchlib_setup.c b/nuttx/drivers/bch/bchlib_setup.c
index f0ce24dae..b97b63dd2 100644
--- a/nuttx/drivers/bch/bchlib_setup.c
+++ b/nuttx/drivers/bch/bchlib_setup.c
@@ -1,7 +1,7 @@
/****************************************************************************
* drivers/bch/bchlib_setup.c
*
- * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -49,6 +49,7 @@
#include <assert.h>
#include <debug.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/fs.h>
#include "bch_internal.h"
@@ -92,7 +93,7 @@ int bchlib_setup(const char *blkdev, bool readonly, FAR void **handle)
/* Allocate the BCH state structure */
- bch = (FAR struct bchlib_s*)zalloc(sizeof(struct bchlib_s));
+ bch = (FAR struct bchlib_s*)kzalloc(sizeof(struct bchlib_s));
if (!bch)
{
fdbg("Failed to allocate BCH structure\n");
@@ -141,7 +142,7 @@ int bchlib_setup(const char *blkdev, bool readonly, FAR void **handle)
/* Allocate the sector I/O buffer */
- bch->buffer = (FAR uint8_t *)malloc(bch->sectsize);
+ bch->buffer = (FAR uint8_t *)kmalloc(bch->sectsize);
if (!bch->buffer)
{
fdbg("Failed to allocate sector buffer\n");
@@ -153,6 +154,6 @@ int bchlib_setup(const char *blkdev, bool readonly, FAR void **handle)
return OK;
errout_with_bch:
- free(bch);
+ kfree(bch);
return ret;
}
diff --git a/nuttx/drivers/bch/bchlib_teardown.c b/nuttx/drivers/bch/bchlib_teardown.c
index 3b97ff167..e2084125c 100644
--- a/nuttx/drivers/bch/bchlib_teardown.c
+++ b/nuttx/drivers/bch/bchlib_teardown.c
@@ -1,7 +1,7 @@
/****************************************************************************
* drivers/bch/bchlib_teardown.c
*
- * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -44,6 +44,7 @@
#include <assert.h>
#include <debug.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/fs.h>
#include "bch_internal.h"
@@ -102,11 +103,11 @@ int bchlib_teardown(FAR void *handle)
if (bch->buffer)
{
- free(bch->buffer);
+ kfree(bch->buffer);
}
sem_destroy(&bch->sem);
- free(bch);
+ kfree(bch);
return OK;
}
diff --git a/nuttx/drivers/i2c/st_lis331dl.c b/nuttx/drivers/i2c/st_lis331dl.c
index ca2646484..7d5cdc4a2 100644
--- a/nuttx/drivers/i2c/st_lis331dl.c
+++ b/nuttx/drivers/i2c/st_lis331dl.c
@@ -46,6 +46,7 @@
#include <errno.h>
#include <stdio.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/i2c/st_lis331dl.h>
/************************************************************************************
@@ -152,7 +153,7 @@ struct st_lis331dl_dev_s * st_lis331dl_init(struct i2c_dev_s * i2c, uint16_t add
ASSERT(i2c);
ASSERT(address);
- if ( (dev = malloc( sizeof(struct st_lis331dl_dev_s) )) == NULL )
+ if ( (dev = kmalloc( sizeof(struct st_lis331dl_dev_s) )) == NULL )
return NULL;
memset(dev, 0, sizeof(struct st_lis331dl_dev_s));
@@ -189,7 +190,7 @@ struct st_lis331dl_dev_s * st_lis331dl_init(struct i2c_dev_s * i2c, uint16_t add
}
/* Error exit */
- free(dev);
+ kfree(dev);
errno = retval;
return NULL;
}
@@ -200,7 +201,7 @@ int st_lis331dl_deinit(struct st_lis331dl_dev_s * dev)
ASSERT(dev);
st_lis331dl_powerdown(dev);
- free(dev);
+ kfree(dev);
return OK;
}
diff --git a/nuttx/drivers/loop.c b/nuttx/drivers/loop.c
index dffa6e078..77cb9daf6 100644
--- a/nuttx/drivers/loop.c
+++ b/nuttx/drivers/loop.c
@@ -1,7 +1,7 @@
/****************************************************************************
* drivers/loop.c
*
- * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -56,6 +56,7 @@
#include <debug.h>
#include <errno.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/fs.h>
/****************************************************************************
@@ -377,7 +378,7 @@ int losetup(const char *devname, const char *filename, uint16_t sectsize,
/* Allocate a loop device structure */
- dev = (FAR struct loop_struct_s *)zalloc(sizeof(struct loop_struct_s));
+ dev = (FAR struct loop_struct_s *)kzalloc(sizeof(struct loop_struct_s));
if (!dev)
{
return -ENOMEM;
@@ -437,7 +438,7 @@ int losetup(const char *devname, const char *filename, uint16_t sectsize,
errout_with_fd:
close(dev->fd);
errout_with_dev:
- free(dev);
+ kfree(dev);
return ret;
}
@@ -500,6 +501,6 @@ int loteardown(const char *devname)
(void)close(dev->fd);
}
- free(dev);
+ kfree(dev);
return ret;
}
diff --git a/nuttx/drivers/mmcsd/mmcsd_sdio.c b/nuttx/drivers/mmcsd/mmcsd_sdio.c
index 3fd7b0847..28bbe08a3 100644
--- a/nuttx/drivers/mmcsd/mmcsd_sdio.c
+++ b/nuttx/drivers/mmcsd/mmcsd_sdio.c
@@ -52,6 +52,7 @@
#include <debug.h>
#include <errno.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/fs.h>
#include <nuttx/ioctl.h>
#include <nuttx/clock.h>
@@ -2891,7 +2892,7 @@ static void mmcsd_hwuninitialize(FAR struct mmcsd_state_s *priv)
{
mmcsd_removed(priv);
SDIO_RESET(priv->dev);
- free(priv);
+ kfree(priv);
}
}
@@ -2932,7 +2933,7 @@ int mmcsd_slotinitialize(int minor, FAR struct sdio_dev_s *dev)
/* Allocate a MMC/SD state structure */
- priv = (FAR struct mmcsd_state_s *)malloc(sizeof(struct mmcsd_state_s));
+ priv = (FAR struct mmcsd_state_s *)kmalloc(sizeof(struct mmcsd_state_s));
if (priv)
{
/* Initialize the MMC/SD state structure */
@@ -3010,6 +3011,6 @@ errout_with_hwinit:
#endif
mmcsd_hwuninitialize(priv);
errout_with_alloc:
- free(priv);
+ kfree(priv);
return ret;
}
diff --git a/nuttx/drivers/mtd/at45db.c b/nuttx/drivers/mtd/at45db.c
index 201fee0d6..6ca2b12bc 100644
--- a/nuttx/drivers/mtd/at45db.c
+++ b/nuttx/drivers/mtd/at45db.c
@@ -2,7 +2,7 @@
* drivers/mtd/at45db.c
* Driver for SPI-based AT45DB161D (16Mbit)
*
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -59,6 +59,7 @@
#include <errno.h>
#include <debug.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/arch.h>
#include <nuttx/ioctl.h>
#include <nuttx/spi.h>
@@ -826,7 +827,7 @@ FAR struct mtd_dev_s *at45db_initialize(FAR struct spi_dev_s *spi)
* to be extended to handle multiple FLASH parts on the same SPI bus.
*/
- priv = (FAR struct at45db_dev_s *)malloc(sizeof(struct at45db_dev_s));
+ priv = (FAR struct at45db_dev_s *)kmalloc(sizeof(struct at45db_dev_s));
if (priv)
{
/* Initialize the allocated structure */
@@ -893,6 +894,6 @@ FAR struct mtd_dev_s *at45db_initialize(FAR struct spi_dev_s *spi)
errout:
at45db_unlock(priv);
- free(priv);
+ kfree(priv);
return NULL;
}
diff --git a/nuttx/drivers/mtd/ftl.c b/nuttx/drivers/mtd/ftl.c
index 40f208f56..2aaff1b37 100755
--- a/nuttx/drivers/mtd/ftl.c
+++ b/nuttx/drivers/mtd/ftl.c
@@ -49,6 +49,7 @@
#include <debug.h>
#include <errno.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/fs.h>
#include <nuttx/ioctl.h>
#include <nuttx/mtd.h>
@@ -468,7 +469,7 @@ int ftl_initialize(int minor, uint8_t *buffer, FAR struct mtd_dev_s *mtd)
/* Allocate a ramdisk device structure */
- dev = (struct ftl_struct_s *)malloc(sizeof(struct ftl_struct_s));
+ dev = (struct ftl_struct_s *)kmalloc(sizeof(struct ftl_struct_s));
if (dev)
{
/* Initialize the ramdisk device structure */
@@ -484,18 +485,18 @@ int ftl_initialize(int minor, uint8_t *buffer, FAR struct mtd_dev_s *mtd)
if (ret < 0)
{
fdbg("MTD ioctl(MTDIOC_GEOMETRY) failed: %d\n", ret);
- free(dev);
+ kfree(dev);
return ret;
}
/* Allocate one, in-memory erase block buffer */
#ifdef CONFIG_FS_WRITABLE
- dev->eblock = (FAR uint8_t *)malloc(dev->geo.erasesize);
+ dev->eblock = (FAR uint8_t *)kmalloc(dev->geo.erasesize);
if (!dev->eblock)
{
fdbg("Failed to allocate an erase block buffer\n");
- free(dev);
+ kfree(dev);
return -ENOMEM;
}
#endif
@@ -525,7 +526,7 @@ int ftl_initialize(int minor, uint8_t *buffer, FAR struct mtd_dev_s *mtd)
if (ret < 0)
{
fdbg("rwb_initialize failed: %d\n", ret);
- free(dev);
+ kfree(dev);
return ret;
}
#endif
@@ -540,7 +541,7 @@ int ftl_initialize(int minor, uint8_t *buffer, FAR struct mtd_dev_s *mtd)
if (ret < 0)
{
fdbg("register_blockdriver failed: %d\n", -ret);
- free(dev);
+ kfree(dev);
}
}
return ret;
diff --git a/nuttx/drivers/mtd/m25px.c b/nuttx/drivers/mtd/m25px.c
index 18b9aea02..474006c7f 100644
--- a/nuttx/drivers/mtd/m25px.c
+++ b/nuttx/drivers/mtd/m25px.c
@@ -2,7 +2,7 @@
* drivers/mtd/m25px.c
* Driver for SPI-based M25P1 (128Kbit), M25P64 (64Mbit), and M25P128 (128Mbit) FLASH
*
- * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -47,6 +47,7 @@
#include <errno.h>
#include <debug.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/ioctl.h>
#include <nuttx/spi.h>
#include <nuttx/mtd.h>
@@ -673,7 +674,7 @@ FAR struct mtd_dev_s *m25p_initialize(FAR struct spi_dev_s *dev)
* to be extended to handle multiple FLASH parts on the same SPI bus.
*/
- priv = (FAR struct m25p_dev_s *)malloc(sizeof(struct m25p_dev_s));
+ priv = (FAR struct m25p_dev_s *)kmalloc(sizeof(struct m25p_dev_s));
if (priv)
{
/* Initialize the allocated structure */
@@ -697,7 +698,7 @@ FAR struct mtd_dev_s *m25p_initialize(FAR struct spi_dev_s *dev)
/* Unrecognized! Discard all of that work we just did and return NULL */
fdbg("Unrecognized\n");
- free(priv);
+ kfree(priv);
priv = NULL;
}
}
diff --git a/nuttx/drivers/mtd/ramtron.c b/nuttx/drivers/mtd/ramtron.c
index ab27a0dc2..5739b3b05 100755
--- a/nuttx/drivers/mtd/ramtron.c
+++ b/nuttx/drivers/mtd/ramtron.c
@@ -67,6 +67,7 @@
#include <debug.h>
#include <assert.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/ioctl.h>
#include <nuttx/spi.h>
#include <nuttx/mtd.h>
@@ -635,7 +636,7 @@ FAR struct mtd_dev_s *ramtron_initialize(FAR struct spi_dev_s *dev)
* to be extended to handle multiple FLASH parts on the same SPI bus.
*/
- priv = (FAR struct ramtron_dev_s *)malloc(sizeof(struct ramtron_dev_s));
+ priv = (FAR struct ramtron_dev_s *)kmalloc(sizeof(struct ramtron_dev_s));
if (priv)
{
/* Initialize the allocated structure */
@@ -656,7 +657,7 @@ FAR struct mtd_dev_s *ramtron_initialize(FAR struct spi_dev_s *dev)
if (ramtron_readid(priv) != OK)
{
/* Unrecognized! Discard all of that work we just did and return NULL */
- free(priv);
+ kfree(priv);
priv = NULL;
}
}
diff --git a/nuttx/drivers/net/slip.c b/nuttx/drivers/net/slip.c
index 725d7f846..a1880db8e 100644
--- a/nuttx/drivers/net/slip.c
+++ b/nuttx/drivers/net/slip.c
@@ -186,7 +186,7 @@ struct slip_driver_s
****************************************************************************/
/* We really should get rid of CONFIG_SLIP_NINTERFACES and, instead,
- * malloc() new interface instances as needed.
+ * kmalloc() new interface instances as needed.
*/
static struct slip_driver_s g_slip[CONFIG_SLIP_NINTERFACES];
diff --git a/nuttx/drivers/pipes/pipe_common.c b/nuttx/drivers/pipes/pipe_common.c
index a6af41fe1..52077beed 100644
--- a/nuttx/drivers/pipes/pipe_common.c
+++ b/nuttx/drivers/pipes/pipe_common.c
@@ -52,6 +52,7 @@
#include <assert.h>
#include <debug.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/fs.h>
#if CONFIG_DEBUG
# include <nuttx/arch.h>
@@ -150,7 +151,7 @@ FAR struct pipe_dev_s *pipecommon_allocdev(void)
/* Allocate a private structure to manage the pipe */
- dev = (struct pipe_dev_s *)malloc(sizeof(struct pipe_dev_s));
+ dev = (struct pipe_dev_s *)kmalloc(sizeof(struct pipe_dev_s));
if (dev)
{
/* Initialize the private structure */
@@ -172,7 +173,7 @@ void pipecommon_freedev(FAR struct pipe_dev_s *dev)
sem_destroy(&dev->d_bfsem);
sem_destroy(&dev->d_rdsem);
sem_destroy(&dev->d_wrsem);
- free(dev);
+ kfree(dev);
}
/****************************************************************************
@@ -209,7 +210,7 @@ int pipecommon_open(FAR struct file *filep)
if (dev->d_refs == 0)
{
- dev->d_buffer = (uint8_t*)malloc(CONFIG_DEV_PIPE_SIZE);
+ dev->d_buffer = (uint8_t*)kmalloc(CONFIG_DEV_PIPE_SIZE);
if (!dev->d_buffer)
{
(void)sem_post(&dev->d_bfsem);
@@ -330,7 +331,7 @@ int pipecommon_close(FAR struct file *filep)
{
/* Yes... deallocate the buffer */
- free(dev->d_buffer);
+ kfree(dev->d_buffer);
dev->d_buffer = NULL;
/* And reset all counts and indices */
diff --git a/nuttx/drivers/ramdisk.c b/nuttx/drivers/ramdisk.c
index e424459d4..23b07378d 100644
--- a/nuttx/drivers/ramdisk.c
+++ b/nuttx/drivers/ramdisk.c
@@ -1,7 +1,7 @@
/****************************************************************************
* drivers/ramdisk.c
*
- * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -49,6 +49,7 @@
#include <debug.h>
#include <errno.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/fs.h>
#include <nuttx/ramdisk.h>
@@ -305,7 +306,7 @@ int romdisk_register(int minor, uint8_t *buffer, uint32_t nsectors,
/* Allocate a ramdisk device structure */
- dev = (struct rd_struct_s *)malloc(sizeof(struct rd_struct_s));
+ dev = (struct rd_struct_s *)kmalloc(sizeof(struct rd_struct_s));
if (dev)
{
/* Initialize the ramdisk device structure */
@@ -327,7 +328,7 @@ int romdisk_register(int minor, uint8_t *buffer, uint32_t nsectors,
if (ret < 0)
{
fdbg("register_blockdriver failed: %d\n", -ret);
- free(dev);
+ kfree(dev);
}
}
return ret;
diff --git a/nuttx/drivers/rwbuffer.c b/nuttx/drivers/rwbuffer.c
index 91ab7785f..5f3dbe98c 100644
--- a/nuttx/drivers/rwbuffer.c
+++ b/nuttx/drivers/rwbuffer.c
@@ -1,7 +1,7 @@
/****************************************************************************
* drivers/rwbuffer.c
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -50,6 +50,7 @@
#include <errno.h>
#include <debug.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/wqueue.h>
#include <nuttx/rwbuffer.h>
@@ -425,10 +426,10 @@ int rwb_initialize(FAR struct rwbuffer_s *rwb)
if (rwb->wrmaxblocks > 0)
{
allocsize = rwb->wrmaxblocks * rwb->blocksize;
- rwb->wrbuffer = malloc(allocsize);
+ rwb->wrbuffer = kmalloc(allocsize);
if (!rwb->wrbuffer)
{
- fdbg("Write buffer malloc(%d) failed\n", allocsizee);
+ fdbg("Write buffer kmalloc(%d) failed\n", allocsizee);
return -ENOMEM;
}
}
@@ -453,10 +454,10 @@ int rwb_initialize(FAR struct rwbuffer_s *rwb)
if (rwb->rhmaxblocks > 0)
{
allocsize = rwb->rhmaxblocks * rwb->blocksize;
- rwb->rhbuffer = malloc(allocsize);
+ rwb->rhbuffer = kmalloc(allocsize);
if (!rwb->rhbuffer)
{
- fdbg("Read-ahead buffer malloc(%d) failed\n", allocsize);
+ fdbg("Read-ahead buffer kmalloc(%d) failed\n", allocsize);
return -ENOMEM;
}
}
@@ -477,7 +478,7 @@ void rwb_uninitialize(FAR struct rwbuffer_s *rwb)
sem_destroy(&rwb->wrsem);
if (rwb->wrbuffer)
{
- free(rwb->wrbuffer);
+ kfree(rwb->wrbuffer);
}
#endif
@@ -485,7 +486,7 @@ void rwb_uninitialize(FAR struct rwbuffer_s *rwb)
sem_destroy(&rwb->rhsem);
if (rwb->rhbuffer)
{
- free(rwb->rhbuffer);
+ kfree(rwb->rhbuffer);
}
#endif
}
diff --git a/nuttx/drivers/usbdev/usbdev_serial.c b/nuttx/drivers/usbdev/usbdev_serial.c
index 22b689e16..25753cb1e 100644
--- a/nuttx/drivers/usbdev/usbdev_serial.c
+++ b/nuttx/drivers/usbdev/usbdev_serial.c
@@ -1,7 +1,7 @@
/****************************************************************************
* drivers/usbdev/usbdev_serial.c
*
- * Copyright (C) 2008-2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008-2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* This logic emulates the Prolific PL2303 serial/USB converter
@@ -53,6 +53,7 @@
#include <queue.h>
#include <debug.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/arch.h>
#include <nuttx/serial.h>
#include <nuttx/usb/usb.h>
@@ -1300,9 +1301,9 @@ static int usbclass_bind(FAR struct usbdev_s *dev, FAR struct usbdevclass_driver
/* Pre-allocate all endpoints... the endpoints will not be functional
* until the SET CONFIGURATION request is processed in usbclass_setconfig.
- * This is done here because there may be calls to malloc and the SET
+ * This is done here because there may be calls to kmalloc and the SET
* CONFIGURATION processing probably occurrs within interrupt handling
- * logic where malloc calls will fail.
+ * logic where kmalloc calls will fail.
*/
/* Pre-allocate the IN interrupt endpoint */
@@ -2163,7 +2164,7 @@ int usbdev_serialinitialize(int minor)
/* Allocate the structures needed */
- alloc = (FAR struct usbser_alloc_s*)malloc(sizeof(struct usbser_alloc_s));
+ alloc = (FAR struct usbser_alloc_s*)kmalloc(sizeof(struct usbser_alloc_s));
if (!alloc)
{
usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_ALLOCDEVSTRUCT), 0);
@@ -2244,6 +2245,6 @@ int usbdev_serialinitialize(int minor)
errout_with_class:
usbdev_unregister(&drvr->drvr);
errout_with_alloc:
- free(alloc);
+ kfree(alloc);
return ret;
}
diff --git a/nuttx/drivers/usbdev/usbdev_storage.c b/nuttx/drivers/usbdev/usbdev_storage.c
index fc61670d2..4f2ffcc6e 100644
--- a/nuttx/drivers/usbdev/usbdev_storage.c
+++ b/nuttx/drivers/usbdev/usbdev_storage.c
@@ -1,7 +1,7 @@
/****************************************************************************
* drivers/usbdev/usbdev_storage.c
*
- * Copyright (C) 2008-2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008-2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Mass storage class device. Bulk-only with SCSI subclass.
@@ -72,6 +72,7 @@
#include <queue.h>
#include <debug.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/arch.h>
#include <nuttx/fs.h>
#include <nuttx/usb/usb.h>
@@ -531,9 +532,9 @@ static int usbstrg_bind(FAR struct usbdev_s *dev, FAR struct usbdevclass_driver_
/* Pre-allocate all endpoints... the endpoints will not be functional
* until the SET CONFIGURATION request is processed in usbstrg_setconfig.
- * This is done here because there may be calls to malloc and the SET
+ * This is done here because there may be calls to kmalloc and the SET
* CONFIGURATION processing probably occurrs within interrupt handling
- * logic where malloc calls will fail.
+ * logic where kmalloc calls will fail.
*/
/* Pre-allocate the IN bulk endpoint */
@@ -1477,7 +1478,7 @@ int usbstrg_configure(unsigned int nluns, void **handle)
/* Allocate the structures needed */
- alloc = (FAR struct usbstrg_alloc_s*)malloc(sizeof(struct usbstrg_alloc_s));
+ alloc = (FAR struct usbstrg_alloc_s*)kmalloc(sizeof(struct usbstrg_alloc_s));
if (!alloc)
{
usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_ALLOCDEVSTRUCT), 0);
@@ -1497,7 +1498,7 @@ int usbstrg_configure(unsigned int nluns, void **handle)
/* Allocate the LUN table */
- priv->luntab = (struct usbstrg_lun_s*)malloc(priv->nluns*sizeof(struct usbstrg_lun_s));
+ priv->luntab = (struct usbstrg_lun_s*)kmalloc(priv->nluns*sizeof(struct usbstrg_lun_s));
if (!priv->luntab)
{
ret = -ENOMEM;
@@ -1638,7 +1639,7 @@ int usbstrg_bindlun(FAR void *handle, FAR const char *drvrpath,
if (!priv->iobuffer)
{
- priv->iobuffer = (uint8_t*)malloc(geo.geo_sectorsize);
+ priv->iobuffer = (uint8_t*)kmalloc(geo.geo_sectorsize);
if (!priv->iobuffer)
{
usbtrace(TRACE_CLSERROR(USBSTRG_TRACEERR_ALLOCIOBUFFER), geo.geo_sectorsize);
@@ -1891,13 +1892,13 @@ void usbstrg_uninitialize(FAR void *handle)
{
usbstrg_lununinitialize(&priv->luntab[i]);
}
- free(priv->luntab);
+ kfree(priv->luntab);
/* Release the I/O buffer */
if (priv->iobuffer)
{
- free(priv->iobuffer);
+ kfree(priv->iobuffer);
}
/* Uninitialize and release the driver structure */
@@ -1905,5 +1906,5 @@ void usbstrg_uninitialize(FAR void *handle)
pthread_mutex_destroy(&priv->mutex);
pthread_cond_destroy(&priv->cond);
- free(priv);
+ kfree(priv);
}
diff --git a/nuttx/drivers/usbhost/usbhost_hidkbd.c b/nuttx/drivers/usbhost/usbhost_hidkbd.c
index 74adff7ba..ef880ea75 100644
--- a/nuttx/drivers/usbhost/usbhost_hidkbd.c
+++ b/nuttx/drivers/usbhost/usbhost_hidkbd.c
@@ -53,6 +53,7 @@
#include <errno.h>
#include <debug.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/fs.h>
#include <nuttx/arch.h>
#include <nuttx/wqueue.h>
@@ -490,7 +491,7 @@ static inline FAR struct usbhost_state_s *usbhost_allocclass(void)
FAR struct usbhost_state_s *priv;
DEBUGASSERT(!up_interrupt_context());
- priv = (FAR struct usbhost_state_s *)malloc(sizeof(struct usbhost_state_s));
+ priv = (FAR struct usbhost_state_s *)kmalloc(sizeof(struct usbhost_state_s));
uvdbg("Allocated: %p\n", priv);;
return priv;
}
@@ -513,12 +514,10 @@ static inline void usbhost_freeclass(FAR struct usbhost_state_s *class)
{
DEBUGASSERT(class != NULL);
- /* Free the class instance (calling sched_free() in case we are executing
- * from an interrupt handler.
- */
+ /* Free the class instance. */
uvdbg("Freeing: %p\n", class);;
- free(class);
+ kfree(class);
}
/****************************************************************************
diff --git a/nuttx/drivers/usbhost/usbhost_skeleton.c b/nuttx/drivers/usbhost/usbhost_skeleton.c
index efb7a58ba..c33dda586 100644
--- a/nuttx/drivers/usbhost/usbhost_skeleton.c
+++ b/nuttx/drivers/usbhost/usbhost_skeleton.c
@@ -47,6 +47,7 @@
#include <errno.h>
#include <debug.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/fs.h>
#include <nuttx/arch.h>
#include <nuttx/wqueue.h>
@@ -252,7 +253,7 @@ static inline FAR struct usbhost_state_s *usbhost_allocclass(void)
FAR struct usbhost_state_s *priv;
DEBUGASSERT(!up_interrupt_context());
- priv = (FAR struct usbhost_state_s *)malloc(sizeof(struct usbhost_state_s));
+ priv = (FAR struct usbhost_state_s *)kmalloc(sizeof(struct usbhost_state_s));
uvdbg("Allocated: %p\n", priv);;
return priv;
}
@@ -275,12 +276,12 @@ static inline void usbhost_freeclass(FAR struct usbhost_state_s *class)
{
DEBUGASSERT(class != NULL);
- /* Free the class instance (calling sched_free() in case we are executing
- * from an interrupt handler.
+ /* Free the class instance (perhaps calling sched_free() in case we are
+ * executing from an interrupt handler.
*/
uvdbg("Freeing: %p\n", class);;
- free(class);
+ kfree(class);
}
/****************************************************************************
diff --git a/nuttx/drivers/usbhost/usbhost_storage.c b/nuttx/drivers/usbhost/usbhost_storage.c
index 31f6c2aea..118758a60 100644
--- a/nuttx/drivers/usbhost/usbhost_storage.c
+++ b/nuttx/drivers/usbhost/usbhost_storage.c
@@ -1,7 +1,7 @@
/****************************************************************************
* drivers/usbhost/usbhost_storage.c
*
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -47,6 +47,7 @@
#include <errno.h>
#include <debug.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/fs.h>
#include <nuttx/arch.h>
#include <nuttx/wqueue.h>
@@ -72,7 +73,7 @@
#endif
/* If the create() method is called by the USB host device driver from an
- * interrupt handler, then it will be unable to call malloc() in order to
+ * interrupt handler, then it will be unable to call kmalloc() in order to
* allocate a new class instance. If the create() method is called from the
* interrupt level, then class instances must be pre-allocated.
*/
@@ -378,11 +379,11 @@ static inline FAR struct usbhost_state_s *usbhost_allocclass(void)
FAR struct usbhost_state_s *priv;
/* We are not executing from an interrupt handler so we can just call
- * malloc() to get memory for the class instance.
+ * kmalloc() to get memory for the class instance.
*/
DEBUGASSERT(!up_interrupt_context());
- priv = (FAR struct usbhost_state_s *)malloc(sizeof(struct usbhost_state_s));
+ priv = (FAR struct usbhost_state_s *)kmalloc(sizeof(struct usbhost_state_s));
uvdbg("Allocated: %p\n", priv);;
return priv;
}
@@ -427,7 +428,7 @@ static inline void usbhost_freeclass(FAR struct usbhost_state_s *class)
*/
uvdbg("Freeing: %p\n", class);;
- free(class);
+ kfree(class);
}
#endif