summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-09-11 20:33:58 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-09-11 20:33:58 +0000
commit63240531781806cb440108ebd5ad0c3dc62510d3 (patch)
tree386d184c161ad982f82fe673bdf69319f84cca6b /nuttx
parent205242a575697630d073edc02a6341e6d9be22a6 (diff)
downloadpx4-nuttx-63240531781806cb440108ebd5ad0c3dc62510d3.tar.gz
px4-nuttx-63240531781806cb440108ebd5ad0c3dc62510d3.tar.bz2
px4-nuttx-63240531781806cb440108ebd5ad0c3dc62510d3.zip
Update to granule allocator; Update to ENC28j60 driver
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5130 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/Documentation/NuttxPortingGuide.html59
-rw-r--r--nuttx/configs/README.txt24
-rw-r--r--nuttx/configs/fire-stm32v2/nsh/defconfig1
-rw-r--r--nuttx/configs/shenzhou/nsh/defconfig86
-rw-r--r--nuttx/drivers/net/enc28j60.c55
-rw-r--r--nuttx/include/nuttx/gran.h8
-rw-r--r--nuttx/mm/Kconfig30
-rw-r--r--nuttx/mm/Makefile7
-rw-r--r--nuttx/mm/mm_gran.h26
-rw-r--r--nuttx/mm/mm_granalloc.c20
-rw-r--r--nuttx/mm/mm_granfree.c35
-rw-r--r--nuttx/mm/mm_graninit.c11
12 files changed, 221 insertions, 141 deletions
diff --git a/nuttx/Documentation/NuttxPortingGuide.html b/nuttx/Documentation/NuttxPortingGuide.html
index 0e169d60d..f2c89dcbe 100644
--- a/nuttx/Documentation/NuttxPortingGuide.html
+++ b/nuttx/Documentation/NuttxPortingGuide.html
@@ -3907,22 +3907,9 @@ build
</li>
</ul>
-<h2>General OS setup</h2>
+<h2>Memory Management</h2>
<ul>
<li>
- <code>CONFIG_ARCH_LOWPUTC</code>: architecture supports low-level, boot
- time console output
- </li>
- <li>
- <code>CONFIG_NUTTX_KERNEL</code>:
- With most MCUs, NuttX is built as a flat, single executable image
- containing the NuttX RTOS along with all application code.
- The RTOS code and the application run in the same address space and at the same kernel-mode privileges.
- If this option is selected, NuttX will be built separately as a monolithic, kernel-mode module and the applications
- can be added as a separately built, user-mode module.
- In this a system call layer will be built to support the user- to kernel-mode interface to the RTOS.
- </li>
- <li>
<code>CONFIG_MM_REGIONS</code>: If the architecture includes multiple
regions of memory to allocate from, this specifies the
number of memory regions that the memory manager must
@@ -3940,6 +3927,50 @@ build
smaller, 16-bit-based allocation overhead.
</li>
<li>
+ <code>CONFIG_HEAP2_BASE</code> and <code>CONFIG_HEAP2_SIZE</code>:
+ Some architectures use these settings to specify the size of
+ a second heap region.
+ <li>
+ </li>
+ <code>CONFIG_GRAN</code>:
+ Enable granual allocator support. Allocations will be aligned to the
+ granule size; allocations will be in units of the granule size.
+ Larger granules will give better performance and less overhead but
+ more losses of memory due to alignment and quantization waste.
+ NOTE: The current implementation also restricts the maximum
+ allocation size to 32 granaules. That restriction could be
+ eliminated with some additional coding effort.
+ <li>
+ </li>
+ <code>CONFIG_GRAN_SINGLE</code>:
+ Select if there is only one instance of the granule allocator (i.e.,
+ gran_initialize will be called only once. In this case, (1) there
+ are a few optimizations that can can be done and (2) the GRAN_HANDLE
+ is not needed.
+ </li>
+ <li>
+ <code>CONFIG_DEBUG_GRAM</code>:
+ Just like <code>CONFIG_DEBUG_MM</code>, but only generates ouput from the gran
+ allocation logic.
+ </li>
+</ul>
+
+<h2>General OS setup</h2>
+<ul>
+ <li>
+ <code>CONFIG_ARCH_LOWPUTC</code>: architecture supports low-level, boot
+ time console output
+ </li>
+ <li>
+ <code>CONFIG_NUTTX_KERNEL</code>:
+ With most MCUs, NuttX is built as a flat, single executable image
+ containing the NuttX RTOS along with all application code.
+ The RTOS code and the application run in the same address space and at the same kernel-mode privileges.
+ If this option is selected, NuttX will be built separately as a monolithic, kernel-mode module and the applications
+ can be added as a separately built, user-mode module.
+ In this a system call layer will be built to support the user- to kernel-mode interface to the RTOS.
+ </li>
+ <li>
<code>CONFIG_MSEC_PER_TICK</code>: The default system timer is 100Hz
or <code>MSEC_PER_TICK</code>=10. This setting may be defined to inform NuttX
that the processor hardware is providing system timer interrupts at some interrupt
diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt
index b51b87bec..b3d0e91f5 100644
--- a/nuttx/configs/README.txt
+++ b/nuttx/configs/README.txt
@@ -270,8 +270,6 @@ defconfig -- This is a configuration file similar to the Linux
CONFIG_DEBUG_GRAPHICS - enable NX graphics debug output
(disabled by default)
- CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot
- time console output
CONFIG_MM_REGIONS - If the architecture includes multiple
regions of memory to allocate from, this specifies the
number of memory regions that the memory manager must
@@ -285,6 +283,28 @@ defconfig -- This is a configuration file similar to the Linux
of size less than or equal to 64Kb. In this case, CONFIG_MM_SMALL
can be defined so that those MCUs will also benefit from the
smaller, 16-bit-based allocation overhead.
+ CONFIG_HEAP2_BASE and CONFIG_HEAP2_SIZE
+ Some architectures use these settings to specify the size of
+ a second heap region.
+ CONFIG_GRAN
+ Enable granual allocator support. Allocations will be aligned to the
+ granule size; allocations will be in units of the granule size.
+ Larger granules will give better performance and less overhead but
+ more losses of memory due to alignment and quantization waste.
+ NOTE: The current implementation also restricts the maximum
+ allocation size to 32 granaules. That restriction could be
+ eliminated with some additional coding effort.
+ CONFIG_GRAN_SINGLE
+ Select if there is only one instance of the granule allocator (i.e.,
+ gran_initialize will be called only once. In this case, (1) there
+ are a few optimizations that can can be done and (2) the GRAN_HANDLE
+ is not needed.
+ CONFIG_DEBUG_GRAM
+ Just like CONFIG_DEBUG_MM, but only generates ouput from the gran
+ allocation logic.
+
+ CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot
+ time console output
CONFIG_MSEC_PER_TICK - The default system timer is 100Hz
or MSEC_PER_TICK=10. This setting may be defined to
inform NuttX that the processor hardware is providing
diff --git a/nuttx/configs/fire-stm32v2/nsh/defconfig b/nuttx/configs/fire-stm32v2/nsh/defconfig
index ef5fcbf40..fda34debe 100644
--- a/nuttx/configs/fire-stm32v2/nsh/defconfig
+++ b/nuttx/configs/fire-stm32v2/nsh/defconfig
@@ -481,6 +481,7 @@ CONFIG_FAT_MAXFNAME=32
#
# CONFIG_MM_SMALL is not set
CONFIG_MM_REGIONS=1
+# CONFIG_GRAN is not set
#
# Library Routines
diff --git a/nuttx/configs/shenzhou/nsh/defconfig b/nuttx/configs/shenzhou/nsh/defconfig
index 7aa442e12..0c18b129f 100644
--- a/nuttx/configs/shenzhou/nsh/defconfig
+++ b/nuttx/configs/shenzhou/nsh/defconfig
@@ -304,66 +304,22 @@ CONFIG_DEV_NULL=y
# CONFIG_DEV_ZERO is not set
# CONFIG_LOOP is not set
# CONFIG_RAMDISK is not set
-
-#
-# CAN Driver Options
-#
# CONFIG_CAN is not set
-
-#
-# PWM Driver Options
-#
# CONFIG_PWM is not set
-
-#
-# I2C Driver Options
-#
# CONFIG_I2C is not set
-
-#
-# SPI Driver Options
-#
CONFIG_SPI=y
# CONFIG_SPI_OWNBUS is not set
CONFIG_SPI_EXCHANGE=y
CONFIG_SPI_CMDDATA=y
-
-#
-# RTC Driver Options
-#
CONFIG_RTC=y
# CONFIG_RTC_DATETIME is not set
# CONFIG_RTC_HIRES is not set
# CONFIG_RTC_ALARM is not set
-
-#
-# Watchdog Driver Options
-#
# CONFIG_WATCHDOG is not set
-
-#
-# Analog Driver Options
-#
# CONFIG_ANALOG is not set
-
-#
-# Block-to-Character Driver Support
-#
# CONFIG_BCH is not set
-
-#
-# Input device Driver Options
-#
# CONFIG_INPUT is not set
-
-#
-# LCD Driver Options
-#
# CONFIG_LCD is not set
-
-#
-# MMCSD Driver Options
-#
CONFIG_MMCSD=y
CONFIG_MMCSD_NSLOTS=1
# CONFIG_MMCSD_READONLY is not set
@@ -373,42 +329,14 @@ CONFIG_MMCSD_HAVECARDDETECT=y
CONFIG_MMCSD_SPI=y
CONFIG_MMCSD_SPICLOCK=12500000
# CONFIG_MMCSD_SDIO is not set
-
-#
-# I2C Driver Options
-#
# CONFIG_MTD is not set
-
-#
-# Network Device Driver Options
-#
# CONFIG_NETDEVICES is not set
# CONFIG_NET_SLIP is not set
-
-#
-# Pipe Options
-#
# CONFIG_PIPES is not set
-
-#
-# Power Management Options
-#
# CONFIG_PM is not set
# CONFIG_POWER is not set
-
-#
-# Sensor Driver Options
-#
# CONFIG_SENSORS is not set
-
-#
-# Osmocom-bb Sercomm Driver Options
-#
# CONFIG_SERCOMM_CONSOLE is not set
-
-#
-# Serial Driver Options
-#
CONFIG_SERIAL=y
# CONFIG_LOWLEVEL_CONSOLE is not set
# CONFIG_16550_UART is not set
@@ -427,20 +355,8 @@ CONFIG_USART2_BAUD=115200
CONFIG_USART2_BITS=8
CONFIG_USART2_PARITY=0
CONFIG_USART2_2STOP=0
-
-#
-# USB Device Driver Options
-#
# CONFIG_USBDEV is not set
-
-#
-# USB Host Driver Options
-#
# CONFIG_USBHOST is not set
-
-#
-# Wireless Device Driver Options
-#
# CONFIG_WIRELESS is not set
#
@@ -496,6 +412,7 @@ CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
CONFIG_FAT_MAXFNAME=32
# CONFIG_FS_FATTIME is not set
+# CONFIG_FAT_DMAMEMORY is not set
# CONFIG_FS_RAMMAP is not set
# CONFIG_NFS is not set
# CONFIG_FS_NXFFS is not set
@@ -511,6 +428,7 @@ CONFIG_FAT_MAXFNAME=32
#
# CONFIG_MM_SMALL is not set
CONFIG_MM_REGIONS=1
+# CONFIG_GRAN is not set
#
# Library Routines
diff --git a/nuttx/drivers/net/enc28j60.c b/nuttx/drivers/net/enc28j60.c
index eee9ff6f0..a2f3d5871 100644
--- a/nuttx/drivers/net/enc28j60.c
+++ b/nuttx/drivers/net/enc28j60.c
@@ -164,6 +164,15 @@
* Private Types
****************************************************************************/
+/* The state of the interface */
+
+enum enc_state_e
+{
+ ENCSTATE_UNIT = 0, /* The interface is in an unknown state */
+ ENCSTATE_DOWN, /* The interface is down */
+ ENCSTATE_UP /* The interface is up */
+};
+
/* The enc_driver_s encapsulates all state information for a single hardware
* interface
*/
@@ -172,7 +181,7 @@ struct enc_driver_s
{
/* Device control */
- bool bifup; /* true:ifup false:ifdown */
+ uint8_t ifstate; /* Interface state: See ENCSTATE_* */
uint8_t bank; /* Currently selected bank */
uint16_t nextpkt; /* Next packet address */
FAR const struct enc_lower_s *lower; /* Low-level MCU-specific support */
@@ -1656,7 +1665,7 @@ static int enc_ifup(struct uip_driver_s *dev)
* controller
*/
- priv->bifup = true;
+ priv->ifstate = ENCSTATE_UP;
priv->lower->enable(priv->lower);
}
@@ -1686,8 +1695,8 @@ static int enc_ifdown(struct uip_driver_s *dev)
int ret;
nlldbg("Taking down: %d.%d.%d.%d\n",
- dev->d_ipaddr & 0xff, (dev->d_ipaddr >> 8) & 0xff,
- (dev->d_ipaddr >> 16) & 0xff, dev->d_ipaddr >> 24 );
+ dev->d_ipaddr & 0xff, (dev->d_ipaddr >> 8) & 0xff,
+ (dev->d_ipaddr >> 16) & 0xff, dev->d_ipaddr >> 24 );
/* Disable the Ethernet interrupt */
@@ -1704,7 +1713,7 @@ static int enc_ifdown(struct uip_driver_s *dev)
ret = enc_reset(priv);
enc_pwrsave(priv);
- priv->bifup = false;
+ priv->ifstate = ENCSTATE_DOWN;
irqrestore(flags);
return ret;
}
@@ -1737,7 +1746,7 @@ static int enc_txavail(struct uip_driver_s *dev)
/* Ignore the notification if the interface is not yet up */
- if (priv->bifup)
+ if (priv->ifstate == ENCSTATE_UP)
{
/* Check if the hardware is ready to send another packet. The driver
* starts a transmission process by setting ECON1.TXRTS. When the packet is
@@ -2131,8 +2140,7 @@ static int enc_reset(FAR struct enc_driver_s *priv)
int enc_initialize(FAR struct spi_dev_s *spi,
FAR const struct enc_lower_s *lower, unsigned int devno)
{
- FAR struct enc_driver_s *priv ;
- int ret;
+ FAR struct enc_driver_s *priv;
DEBUGASSERT(devno < CONFIG_ENC28J60_NINTERFACES);
priv = &g_enc28j60[devno];
@@ -2156,29 +2164,28 @@ int enc_initialize(FAR struct spi_dev_s *spi,
priv->spi = spi; /* Save the SPI instance */
priv->lower = lower; /* Save the low-level MCU interface */
- /* Make sure that the interface is in the down state. NOTE: The MAC
- * address will not be set up until ifup. That gives the app time to set
- * the MAC address before bringing the interface up.
+ /* The interface should be in the down state. However, this function is called
+ * too early in initalization to perform the ENC28J60 reset in enc_ifdown. We
+ * are depending upon the fact that the application level logic will call enc_ifdown
+ * later to reset the ENC28J60. NOTE: The MAC address will not be set up until
+ * enc_ifup() is called. That gives the app time to set the MAC address before
+ * bringing the interface up.
*/
- ret = enc_ifdown(&priv->dev);
- if (ret == OK)
- {
- /* Attach the interrupt to the driver (but don't enable it yet) */
-
- if (lower->attach(lower, enc_interrupt))
- {
- /* We could not attach the ISR to the interrupt */
+ priv->ifstate = ENCSTATE_UNIT;
- ret = -EAGAIN;
- }
+ /* Attach the interrupt to the driver (but don't enable it yet) */
- /* Register the device with the OS so that socket IOCTLs can be performed */
+ if (lower->attach(lower, enc_interrupt))
+ {
+ /* We could not attach the ISR to the interrupt */
- (void)netdev_register(&priv->dev);
+ return -EAGAIN;
}
- return ret;
+ /* Register the device with the OS so that socket IOCTLs can be performed */
+
+ return netdev_register(&priv->dev);
}
/****************************************************************************
diff --git a/nuttx/include/nuttx/gran.h b/nuttx/include/nuttx/gran.h
index 2036a29a1..bb08f9b37 100644
--- a/nuttx/include/nuttx/gran.h
+++ b/nuttx/include/nuttx/gran.h
@@ -43,6 +43,11 @@
#include <nuttx/config.h>
+#include <sys/types.h>
+#include <stdint.h>
+
+#ifdef CONFIG_GRAN
+
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
@@ -52,6 +57,8 @@
* granule allocator (i.e., gran_initialize will be called only once.
* In this case, (1) there are a few optimizations that can can be done
* and (2) the GRAN_HANDLE is not needed.
+ * CONFIG_DEBUG_GRAN - Just like CONFIG_DEBUG_MM, but only generates ouput
+ * from the gran allocation logic.
*/
/****************************************************************************
@@ -158,4 +165,5 @@ EXTERN void gran_free(GRAN_HANDLE handle, FAR void *memory, size_t size);
}
#endif
+#endif /* CONFIG_GRAN */
#endif /* __INCLUDE_NUTTX_GRAN_H */
diff --git a/nuttx/mm/Kconfig b/nuttx/mm/Kconfig
index bf3540138..2e5bc95db 100644
--- a/nuttx/mm/Kconfig
+++ b/nuttx/mm/Kconfig
@@ -42,3 +42,33 @@ config HEAP2_SIZE
---help---
The size of the second heap region.
+config GRAN
+ bool "Enable Granule Allocator"
+ default n
+ ---help---
+ Enable granual allocator support. Allocations will be aligned to the
+ granule size; allocations will be in units of the granule size.
+ Larger granules will give better performance and less overhead but
+ more losses of memory due to alignment and quantization waste.
+
+ NOTE: The current implementation also restricts the maximum
+ allocation size to 32 granaules. That restriction could be
+ eliminated with some additional coding effort.
+
+config GRAN_SINGLE
+ bool "Single Granule Allocator"
+ default n
+ depends on GRAN
+ ---help---
+ Select if there is only one instance of the granule allocator (i.e.,
+ gran_initialize will be called only once. In this case, (1) there
+ are a few optimizations that can can be done and (2) the GRAN_HANDLE
+ is not needed.
+
+config DEBUG_GRAN
+ bool "Granule Allocator Debug"
+ default n
+ depends on GRAN && DEBUG
+ ---help---
+ Just like CONFIG_DEBUG_MM, but only generates ouput from the gran
+ allocation logic.
diff --git a/nuttx/mm/Makefile b/nuttx/mm/Makefile
index 7e6eb68a7..ef168f0db 100644
--- a/nuttx/mm/Makefile
+++ b/nuttx/mm/Makefile
@@ -36,10 +36,15 @@
-include $(TOPDIR)/Make.defs
ASRCS =
-AOBJS = $(ASRCS:.S=$(OBJEXT))
CSRCS = mm_initialize.c mm_sem.c mm_addfreechunk.c mm_size2ndx.c mm_shrinkchunk.c \
mm_malloc.c mm_zalloc.c mm_calloc.c mm_realloc.c \
mm_memalign.c mm_free.c mm_mallinfo.c
+
+ifeq ($(CONFIG_GRAN),y)
+CSRCS = mm_graninit.c mm_granalloc.c mm_granfree.c
+endif
+
+AOBJS = $(ASRCS:.S=$(OBJEXT))
COBJS = $(CSRCS:.c=$(OBJEXT))
SRCS = $(ASRCS) $(CSRCS)
diff --git a/nuttx/mm/mm_gran.h b/nuttx/mm/mm_gran.h
index 6f5f890ed..d8a334e29 100644
--- a/nuttx/mm/mm_gran.h
+++ b/nuttx/mm/mm_gran.h
@@ -42,17 +42,41 @@
#include <nuttx/config.h>
+#include <stdint.h>
+
#include <nuttx/gran.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
+/* Sizes of things */
+
#define SIZEOF_GAT(n) \
((n + 31) >> 5)
#define SIZEOF_GRAN_S(n) \
(sizeof(struct gran_s) + sizeof(uint32_t) * (SIZEOF_GAT(n) - 1))
+/* Debug */
+
+#ifdef CONFIG_CPP_HAVE_VARARGS
+# ifdef CONFIG_DEBUG_GRAM
+# define gramdbg(format, arg...) dbg(format, ##arg)
+# define gramvdbg(format, arg...) vdbg(format, ##arg)
+# else
+# define gramdbg(format, arg...) mdbg(format, ##arg)
+# define gramvdbg(format, arg...) mvdbg(format, ##arg)
+# endif
+#else
+# ifdef CONFIG_DEBUG_GRAM
+# define gramdbg dbg
+# define gramvdbg vdbg
+# else
+# define gramdbg (void)
+# define gramvdbg (void)
+# endif
+#endif
+
/****************************************************************************
* Public Types
****************************************************************************/
@@ -64,7 +88,7 @@ struct gran_s
uint8_t log2gran; /* Log base 2 of the size of one granule */
uint16_t ngranules; /* The total number of (aligned) granules in the heap */
uintptr_t heapstart; /* The aligned start of the granule heap */
- uint32_t gat[i]; /* Start of the granule allocation table */
+ uint32_t gat[1]; /* Start of the granule allocation table */
};
/****************************************************************************
diff --git a/nuttx/mm/mm_granalloc.c b/nuttx/mm/mm_granalloc.c
index f94f447e3..a8802a6c5 100644
--- a/nuttx/mm/mm_granalloc.c
+++ b/nuttx/mm/mm_granalloc.c
@@ -39,8 +39,14 @@
#include <nuttx/config.h>
+#include <assert.h>
+
#include <nuttx/gran.h>
+#include "mm_gran.h"
+
+#ifdef CONFIG_GRAN
+
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
@@ -61,7 +67,7 @@
*
****************************************************************************/
-static inline FAR void *gran_mark_allocated(FAR struct gran_s *priv, uintptr_t alloc, unsigned int ngranules)
+static inline void gran_mark_allocated(FAR struct gran_s *priv, uintptr_t alloc, unsigned int ngranules)
{
unsigned int granno;
unsigned int gatidx;
@@ -128,13 +134,13 @@ static inline FAR void *gran_common_alloc(FAR struct gran_s *priv, size_t size)
int i;
int j;
- DEBUGASSERT(priv);
+ DEBUGASSERT(priv && size <= 32 * (1 << priv->log2gran));
if (priv && size > 0)
{
/* How many contiguous granules we we need to find? */
- tmpmask = (1 << log2gran) - 1;
- ngranules = (size + tmpmask) >> log2gran;
+ tmpmask = (1 << priv->log2gran) - 1;
+ ngranules = (size + tmpmask) >> priv->log2gran;
/* Then create mask for that number of granules */
@@ -188,11 +194,11 @@ static inline FAR void *gran_common_alloc(FAR struct gran_s *priv, size_t size)
*/
curr >>= 1;
- if (next & 1)
+ if ((next & 1) != 0)
{
curr |= 0x80000000;
}
- next >> 1;
+ next >>= 1;
/* Increment the next candidate allocation address */
@@ -239,3 +245,5 @@ FAR void *gran_alloc(GRAN_HANDLE handle, size_t size)
return gran_common_alloc((FAR struct gran_s *)handle, size);
}
#endif
+
+#endif /* CONFIG_GRAN */
diff --git a/nuttx/mm/mm_granfree.c b/nuttx/mm/mm_granfree.c
index 4679ae62b..e359cded8 100644
--- a/nuttx/mm/mm_granfree.c
+++ b/nuttx/mm/mm_granfree.c
@@ -39,8 +39,14 @@
#include <nuttx/config.h>
+#include <assert.h>
+
#include <nuttx/gran.h>
+#include "mm_gran.h"
+
+#ifdef CONFIG_GRAN
+
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
@@ -66,18 +72,29 @@ static inline void gran_common_free(FAR struct gran_s *priv,
unsigned int granno;
unsigned int gatidx;
unsigned int gatbit;
+ unsigned int granmask;
+ unsigned int ngranules;
unsigned int avail;
- uint32_t mask;
+ uint32_t gatmask;
+
+ DEBUGASSERT(priv && memory && size <= 32 * (1 << priv->log2gran));
- /* Determine the granule number of the allocation */
+ /* Determine the granule number of the first granule in the allocation */
- granno = (alloc - priv->heapstart) >> priv->log2gran;
+ granno = ((uintptr_t)memory - priv->heapstart) >> priv->log2gran;
- /* Determine the GAT table index associated with the allocation */
+ /* Determine the GAT table index and bit number associated with the
+ * allocation.
+ */
gatidx = granno >> 5;
gatbit = granno & 31;
+ /* Determine the number of granules in the allocation */
+
+ granmask = (1 << priv->log2gran) - 1;
+ ngranules = (size + granmask) >> priv->log2gran;
+
/* Clear bits in the first GAT entry */
avail = 32 - gatbit;
@@ -91,15 +108,15 @@ static inline void gran_common_free(FAR struct gran_s *priv,
else
{
- mask = 0xffffffff >> (32 - ngranules);
- priv->gat[gatidx] &= ~(mask << gatbit);
+ gatmask = 0xffffffff >> (32 - ngranules);
+ priv->gat[gatidx] &= ~(gatmask << gatbit);
return;
}
/* Clear bits in the second GAT entry */
- mask = 0xffffffff >> (32 - ngranules);
- priv->gat[gatidx+1] &= ~(mask << gatbit);
+ gatmask = 0xffffffff >> (32 - ngranules);
+ priv->gat[gatidx+1] &= ~(gatmask << gatbit);
}
/****************************************************************************
@@ -132,3 +149,5 @@ void gran_free(GRAN_HANDLE handle, FAR void *memory, size_t size)
return gran_common_free((FAR struct gran_s *)handle, memory, size);
}
#endif
+
+#endif /* CONFIG_GRAN */
diff --git a/nuttx/mm/mm_graninit.c b/nuttx/mm/mm_graninit.c
index 99b499155..46b5f5ff1 100644
--- a/nuttx/mm/mm_graninit.c
+++ b/nuttx/mm/mm_graninit.c
@@ -39,8 +39,14 @@
#include <nuttx/config.h>
+#include <stdlib.h>
+
#include <nuttx/gran.h>
+#include "mm_gran.h"
+
+#ifdef CONFIG_GRAN
+
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
@@ -108,7 +114,7 @@ static inline FAR struct gran_s *gran_common_initialize(FAR void *heapstart,
priv->log2gran = log2gran;
priv->ngranules = ngranules;
- priv->heapstart = alignedstart
+ priv->heapstart = alignedstart;
}
return priv;
@@ -161,3 +167,6 @@ GRAN_HANDLE gran_initialize(FAR void *heapstart, size_t heapsize, uint8_t log2gr
}
#endif
+#endif /* CONFIG_GRAN */
+
+