Parent repository is bk://bk.phunnypharm.org/ieee1394-2.6
======== ChangeSet 1.1572 ========
D 1.1572 04/02/11 22:25:54-08:00 akpm@mnm.(none) 36569 36560 0/0/1
P ChangeSet
C Merge mnm.(none):/usr/src/bk25 into mnm.(none):/usr/src/bk-ieee1394
------------------------------------------------

diff -Nru a/drivers/ieee1394/Makefile b/drivers/ieee1394/Makefile
--- a/drivers/ieee1394/Makefile	Wed Feb 11 22:28:46 2004
+++ b/drivers/ieee1394/Makefile	Wed Feb 11 22:28:46 2004
@@ -3,7 +3,8 @@
 #
 
 ieee1394-objs := ieee1394_core.o ieee1394_transactions.o hosts.o \
-		 highlevel.o csr.o nodemgr.o oui.o dma.o iso.o
+		 highlevel.o csr.o nodemgr.o oui.o dma.o iso.o \
+		 csr1212.o
 
 obj-$(CONFIG_IEEE1394) += ieee1394.o
 obj-$(CONFIG_IEEE1394_PCILYNX) += pcilynx.o
diff -Nru a/drivers/ieee1394/csr.c b/drivers/ieee1394/csr.c
--- a/drivers/ieee1394/csr.c	Wed Feb 11 22:28:46 2004
+++ b/drivers/ieee1394/csr.c	Wed Feb 11 22:28:46 2004
@@ -23,6 +23,7 @@
 #include <linux/param.h>
 #include <linux/spinlock.h>
 
+#include "csr1212.h"
 #include "ieee1394_types.h"
 #include "hosts.h"
 #include "ieee1394.h"
@@ -35,7 +36,10 @@
 module_param(fcp, int, 0444);
 MODULE_PARM_DESC(fcp, "Map FCP registers (default = 1, disable = 0).");
 
+static struct csr1212_keyval *node_cap = NULL;
+
 static void add_host(struct hpsb_host *host);
+static void remove_host(struct hpsb_host *host);
 static void host_reset(struct hpsb_host *host);
 static int read_maps(struct hpsb_host *host, int nodeid, quadlet_t *buffer,
 		     u64 addr, size_t length, u16 fl);
@@ -49,10 +53,15 @@
 		     u64 addr, quadlet_t data, quadlet_t arg, int extcode, u16 fl);
 static int lock64_regs(struct hpsb_host *host, int nodeid, octlet_t * store,
 		       u64 addr, octlet_t data, octlet_t arg, int extcode, u16 fl);
+static int read_config_rom(struct hpsb_host *host, int nodeid, quadlet_t *buffer,
+			   u64 addr, size_t length, u16 fl);
+static u64 allocate_addr_range(u64 size, u32 alignment, void *__host);
+static void release_addr_range(u64 addr, void *__host);
 
 static struct hpsb_highlevel csr_highlevel = {
 	.name =		"standard registers",
 	.add_host =	add_host,
+	.remove_host =	remove_host,
 	.host_reset =	host_reset,
 };
 
@@ -71,6 +80,15 @@
 	.lock64 = lock64_regs,
 };
 
+static struct hpsb_address_ops config_rom_ops = {
+	.read = read_config_rom,
+};
+
+struct csr1212_bus_ops csr_bus_ops = {
+	.allocate_addr_range =	allocate_addr_range,
+	.release_addr =		release_addr_range,
+};
+
 
 static u16 csr_crc16(unsigned *data, int length)
 {
@@ -162,10 +180,13 @@
 
 static void add_host(struct hpsb_host *host)
 {
+	struct csr1212_keyval *root;
+	quadlet_t bus_info[CSR_BUS_INFO_SIZE];
+
 	hpsb_register_addrspace(&csr_highlevel, host, &reg_ops,
 				CSR_REGISTER_BASE,
 				CSR_REGISTER_BASE + CSR_CONFIG_ROM);
-	hpsb_register_addrspace(&csr_highlevel, host, &map_ops,
+	hpsb_register_addrspace(&csr_highlevel, host, &config_rom_ops,
 				CSR_REGISTER_BASE + CSR_CONFIG_ROM,
 				CSR_REGISTER_BASE + CSR_CONFIG_ROM_END);
 	if (fcp) {
@@ -182,8 +203,6 @@
 
         host->csr.lock = SPIN_LOCK_UNLOCKED;
 
-        host->csr.rom_size = host->driver->get_rom(host, &host->csr.rom);
-        host->csr.rom_version           = 0;
         host->csr.state                 = 0;
         host->csr.node_ids              = 0;
         host->csr.split_timeout_hi      = 0;
@@ -202,43 +221,100 @@
 			host->driver->hw_csr_reg(host, 2, 0xfffffffe, ~0);
 		}
 	}
+
+	if (host->csr.max_rec >= 9)
+		host->csr.max_rom = 2;
+	else if (host->csr.max_rec >= 5)
+		host->csr.max_rom = 1;
+	else
+		host->csr.max_rom = 0;
+
+	host->csr.generation = 2;
+
+	bus_info[1] = __constant_cpu_to_be32(0x31333934);
+	bus_info[2] = cpu_to_be32((1 << CSR_IRMC_SHIFT) |
+				  (1 << CSR_CMC_SHIFT) |
+				  (1 << CSR_ISC_SHIFT) |
+				  (0 << CSR_BMC_SHIFT) |
+				  (0 << CSR_PMC_SHIFT) |
+				  (host->csr.cyc_clk_acc << CSR_CYC_CLK_ACC_SHIFT) |
+				  (host->csr.max_rec << CSR_MAX_REC_SHIFT) |
+				  (host->csr.max_rom << CSR_MAX_ROM_SHIFT) |
+				  (host->csr.generation << CSR_GENERATION_SHIFT) |
+				  host->csr.lnk_spd);
+
+	bus_info[3] = cpu_to_be32(host->csr.guid_hi);
+	bus_info[4] = cpu_to_be32(host->csr.guid_lo);
+
+	/* The hardware copy of the bus info block will be set later when a
+	 * bus reset is issued. */
+
+	csr1212_init_local_csr(host->csr.rom, bus_info, host->csr.max_rom);
+
+	host->csr.rom->max_rom = host->csr.max_rom;
+
+	root = host->csr.rom->root_kv;
+
+	if(csr1212_attach_keyval_to_directory(root, node_cap) != CSR1212_SUCCESS) {
+		HPSB_ERR("Failed to attach Node Capabilities to root directory");
+	}
+
+	host->update_config_rom = 1;
 }
 
-int hpsb_update_config_rom(struct hpsb_host *host, const quadlet_t *new_rom, 
-	size_t size, unsigned char rom_version)
+static void remove_host(struct hpsb_host *host)
 {
-	unsigned long flags;
-	int ret;
+	quadlet_t bus_info[CSR_BUS_INFO_SIZE];
 
-        spin_lock_irqsave(&host->csr.lock, flags); 
-        if (rom_version != host->csr.rom_version)
-                 ret = -1;
-        else if (size > (CSR_CONFIG_ROM_SIZE << 2))
-                 ret = -2;
-        else {
-                 memcpy(host->csr.rom,new_rom,size);
-                 host->csr.rom_size=size;
-                 host->csr.rom_version++;
-                 ret=0;
-        }
-        spin_unlock_irqrestore(&host->csr.lock, flags);
-        return ret;
+	bus_info[1] = __constant_cpu_to_be32(0x31333934);
+	bus_info[2] = cpu_to_be32((0 << CSR_IRMC_SHIFT) |
+				  (0 << CSR_CMC_SHIFT) |
+				  (0 << CSR_ISC_SHIFT) |
+				  (0 << CSR_BMC_SHIFT) |
+				  (0 << CSR_PMC_SHIFT) |
+				  (host->csr.cyc_clk_acc << CSR_CYC_CLK_ACC_SHIFT) |
+				  (host->csr.max_rec << CSR_MAX_REC_SHIFT) |
+				  (0 << CSR_MAX_ROM_SHIFT) |
+				  (0 << CSR_GENERATION_SHIFT) |
+				  host->csr.lnk_spd);
+
+	bus_info[3] = cpu_to_be32(host->csr.guid_hi);
+	bus_info[4] = cpu_to_be32(host->csr.guid_lo);
+
+	csr1212_detach_keyval_from_directory(host->csr.rom->root_kv, node_cap);
+
+	csr1212_init_local_csr(host->csr.rom, bus_info, 0);
+	host->update_config_rom = 1;
 }
 
-int hpsb_get_config_rom(struct hpsb_host *host, quadlet_t *buffer, 
-	size_t buffersize, size_t *rom_size, unsigned char *rom_version)
+
+int hpsb_update_config_rom(struct hpsb_host *host, const quadlet_t *new_rom, 
+	size_t buffersize, unsigned char rom_version)
 {
 	unsigned long flags;
 	int ret;
 
+	HPSB_NOTICE("hpsb_update_config_rom() is deprecated");
+
         spin_lock_irqsave(&host->csr.lock, flags); 
-        *rom_version=host->csr.rom_version;
-        *rom_size=host->csr.rom_size;
-        if (buffersize < host->csr.rom_size)
-                 ret = -1;
+	if (rom_version != host->csr.generation)
+                ret = -1;
+	else if (buffersize > host->csr.rom->cache_head->size)
+		ret = -2;
         else {
-                 memcpy(buffer,host->csr.rom,host->csr.rom_size);
-                 ret=0;
+		/* Just overwrite the generated ConfigROM image with new data,
+		 * it can be regenerated later. */
+		memcpy(host->csr.rom->cache_head->data, new_rom, buffersize);
+		host->csr.rom->cache_head->len = buffersize;
+
+		if (host->driver->set_hw_config_rom)
+			host->driver->set_hw_config_rom(host, host->csr.rom->bus_info_data);
+		/* Increment the generation number to keep some sort of sync
+		 * with the newer ConfigROM manipulation method. */
+		host->csr.generation++;
+		if (host->csr.generation > 0xf || host->csr.generation < 2)
+			host->csr.generation = 2;
+		ret=0;
         }
         spin_unlock_irqrestore(&host->csr.lock, flags);
         return ret;
@@ -255,13 +331,7 @@
 
         spin_lock_irqsave(&host->csr.lock, flags); 
 
-        if (csraddr < CSR_TOPOLOGY_MAP) {
-                if (csraddr + length > CSR_CONFIG_ROM + host->csr.rom_size) {
-                        spin_unlock_irqrestore(&host->csr.lock, flags);
-                        return RCODE_ADDRESS_ERROR;
-                }
-                src = ((char *)host->csr.rom) + csraddr - CSR_CONFIG_ROM;
-        } else if (csraddr < CSR_SPEED_MAP) {
+	if (csraddr < CSR_SPEED_MAP) {
                 src = ((char *)host->csr.topology_map) + csraddr 
                         - CSR_TOPOLOGY_MAP;
         } else {
@@ -738,14 +808,52 @@
         return RCODE_COMPLETE;
 }
 
+static int read_config_rom(struct hpsb_host *host, int nodeid, quadlet_t *buffer,
+			   u64 addr, size_t length, u16 fl)
+{
+	u32 offset = addr - CSR1212_REGISTER_SPACE_BASE;
 
+	if (csr1212_read(host->csr.rom, offset, buffer, length) == CSR1212_SUCCESS)
+		return RCODE_COMPLETE;
+	else
+		return RCODE_ADDRESS_ERROR;
+}
 
-void init_csr(void)
+static u64 allocate_addr_range(u64 size, u32 alignment, void *__host)
 {
+ 	struct hpsb_host *host = (struct hpsb_host*)__host;
+
+	return hpsb_allocate_and_register_addrspace(&csr_highlevel,
+						    host,
+						    &config_rom_ops,
+						    size, alignment,
+						    CSR1212_UNITS_SPACE_BASE,
+						    CSR1212_UNITS_SPACE_END);
+}
+
+static void release_addr_range(u64 addr, void *__host)
+{
+ 	struct hpsb_host *host = (struct hpsb_host*)__host;
+	hpsb_unregister_addrspace(&csr_highlevel, host, addr);
+}
+
+
+int init_csr(void)
+{
+	node_cap = csr1212_new_immediate(CSR1212_KV_ID_NODE_CAPABILITIES, 0x0083c0);
+	if (!node_cap) {
+		HPSB_ERR("Failed to allocate memory for Node Capabilties ConfigROM entry!");
+		return -ENOMEM;
+	}
+
 	hpsb_register_highlevel(&csr_highlevel);
+
+	return 0;
 }
 
 void cleanup_csr(void)
 {
+	if (node_cap)
+		csr1212_release_keyval(node_cap);
         hpsb_unregister_highlevel(&csr_highlevel);
 }
diff -Nru a/drivers/ieee1394/csr.h b/drivers/ieee1394/csr.h
--- a/drivers/ieee1394/csr.h	Wed Feb 11 22:28:46 2004
+++ b/drivers/ieee1394/csr.h	Wed Feb 11 22:28:46 2004
@@ -6,6 +6,8 @@
 #include <linux/sched.h>
 #endif
 
+#include "csr1212.h"
+
 #define CSR_REGISTER_BASE  0xfffff0000000ULL
 
 /* register offsets relative to CSR_REGISTER_BASE */
@@ -34,6 +36,27 @@
 #define CSR_SPEED_MAP             0x2000
 #define CSR_SPEED_MAP_END         0x3000
 
+/* IEEE 1394 bus specific Configuration ROM Key IDs */
+#define IEEE1394_KV_ID_POWER_REQUIREMENTS (0x30)
+
+/* IEEE 1394 Bus Inforamation Block specifics */
+#define CSR_BUS_INFO_SIZE (5 * sizeof(quadlet_t))
+
+#define CSR_IRMC_SHIFT 31
+#define CSR_CMC_SHIFT  30
+#define CSR_ISC_SHIFT  29
+#define CSR_BMC_SHIFT  28
+#define CSR_PMC_SHIFT  27
+#define CSR_CYC_CLK_ACC_SHIFT 16
+#define CSR_MAX_REC_SHIFT 12
+#define CSR_MAX_ROM_SHIFT 8
+#define CSR_GENERATION_SHIFT 4
+
+#define CSR_SET_BUS_INFO_GENERATION(csr, gen)				\
+	((csr)->bus_info_data[2] =					\
+		cpu_to_be32((be32_to_cpu((csr)->bus_info_data[2]) &	\
+			     ~(0xf << CSR_GENERATION_SHIFT)) |          \
+			    (gen) << CSR_GENERATION_SHIFT))
 
 struct csr_control {
         spinlock_t lock;
@@ -49,17 +72,25 @@
         quadlet_t channels_available_hi, channels_available_lo;
 	quadlet_t broadcast_channel;
 
-        quadlet_t *rom;
-        size_t rom_size;
-        unsigned char rom_version;
+	/* Bus Info */
+	quadlet_t guid_hi, guid_lo;
+	u8 cyc_clk_acc;
+	u8 max_rec;
+	u8 max_rom;
+	u8 generation;	/* Only use values between 0x2 and 0xf */
+	u8 lnk_spd;
+
+	unsigned long gen_timestamp[16];
 
+	struct csr1212_csr *rom;
 
         quadlet_t topology_map[256];
         quadlet_t speed_map[1024];
 };
 
+extern struct csr1212_bus_ops csr_bus_ops;
 
-void init_csr(void);
+int init_csr(void);
 void cleanup_csr(void);
 
 #endif /* _IEEE1394_CSR_H */
diff -Nru a/drivers/ieee1394/csr1212.c b/drivers/ieee1394/csr1212.c
--- /dev/null	Wed Dec 31 16:00:00 1969
+++ b/drivers/ieee1394/csr1212.c	Wed Feb 11 22:28:46 2004
@@ -0,0 +1,1566 @@
+/*
+ * csr1212.c -- IEEE 1212 Control and Status Register support for Linux
+ * 
+ * Copyright (C) 2003 Francois Retief <fgretief@sun.ac.za>
+ *                    Steve Kinneberg <kinnebergsteve@acmsystems.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ *    1. Redistributions of source code must retain the above copyright notice,
+ *       this list of conditions and the following disclaimer.
+ *    2. Redistributions in binary form must reproduce the above copyright
+ *       notice, this list of conditions and the following disclaimer in the
+ *       documentation and/or other materials provided with the distribution.
+ *    3. The name of the author may not be used to endorse or promote products
+ *       derived from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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.
+ */
+
+
+/* TODO List:
+ * - Verify interface consistency: i.e., public functions that take a size
+ *   parameter expect size to be in bytes.
+ * - Convenience functions for reading a block of data from a given offset.
+ */
+
+#ifndef __KERNEL__
+#include <string.h>
+#endif
+
+#include "csr1212.h"
+
+
+/* Permitted key type for each key id */
+#define __I (1 << CSR1212_KV_TYPE_IMMEDIATE)
+#define __C (1 << CSR1212_KV_TYPE_CSR_OFFSET)
+#define __D (1 << CSR1212_KV_TYPE_DIRECTORY)
+#define __L (1 << CSR1212_KV_TYPE_LEAF)
+static const u_int8_t csr1212_key_id_type_map[0x30] = {
+	0,			/* Reserved */
+	__D | __L,		/* Descriptor */
+	__I | __D | __L,	/* Bus_Dependent_Info */
+	__I | __D | __L,	/* Vendor */
+	__I,			/* Hardware_Version */
+	0, 0,			/* Reserved */
+	__D | __L,		/* Module */
+	0, 0, 0, 0,		/* Reserved */
+	__I,			/* Node_Capabilities */
+	__L,			/* EUI_64 */
+	0, 0, 0,		/* Reserved */
+	__D,			/* Unit */
+	__I,			/* Specifier_ID */
+	__I,			/* Version */
+	__I | __C | __D | __L,	/* Dependent_Info */
+	__L,			/* Unit_Location */
+	0,			/* Reserved */
+	__I,			/* Model */
+	__D,			/* Instance */
+	__L,			/* Keyword */
+	__D,			/* Feature */
+	__L,			/* Extended_ROM */
+	__I,			/* Extended_Key_Specifier_ID */
+	__I,			/* Extended_Key */
+	__I | __C | __D | __L,	/* Extended_Data */
+	__L,			/* Modifiable_Descriptor */
+	__I,			/* Directory_ID */
+	__I,			/* Revision */
+};
+#undef __I
+#undef __C
+#undef __D
+#undef __L
+
+
+#define quads_to_bytes(_q) ((_q) * sizeof(u_int32_t))
+#define bytes_to_quads(_b) (((_b) + sizeof(u_int32_t) - 1) / sizeof(u_int32_t))
+
+static inline void free_keyval(struct csr1212_keyval *kv)
+{
+	if (kv->key.type == CSR1212_KV_TYPE_LEAF)
+		CSR1212_FREE(kv->value.leaf.data);
+
+	CSR1212_FREE(kv);
+}
+
+static u_int16_t csr1212_crc16(const u_int32_t *buffer, size_t length)
+{
+	int shift;
+	u_int32_t data;
+	u_int16_t sum, crc = 0;
+
+	for (; length; length--) {
+		data = CSR1212_BE32_TO_CPU(*buffer);
+		buffer++;
+		for (shift = 28; shift >= 0; shift -= 4 ) {
+			sum = ((crc >> 12) ^ (data >> shift)) & 0xf;
+			crc = (crc << 4) ^ (sum << 12) ^ (sum << 5) ^ (sum);
+		}
+		crc &= 0xffff;
+	}
+
+	return CSR1212_CPU_TO_BE16(crc);
+}
+
+#if 0
+/* Microsoft computes the CRC with the bytes in reverse order.  Therefore we
+ * have a special version of the CRC algorithm to account for their buggy
+ * software. */
+static u_int16_t csr1212_msft_crc16(const u_int32_t *buffer, size_t length)
+{
+	int shift;
+	u_int32_t data;
+	u_int16_t sum, crc = 0;
+
+	for (; length; length--) {
+		data = CSR1212_LE32_TO_CPU(*buffer);
+		buffer++;
+		for (shift = 28; shift >= 0; shift -= 4 ) {
+			sum = ((crc >> 12) ^ (data >> shift)) & 0xf;
+			crc = (crc << 4) ^ (sum << 12) ^ (sum << 5) ^ (sum);
+		}
+		crc &= 0xffff;
+	}
+
+	return CSR1212_CPU_TO_BE16(crc);
+}
+#endif
+
+static inline struct csr1212_dentry *csr1212_find_keyval(struct csr1212_keyval *dir,
+							 struct csr1212_keyval *kv)
+{
+	struct csr1212_dentry *pos;
+
+	for (pos = dir->value.directory.dentries_head;
+	     pos != NULL; pos = pos->next) {
+		if (pos->kv == kv)
+			return pos;
+	}
+	return NULL;
+}
+
+
+static inline struct csr1212_keyval *csr1212_find_keyval_offset(struct csr1212_keyval *kv_list,
+								u_int32_t offset)
+{
+	struct csr1212_keyval *kv;
+
+	for (kv = kv_list; kv != NULL; kv = kv->next) {
+		if (kv->offset == offset)
+			return kv;
+	}
+	return NULL;
+}
+
+
+/* Creation Routines */
+struct csr1212_csr *csr1212_create_csr(struct csr1212_bus_ops *ops,
+				       size_t bus_info_size, void *private)
+{
+	struct csr1212_csr *csr;
+
+	csr = CSR1212_MALLOC(sizeof(*csr));
+	if (!csr)
+		return NULL;
+
+	csr->cache_head = 
+		csr1212_rom_cache_malloc(CSR1212_CONFIG_ROM_SPACE_OFFSET,
+					 CSR1212_CONFIG_ROM_SPACE_SIZE);
+	if (!csr->cache_head) {
+		CSR1212_FREE(csr);
+		return NULL;
+	}
+
+        /* The keyval key id is not used for the root node, but a valid key id
+         * that can be used for a directory needs to be passed to
+         * csr1212_new_directory(). */
+	csr->root_kv = csr1212_new_directory(CSR1212_KV_ID_VENDOR);
+	if (!csr->root_kv) {
+		CSR1212_FREE(csr->cache_head);
+		CSR1212_FREE(csr);
+		return NULL;
+	}
+
+	csr->bus_info_data = csr->cache_head->data;
+	csr->bus_info_len = bus_info_size;
+	csr->crc_len = bus_info_size;
+	csr->ops = ops;
+	csr->private = private;
+	csr->cache_tail = csr->cache_head;
+
+	return csr;
+}
+
+
+
+void csr1212_init_local_csr(struct csr1212_csr *csr,
+			    const u_int32_t *bus_info_data, int max_rom)
+{
+	csr->max_rom = max_rom;
+	memcpy(csr->bus_info_data, bus_info_data, csr->bus_info_len);
+}
+
+
+static struct csr1212_keyval *csr1212_new_keyval(u_int8_t type, u_int8_t key)
+{
+	struct csr1212_keyval *kv;
+
+	if (key < 0x30 && ((csr1212_key_id_type_map[key] & (1 << type)) == 0))
+		return NULL;
+
+	kv = CSR1212_MALLOC(sizeof(*kv));
+	if (!kv)
+		return NULL;
+
+	kv->key.type = type;
+	kv->key.id = key;
+
+	kv->associate = NULL;
+	kv->refcnt = 1;
+
+	kv->next = NULL;
+	kv->prev = NULL;
+	kv->offset = 0;
+	kv->valid = 0;
+	return kv;
+}
+
+struct csr1212_keyval *csr1212_new_immediate(u_int8_t key, u_int32_t value)
+{
+	struct csr1212_keyval *kv = csr1212_new_keyval(CSR1212_KV_TYPE_IMMEDIATE, key);
+	
+	if (!kv)
+		return NULL;
+
+	kv->value.immediate = value;
+	kv->valid = 1;
+	return kv;
+}
+
+struct csr1212_keyval *csr1212_new_leaf(u_int8_t key, const void *data, size_t data_len)
+{
+	struct csr1212_keyval *kv = csr1212_new_keyval(CSR1212_KV_TYPE_LEAF, key);
+
+	if (!kv)
+		return NULL;
+	
+	if (data_len > 0) {
+		kv->value.leaf.data = CSR1212_MALLOC(data_len);
+		if (!kv->value.leaf.data)
+		{
+			CSR1212_FREE(kv);
+			return NULL;
+		}
+
+		if (data)
+			memcpy(kv->value.leaf.data, data, data_len);
+	} else {
+		kv->value.leaf.data = NULL;
+	}
+
+	kv->value.leaf.len = bytes_to_quads(data_len);
+	kv->offset = 0;
+	kv->valid = 1;
+
+	return kv;
+}
+
+struct csr1212_keyval *csr1212_new_csr_offset(u_int8_t key, u_int32_t csr_offset)
+{
+	struct csr1212_keyval *kv = csr1212_new_keyval(CSR1212_KV_TYPE_CSR_OFFSET, key);
+
+	if (!kv)
+		return NULL;
+
+	kv->value.csr_offset = csr_offset;
+
+	kv->offset = 0;
+	kv->valid = 1;
+	return kv;
+}
+
+struct csr1212_keyval *csr1212_new_directory(u_int8_t key)
+{
+	struct csr1212_keyval *kv = csr1212_new_keyval(CSR1212_KV_TYPE_DIRECTORY, key);
+
+	if (!kv)
+		return NULL;
+
+	kv->value.directory.len = 0;
+	kv->offset = 0;
+	kv->value.directory.dentries_head = NULL;
+	kv->value.directory.dentries_tail = NULL;
+	kv->valid = 1;
+	return kv;
+}
+
+int csr1212_associate_keyval(struct csr1212_keyval *kv,
+			     struct csr1212_keyval *associate)
+{
+	if (!kv || !associate)
+		return CSR1212_EINVAL;
+
+	if (kv->key.id == CSR1212_KV_ID_DESCRIPTOR ||
+	   (associate->key.id != CSR1212_KV_ID_DESCRIPTOR &&
+	    associate->key.id != CSR1212_KV_ID_DEPENDENT_INFO &&
+	    associate->key.id != CSR1212_KV_ID_EXTENDED_KEY &&
+	    associate->key.id != CSR1212_KV_ID_EXTENDED_DATA &&
+	    associate->key.id < 0x30))
+		return CSR1212_EINVAL;
+
+	if (kv->key.id == CSR1212_KV_ID_EXTENDED_KEY_SPECIFIER_ID &&
+	   associate->key.id != CSR1212_KV_ID_EXTENDED_KEY)
+		return CSR1212_EINVAL;
+
+	if (kv->key.id == CSR1212_KV_ID_EXTENDED_KEY &&
+	   associate->key.id != CSR1212_KV_ID_EXTENDED_DATA)
+		return CSR1212_EINVAL;
+
+	if (associate->key.id == CSR1212_KV_ID_EXTENDED_KEY &&
+	   kv->key.id != CSR1212_KV_ID_EXTENDED_KEY_SPECIFIER_ID)
+		return CSR1212_EINVAL;
+
+	if (associate->key.id == CSR1212_KV_ID_EXTENDED_DATA &&
+	   kv->key.id != CSR1212_KV_ID_EXTENDED_KEY)
+		return CSR1212_EINVAL;
+
+	if (kv->associate)
+		csr1212_release_keyval(kv->associate);
+
+	associate->refcnt++;
+	kv->associate = associate;
+
+	return CSR1212_SUCCESS;
+}
+
+int csr1212_attach_keyval_to_directory(struct csr1212_keyval *dir,
+				       struct csr1212_keyval *kv)
+{
+	struct csr1212_dentry *dentry;
+
+	if (!kv || !dir || dir->key.type != CSR1212_KV_TYPE_DIRECTORY)
+		return CSR1212_EINVAL;
+
+	dentry = CSR1212_MALLOC(sizeof(*dentry));
+	if (!dentry)
+		return CSR1212_ENOMEM;
+
+	dentry->kv = kv;
+
+	kv->refcnt++;
+
+	dentry->next = NULL;
+	dentry->prev = dir->value.directory.dentries_tail;
+
+	if (!dir->value.directory.dentries_head)
+		dir->value.directory.dentries_head = dentry;
+
+	if (dir->value.directory.dentries_tail)
+		dir->value.directory.dentries_tail->next = dentry;
+	dir->value.directory.dentries_tail = dentry;
+
+	return CSR1212_SUCCESS;
+}
+
+struct csr1212_keyval *csr1212_new_extended_immediate(u_int32_t spec, u_int32_t key,
+						      u_int32_t value)
+{
+	struct csr1212_keyval *kvs, *kvk, *kvv;
+
+	kvs = csr1212_new_immediate(CSR1212_KV_ID_EXTENDED_KEY_SPECIFIER_ID, spec);
+	kvk = csr1212_new_immediate(CSR1212_KV_ID_EXTENDED_KEY, key);
+	kvv = csr1212_new_immediate(CSR1212_KV_ID_EXTENDED_DATA, value);
+
+	if (!kvs || !kvk || !kvv) {
+		if (kvs)
+			free_keyval(kvs);
+		if (kvk)
+			free_keyval(kvk);
+		if (kvv)
+			free_keyval(kvv);
+		return NULL;
+	}
+
+	/* Don't keep a local reference to the extended key or value. */
+	kvk->refcnt = 0;
+	kvv->refcnt = 0;
+
+	csr1212_associate_keyval(kvk, kvv);
+	csr1212_associate_keyval(kvs, kvk);
+
+	return kvs;
+}
+
+struct csr1212_keyval *csr1212_new_extended_leaf(u_int32_t spec, u_int32_t key,
+						 const void *data, size_t data_len)
+{
+	struct csr1212_keyval *kvs, *kvk, *kvv;
+
+	kvs = csr1212_new_immediate(CSR1212_KV_ID_EXTENDED_KEY_SPECIFIER_ID, spec);
+	kvk = csr1212_new_immediate(CSR1212_KV_ID_EXTENDED_KEY, key);
+	kvv = csr1212_new_leaf(CSR1212_KV_ID_EXTENDED_DATA, data, data_len);
+
+	if (!kvs || !kvk || !kvv) {
+		if (kvs)
+			free_keyval(kvs);
+		if (kvk)
+			free_keyval(kvk);
+		if (kvv)
+			free_keyval(kvv);
+		return NULL;
+	}
+
+	/* Don't keep a local reference to the extended key or value. */
+	kvk->refcnt = 0;
+	kvv->refcnt = 0;
+
+	csr1212_associate_keyval(kvk, kvv);
+	csr1212_associate_keyval(kvs, kvk);
+
+	return kvs;
+}
+
+struct csr1212_keyval *csr1212_new_descriptor_leaf(u_int8_t dtype, u_int32_t specifier_id,
+						   const void *data, size_t data_len)
+{
+	struct csr1212_keyval *kv;
+
+	kv = csr1212_new_leaf(CSR1212_KV_ID_DESCRIPTOR, NULL,
+			      data_len + CSR1212_DESCRIPTOR_LEAF_OVERHEAD);
+	if (!kv)
+		return NULL;
+
+	CSR1212_DESCRIPTOR_LEAF_SET_TYPE(kv, dtype);
+	CSR1212_DESCRIPTOR_LEAF_SET_SPECIFIER_ID(kv, specifier_id);
+
+	if (data) {
+		memcpy(CSR1212_DESCRIPTOR_LEAF_DATA(kv), data, data_len);
+	}
+
+	return kv;
+}
+
+
+struct csr1212_keyval *csr1212_new_textual_descriptor_leaf(u_int8_t cwidth,
+							   u_int16_t cset,
+							   u_int16_t language,
+							   const void *data,
+							   size_t data_len)
+{
+	struct csr1212_keyval *kv;
+	char *lstr;
+
+	kv = csr1212_new_descriptor_leaf(0, 0, NULL, data_len +
+					 CSR1212_TEXTUAL_DESCRIPTOR_LEAF_OVERHEAD);
+	if (!kv)
+		return NULL;
+
+	CSR1212_TEXTUAL_DESCRIPTOR_LEAF_SET_WIDTH(kv, cwidth);
+	CSR1212_TEXTUAL_DESCRIPTOR_LEAF_SET_CHAR_SET(kv, cset);
+	CSR1212_TEXTUAL_DESCRIPTOR_LEAF_SET_LANGUAGE(kv, language);
+
+	lstr = (char*)CSR1212_TEXTUAL_DESCRIPTOR_LEAF_DATA(kv);
+
+	/* make sure last quadlet is zeroed out */
+	*((u_int32_t*)&(lstr[(data_len - 1) & ~0x3])) = 0;
+
+	/* don't copy the NUL terminator */
+	memcpy(lstr, data, data_len);
+
+	return kv;
+}
+
+static int csr1212_check_minimal_ascii(const char *s)
+{
+	static const char minimal_ascii_table[] = {
+		0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07,
+		0x00, 0x00, 0x0a, 0x00, 0x0C, 0x0D, 0x00, 0x00,
+		0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+		0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+		0x20, 0x21, 0x22, 0x00, 0x00, 0x25, 0x26, 0x27,
+		0x28, 0x29, 0x2a, 0x2b, 0x2c, 0x2d, 0x2e, 0x2f,
+		0x30, 0x31, 0x32, 0x33, 0x34, 0x35, 0x36, 0x37,
+		0x38, 0x39, 0x3a, 0x3b, 0x3c, 0x3d, 0x3e, 0x3f,
+		0x40, 0x41, 0x42, 0x43, 0x44, 0x45, 0x46, 0x47,
+		0x48, 0x49, 0x4a, 0x4b, 0x4c, 0x4d, 0x4e, 0x4f,
+		0x50, 0x51, 0x52, 0x53, 0x54, 0x55, 0x56, 0x57,
+		0x58, 0x59, 0x5a, 0x00, 0x00, 0x00, 0x00, 0x5f,
+		0x00, 0x61, 0x62, 0x63, 0x64, 0x65, 0x66, 0x67,
+		0x68, 0x69, 0x6a, 0x6b, 0x6c, 0x6d, 0x6e, 0x6f,
+		0x70, 0x71, 0x72, 0x73, 0x74, 0x75, 0x76, 0x77,
+		0x78, 0x79, 0x7a, 0x00, 0x00, 0x00, 0x00, 0x00,
+	};
+	for (; *s; s++) {
+		if (minimal_ascii_table[*s & 0x7F] != *s)
+			return -1; /* failed */
+	}
+	/* String conforms to minimal-ascii, as specified by IEEE 1212,
+	 * par. 7.4 */
+	return 0;
+}
+
+struct csr1212_keyval *csr1212_new_string_descriptor_leaf(const char *s)
+{
+	/* Check if string conform to minimal_ascii format */
+	if (csr1212_check_minimal_ascii(s))
+		return NULL;
+
+	/* IEEE 1212, par. 7.5.4.1  Textual descriptors (minimal ASCII) */
+	return csr1212_new_textual_descriptor_leaf(0, 0, 0, s, strlen(s));
+}
+
+struct csr1212_keyval *csr1212_new_icon_descriptor_leaf(u_int32_t version,
+							u_int8_t palette_depth,
+							u_int8_t color_space,
+							u_int16_t language,
+							u_int16_t hscan,
+							u_int16_t vscan,
+							u_int32_t *palette,
+							u_int32_t *pixels)
+{
+	static const int pd[4] = { 0, 4, 16, 256 };
+	static const int cs[16] = { 4, 2 };
+	struct csr1212_keyval *kv;
+	int palette_size = pd[palette_depth] * cs[color_space];
+	int pixel_size = (hscan * vscan + 3) & ~0x3;
+
+	if ((palette_depth && !palette) || !pixels)
+		return NULL;
+
+	kv = csr1212_new_descriptor_leaf(1, 0, NULL,
+					 palette_size + pixel_size +
+					 CSR1212_ICON_DESCRIPTOR_LEAF_OVERHEAD);
+	if (!kv)
+		return NULL;
+
+	CSR1212_ICON_DESCRIPTOR_LEAF_SET_VERSION(kv, version);
+	CSR1212_ICON_DESCRIPTOR_LEAF_SET_PALETTE_DEPTH(kv, palette_depth);
+	CSR1212_ICON_DESCRIPTOR_LEAF_SET_COLOR_SPACE(kv, color_space);
+	CSR1212_ICON_DESCRIPTOR_LEAF_SET_LANGUAGE(kv, language);
+	CSR1212_ICON_DESCRIPTOR_LEAF_SET_HSCAN(kv, hscan);
+	CSR1212_ICON_DESCRIPTOR_LEAF_SET_VSCAN(kv, vscan);
+
+	if (palette_size)
+		memcpy(CSR1212_ICON_DESCRIPTOR_LEAF_PALETTE(kv), palette,
+		       palette_size);
+
+	memcpy(CSR1212_ICON_DESCRIPTOR_LEAF_PIXELS(kv), pixels, pixel_size);
+
+	return kv;
+}
+
+struct csr1212_keyval *csr1212_new_modifiable_descriptor_leaf(u_int16_t max_size,
+							      u_int64_t address)
+{
+	struct csr1212_keyval *kv;
+
+	/* IEEE 1212, par. 7.5.4.3  Modifiable descriptors */
+	kv = csr1212_new_leaf(CSR1212_KV_ID_MODIFIABLE_DESCRIPTOR, NULL, sizeof(u_int64_t));
+	if(!kv)
+		return NULL;
+
+	CSR1212_MODIFIABLE_DESCRIPTOR_SET_MAX_SIZE(kv, max_size);
+	CSR1212_MODIFIABLE_DESCRIPTOR_SET_ADDRESS_HI(kv, address);
+	CSR1212_MODIFIABLE_DESCRIPTOR_SET_ADDRESS_LO(kv, address);
+        
+	return kv;
+}
+
+static int csr1212_check_keyword(const char *s)
+{
+	for (; *s; s++) {
+
+		if (('A' <= *s) && (*s <= 'Z'))
+			continue;
+		if (('0' <= *s) && (*s <= '9'))
+			continue;
+		if (*s == '-')
+			continue;
+
+		return -1; /* failed */
+	}
+	/* String conforms to keyword, as specified by IEEE 1212,
+	 * par. 7.6.5 */
+	return CSR1212_SUCCESS;
+}
+
+struct csr1212_keyval *csr1212_new_keyword_leaf(int strc, const char *strv[])
+{
+	struct csr1212_keyval *kv;
+	char *buffer;
+	int i, data_len = 0;
+
+	/* Check all keywords to see if they conform to restrictions:
+	 * Only the following characters is allowed ['A'..'Z','0'..'9','-']
+	 * Each word is zero-terminated.
+	 * Also calculate the total length of the keywords.
+	 */
+	for (i = 0; i < strc; i++) {
+		if (!strv[i] || csr1212_check_keyword(strv[i])) {
+			return NULL;
+		}
+		data_len += strlen(strv[i]) + 1; /* Add zero-termination char. */
+	}
+
+	/* IEEE 1212, par. 7.6.5 Keyword leaves */
+	kv = csr1212_new_leaf(CSR1212_KV_ID_KEYWORD, NULL, data_len);
+	if (!kv)
+		return NULL;
+
+	buffer = (char *)kv->value.leaf.data;
+
+	/* make sure last quadlet is zeroed out */
+	*((u_int32_t*)&(buffer[(data_len - 1) & ~0x3])) = 0;
+	
+	/* Copy keyword(s) into leaf data buffer */
+	for (i = 0; i < strc; i++) {
+		int len = strlen(strv[i]) + 1;
+		memcpy(buffer, strv[i], len);
+		buffer += len;
+	}
+	return kv;
+}
+
+
+/* Destruction Routines */
+
+void csr1212_detach_keyval_from_directory(struct csr1212_keyval *dir,
+					  struct csr1212_keyval *kv)
+{
+	struct csr1212_dentry *dentry;
+
+	if (!kv || !dir || dir->key.type != CSR1212_KV_TYPE_DIRECTORY)
+		return;
+
+	dentry = csr1212_find_keyval(dir, kv);
+	
+	if (!dentry)
+		return;
+
+	if (dentry->prev)
+		dentry->prev->next = dentry->next;
+	if (dentry->next)
+		dentry->next->prev = dentry->prev;
+	if (dir->value.directory.dentries_head == dentry)
+		dir->value.directory.dentries_head = dentry->next;
+	if (dir->value.directory.dentries_tail == dentry)
+		dir->value.directory.dentries_tail = dentry->prev;
+
+	CSR1212_FREE(dentry);
+
+	csr1212_release_keyval(kv);
+}
+
+
+void csr1212_disassociate_keyval(struct csr1212_keyval *kv)
+{
+	if (kv->associate) {
+		csr1212_release_keyval(kv->associate);
+	}
+
+	kv->associate = NULL;
+}
+
+
+/* This function is used to free the memory taken by a keyval.  If the given
+ * keyval is a directory type, then any keyvals contained in that directory
+ * will be destroyed as well if their respective refcnts are 0.  By means of
+ * list manipulation, this routine will descend a directory structure in a
+ * non-recursive manner. */
+void _csr1212_destroy_keyval(struct csr1212_keyval *kv)
+{
+	struct csr1212_keyval *k, *a;
+	struct csr1212_dentry dentry;
+	struct csr1212_dentry *head, *tail;
+
+	dentry.kv = kv;
+	dentry.next = NULL;
+	dentry.prev = NULL;
+
+	head = &dentry;
+	tail = head;
+
+	while (head) {
+		k = head->kv;
+
+		while (k) {
+			k->refcnt--;
+
+			if (k->refcnt > 0)
+				break;
+
+			a = k->associate;
+
+			if (k->key.type == CSR1212_KV_TYPE_DIRECTORY) {
+				/* If the current entry is a directory, then move all
+				 * the entries to the destruction list. */
+				tail->next = k->value.directory.dentries_head;
+				if (k->value.directory.dentries_head)
+					k->value.directory.dentries_head->prev = tail;
+				tail = k->value.directory.dentries_tail;
+			}
+			free_keyval(k);
+			k = a;
+		}
+
+		head = head->next;
+		if (head) {
+			if (head->prev && head->prev != &dentry) {
+				CSR1212_FREE(head->prev);
+			}
+			head->prev = NULL;
+		} else if (tail != &dentry)
+			CSR1212_FREE(tail);
+	}
+}
+
+
+void csr1212_destroy_csr(struct csr1212_csr *csr)
+{
+	struct csr1212_csr_rom_cache *c, *oc;
+	struct csr1212_cache_region *cr, *ocr;
+
+	csr1212_release_keyval(csr->root_kv);
+
+	c = csr->cache_head;
+	while (c) {
+		oc = c;
+		cr = c->filled_head;
+		while (cr) {
+			ocr = cr;
+			cr = cr->next;
+			CSR1212_FREE(ocr);
+		}
+		c = c->next;
+		CSR1212_FREE(oc);
+	}
+
+	CSR1212_FREE(csr);
+}
+
+
+
+/* CSR Image Creation */
+
+static int csr1212_append_new_cache(struct csr1212_csr *csr, size_t romsize)
+{
+	struct csr1212_csr_rom_cache *cache;
+	u_int64_t csr_addr;
+
+	if (!csr || !csr->ops->allocate_addr_range ||
+	    !csr->ops->release_addr)
+		return CSR1212_ENOMEM;
+
+	/* ROM size must be a multiple of csr->max_rom */
+	romsize = (romsize + (csr->max_rom - 1)) & ~(csr->max_rom - 1);
+
+	csr_addr = csr->ops->allocate_addr_range(romsize, csr->max_rom, csr->private);
+	if (csr_addr == ~0ULL) {
+		return CSR1212_ENOMEM;
+	}
+	if (csr_addr < CSR1212_REGISTER_SPACE_BASE) {
+		/* Invalid address returned from allocate_addr_range(). */
+		csr->ops->release_addr(csr_addr, csr->private);
+		return CSR1212_ENOMEM;
+	}
+
+	cache = csr1212_rom_cache_malloc(csr_addr - CSR1212_REGISTER_SPACE_BASE, romsize);
+	if (!cache) {
+		csr->ops->release_addr(csr_addr, csr->private);
+		return CSR1212_ENOMEM;
+	}
+
+	cache->ext_rom = csr1212_new_keyval(CSR1212_KV_TYPE_LEAF, CSR1212_KV_ID_EXTENDED_ROM);
+	if (!cache->ext_rom) {
+		csr->ops->release_addr(csr_addr, csr->private);
+		CSR1212_FREE(cache);
+		return CSR1212_ENOMEM;
+	}
+
+	if (csr1212_attach_keyval_to_directory(csr->root_kv, cache->ext_rom) != CSR1212_SUCCESS)
+	{
+		csr1212_release_keyval(cache->ext_rom);
+		csr->ops->release_addr(csr_addr, csr->private);
+		CSR1212_FREE(cache);
+		return CSR1212_ENOMEM;
+	}
+	cache->ext_rom->offset = csr_addr - CSR1212_REGISTER_SPACE_BASE;
+	cache->ext_rom->value.leaf.len = 0;
+
+	/* Add cache to tail of cache list */
+	cache->prev = csr->cache_tail;
+	csr->cache_tail->next = cache;
+	csr->cache_tail = cache;
+	return CSR1212_SUCCESS;
+}
+
+static inline void csr1212_remove_cache(struct csr1212_csr *csr,
+					struct csr1212_csr_rom_cache *cache)
+{
+	if (csr->cache_head == cache)
+		csr->cache_head = cache->next;
+	if (csr->cache_tail == cache)
+		csr->cache_tail = cache->prev;
+
+	if (cache->prev)
+		cache->prev->next = cache->next;
+	if (cache->next)
+		cache->next->prev = cache->prev;
+
+	if (cache->ext_rom) {
+		csr1212_detach_keyval_from_directory(csr->root_kv, cache->ext_rom);
+		csr1212_release_keyval(cache->ext_rom);
+	}
+
+	CSR1212_FREE(cache);
+}
+
+static int csr1212_generate_layout_subdir(struct csr1212_keyval *dir,
+					  struct csr1212_keyval **layout_tail)
+{
+	struct csr1212_dentry *dentry;
+	struct csr1212_keyval *dkv;
+	struct csr1212_keyval *last_extkey_spec = NULL;
+	struct csr1212_keyval *last_extkey = NULL;
+	int num_entries = 0;
+
+	for (dentry = dir->value.directory.dentries_head; dentry;
+	     dentry = dentry->next) {
+		for (dkv = dentry->kv; dkv; dkv = dkv->associate) {
+			/* Special Case: Extended Key Specifier_ID */
+			if (dkv->key.id == CSR1212_KV_ID_EXTENDED_KEY_SPECIFIER_ID) {
+				if (last_extkey_spec == NULL) {
+					last_extkey_spec = dkv;
+				} else if (dkv->value.immediate != last_extkey_spec->value.immediate) {
+					last_extkey_spec = dkv;
+				} else {
+					continue;
+				}
+			/* Special Case: Extended Key */
+			} else if (dkv->key.id == CSR1212_KV_ID_EXTENDED_KEY) {
+				if (last_extkey == NULL) {
+					last_extkey = dkv;
+				} else if (dkv->value.immediate != last_extkey->value.immediate) {
+					last_extkey = dkv;
+				} else {
+					continue;
+				}
+			}
+
+			num_entries += 1;
+
+			switch(dkv->key.type) {
+			default:
+			case CSR1212_KV_TYPE_IMMEDIATE:
+			case CSR1212_KV_TYPE_CSR_OFFSET:
+				continue;
+			case CSR1212_KV_TYPE_LEAF:
+			case CSR1212_KV_TYPE_DIRECTORY:
+				/* Remove from list */
+				if (dkv->prev)
+					dkv->prev->next = dkv->next;
+				if (dkv->next)
+					dkv->next->prev = dkv->prev;
+				if (dkv == *layout_tail)
+					*layout_tail = dkv->prev;
+
+				/* Special case: Extended ROM leafs */
+				if (dkv->key.id == CSR1212_KV_ID_EXTENDED_ROM) {
+					dkv->value.leaf.len = 0; /* initialize to zero */
+					/* Don't add Extended ROM leafs in the layout list,
+					 * they are handled differently. */
+					break;
+				}
+
+				/* Add to tail of list */
+				dkv->next = NULL;
+				dkv->prev = *layout_tail;
+				(*layout_tail)->next = dkv;
+				*layout_tail = dkv;
+				break;
+			}
+		}
+	}
+	return num_entries;
+}
+
+size_t csr1212_generate_layout_order(struct csr1212_keyval *kv)
+{
+	struct csr1212_keyval *ltail = kv;
+	size_t agg_size = 0;
+
+	while(kv) {
+		switch(kv->key.type) {
+		case CSR1212_KV_TYPE_LEAF:
+			/* Add 1 quadlet for crc/len field */
+			agg_size += kv->value.leaf.len + 1;
+			break;
+
+		case CSR1212_KV_TYPE_DIRECTORY:
+			kv->value.directory.len = csr1212_generate_layout_subdir(kv, &ltail);
+			/* Add 1 quadlet for crc/len field */
+			agg_size += kv->value.directory.len + 1;
+			break;
+		}
+		kv = kv->next;
+	}
+	return quads_to_bytes(agg_size);
+}
+
+struct csr1212_keyval *csr1212_generate_positions(struct csr1212_csr_rom_cache *cache,
+                                                  struct csr1212_keyval *start_kv,
+                                                  int start_pos)
+{
+	struct csr1212_keyval *kv = start_kv;
+	struct csr1212_keyval *okv = start_kv;
+	int pos = start_pos;
+	int kv_len = 0, okv_len = 0;
+
+	cache->layout_head = kv;
+
+	while(kv && pos < cache->size) {
+		kv->offset = cache->offset + pos;
+
+		switch(kv->key.type) {
+		case CSR1212_KV_TYPE_LEAF:
+			kv_len = kv->value.leaf.len;
+			break;
+
+		case CSR1212_KV_TYPE_DIRECTORY:
+			kv_len = kv->value.directory.len;
+			break;
+
+		default:
+			/* Should never get here */
+			break;
+		}
+
+		pos += quads_to_bytes(kv_len + 1);
+
+		if (pos <= cache->size) {
+			okv = kv;
+			okv_len = kv_len;
+			kv = kv->next;
+		}
+	}
+
+	cache->layout_tail = okv;
+	cache->len = (okv->offset - cache->offset) + quads_to_bytes(okv_len + 1);
+
+	return kv;
+}
+
+static void csr1212_generate_tree_subdir(struct csr1212_keyval *dir,
+					 u_int32_t *data_buffer)
+{
+	struct csr1212_dentry *dentry;
+	struct csr1212_keyval *last_extkey_spec = NULL;
+	struct csr1212_keyval *last_extkey = NULL;
+	int index = 0;
+
+	for (dentry = dir->value.directory.dentries_head; dentry; dentry = dentry->next) {
+		struct csr1212_keyval *a;
+
+		for (a = dentry->kv; a; a = a->associate) {
+			u_int32_t value = 0;
+
+			/* Special Case: Extended Key Specifier_ID */
+			if (a->key.id == CSR1212_KV_ID_EXTENDED_KEY_SPECIFIER_ID) {
+				if (last_extkey_spec == NULL) {
+					last_extkey_spec = a;
+				} else if (a->value.immediate != last_extkey_spec->value.immediate) {
+					last_extkey_spec = a;
+				} else {
+					continue;
+				}
+			/* Special Case: Extended Key */
+			} else if (a->key.id == CSR1212_KV_ID_EXTENDED_KEY) {
+				if (last_extkey == NULL) {
+					last_extkey = a;
+				} else if (a->value.immediate != last_extkey->value.immediate) {
+					last_extkey = a;
+				} else {
+					continue;
+				}
+			}
+
+			switch(a->key.type) {
+			case CSR1212_KV_TYPE_IMMEDIATE:
+				value = a->value.immediate;
+				break;
+			case CSR1212_KV_TYPE_CSR_OFFSET:
+				value = a->value.csr_offset;
+				break;
+			case CSR1212_KV_TYPE_LEAF:
+				value = a->offset;
+				value -= dir->offset + quads_to_bytes(1+index);
+				value = bytes_to_quads(value);
+				break;
+			case CSR1212_KV_TYPE_DIRECTORY:
+				value = a->offset;
+				value -= dir->offset + quads_to_bytes(1+index);
+				value = bytes_to_quads(value);
+				break;
+			default:
+				/* Should never get here */
+				break; /* GDB breakpoint */
+			}
+
+			value |= (a->key.id & CSR1212_KV_KEY_ID_MASK) << CSR1212_KV_KEY_SHIFT;
+			value |= (a->key.type & CSR1212_KV_KEY_TYPE_MASK) <<
+				(CSR1212_KV_KEY_SHIFT + CSR1212_KV_KEY_TYPE_SHIFT);
+			data_buffer[index] = CSR1212_CPU_TO_BE32(value);
+			index++;
+		}
+	}
+}
+
+void csr1212_fill_cache(struct csr1212_csr_rom_cache *cache)
+{
+	struct csr1212_keyval *kv, *nkv;
+	struct csr1212_keyval_img *kvi;
+
+	for (kv = cache->layout_head; kv != cache->layout_tail->next; kv = nkv) {
+		kvi = (struct csr1212_keyval_img *)
+			(cache->data + bytes_to_quads(kv->offset - cache->offset));
+		switch(kv->key.type) {
+		default:
+		case CSR1212_KV_TYPE_IMMEDIATE:
+		case CSR1212_KV_TYPE_CSR_OFFSET:
+			/* Should never get here */
+			break; /* GDB breakpoint */
+
+		case CSR1212_KV_TYPE_LEAF:
+			/* Don't copy over Extended ROM areas, they are
+			 * already filled out! */
+			if (kv->key.id != CSR1212_KV_ID_EXTENDED_ROM)
+				memcpy(kvi->data, kv->value.leaf.data,
+				       quads_to_bytes(kv->value.leaf.len));
+
+			kvi->length = CSR1212_CPU_TO_BE16(kv->value.leaf.len);
+			kvi->crc = csr1212_crc16(kvi->data, kv->value.leaf.len);
+			break;
+
+		case CSR1212_KV_TYPE_DIRECTORY:
+			csr1212_generate_tree_subdir(kv, kvi->data);
+
+			kvi->length = CSR1212_CPU_TO_BE16(kv->value.directory.len);
+			kvi->crc = csr1212_crc16(kvi->data, kv->value.directory.len);
+			break;
+		}
+
+		nkv = kv->next;
+		kv->prev = NULL;
+		kv->next = NULL;
+	}
+}
+
+int csr1212_generate_csr_image(struct csr1212_csr *csr)
+{
+	struct csr1212_bus_info_block_img *bi;
+	struct csr1212_csr_rom_cache *cache;
+	struct csr1212_keyval *kv;
+	size_t agg_size;
+	int ret;
+	int init_offset;
+
+	if (!csr)
+		return CSR1212_EINVAL;
+
+	cache = csr->cache_head;
+
+	bi = (struct csr1212_bus_info_block_img*)cache->data;
+
+	bi->length = bytes_to_quads(csr->bus_info_len) - 1;
+	bi->crc_length = bi->length;
+	bi->crc = csr1212_crc16(bi->data, bi->crc_length);
+
+	agg_size = csr1212_generate_layout_order(csr->root_kv);
+
+	init_offset = csr->bus_info_len;
+
+	for (kv = csr->root_kv, cache = csr->cache_head; kv; cache = cache->next) {
+		if (!cache) {
+			/* Estimate approximate number of additional cache
+			 * regions needed (it assumes that the cache holding
+			 * the first 1K Config ROM space always exists). */
+			int est_c = agg_size / (CSR1212_EXTENDED_ROM_SIZE -
+						(2 * sizeof(u_int32_t))) + 1;
+
+			/* Add additional cache regions, extras will be
+			 * removed later */
+			for (; est_c; est_c--) {
+				ret = csr1212_append_new_cache(csr, CSR1212_EXTENDED_ROM_SIZE);
+				if (ret != CSR1212_SUCCESS)
+					return ret;
+			}
+			/* Need to re-layout for additional cache regions */
+			agg_size = csr1212_generate_layout_order(csr->root_kv);
+			kv = csr->root_kv;
+			cache = csr->cache_head;
+			init_offset = csr->bus_info_len;
+		}
+		kv = csr1212_generate_positions(cache, kv, init_offset);
+		agg_size -= cache->len;
+		init_offset = sizeof(u_int32_t);
+	}
+
+	/* Remove unused, excess cache regions */
+	while (cache) {
+		struct csr1212_csr_rom_cache *oc = cache;
+		
+		cache = cache->next;
+		csr1212_remove_cache(csr, oc);
+	}
+
+
+	/* Go through the list backward so that when done, the correct CRC
+	 * will be calculated for the Extended ROM areas. */
+	for(cache = csr->cache_tail; cache; cache = cache->prev) {
+		/* Only Extended ROM caches should have this set. */
+		if (cache->ext_rom) {
+			int leaf_size;
+
+			/* Make sure the Extended ROM leaf is a multiple of
+			 * max_rom in size. */
+			leaf_size = (cache->len + (csr->max_rom - 1)) &
+				(csr->max_rom - 1);
+
+			/* Zero out the unused ROM region */
+			memset(cache->data + bytes_to_quads(cache->len), 0x00,
+			       leaf_size - cache->len);
+
+			/* Subtract leaf header */
+			leaf_size -= sizeof(u_int32_t);
+
+			/* Update the Extended ROM leaf length */
+			cache->ext_rom->value.leaf.len =
+				bytes_to_quads(leaf_size);
+		} else {
+			/* Zero out the unused ROM region */
+			memset(cache->data + bytes_to_quads(cache->len), 0x00,
+			       cache->size - cache->len);
+		}
+
+		/* Copy the data into the cache buffer */
+		csr1212_fill_cache(cache);
+	}
+
+	return CSR1212_SUCCESS;
+}
+
+int csr1212_read(struct csr1212_csr *csr, u_int32_t offset, void *buffer, u_int32_t len)
+{
+	struct csr1212_csr_rom_cache *cache;
+
+	for (cache = csr->cache_head; cache; cache = cache->next) {
+		if (offset >= cache->offset &&
+		    (offset + len) <= (cache->offset + cache->size)) {
+			memcpy(buffer,
+			       &cache->data[bytes_to_quads(offset - cache->offset)],
+			       len);
+			return CSR1212_SUCCESS;
+		} else if (((offset < cache->offset) &&
+			    ((offset + len) >= cache->offset)) ||
+			   ((offset >= cache->offset) &&
+			    ((offset + len) > (cache->offset + cache->size)))) {
+			return CSR1212_EINVAL;
+		}
+	}
+	return CSR1212_ENOENT;
+}
+
+
+
+/* Parse a chunk of data as a Config ROM */
+
+static int csr1212_parse_bus_info_block(struct csr1212_csr *csr)
+{
+	struct csr1212_bus_info_block_img *bi;
+	struct csr1212_cache_region *cr;
+	int i;
+	int ret;
+
+	/* IEEE 1212 says that the entire bus info block should be readable in
+	 * a single transaction regardless of the max_rom value.
+	 * Unfortunately, many IEEE 1394 devices do not abide by that, so the
+	 * bus info block will be read 1 quadlet at a time.  The rest of the
+	 * ConfigROM will be read according to the max_rom field. */
+	for (i = 0; i < csr->bus_info_len; i += sizeof(csr1212_quad_t)) {
+		ret = csr->ops->bus_read(csr, CSR1212_CONFIG_ROM_SPACE_BASE + i,
+					 sizeof(csr1212_quad_t),
+					 &csr->cache_head->data[bytes_to_quads(i)],
+					 csr->private);
+		if (ret != CSR1212_SUCCESS)
+			return ret;
+	}
+
+	bi = (struct csr1212_bus_info_block_img*)csr->cache_head->data;
+	csr->crc_len = quads_to_bytes(bi->crc_length);
+
+	/* IEEE 1212 recommends that crc_len be equal to bus_info_len, but that is not
+	 * always the case, so read the rest of the crc area 1 quadlet at a time. */
+	for (i = csr->bus_info_len; i <= csr->crc_len; i += sizeof(csr1212_quad_t)) {
+		ret = csr->ops->bus_read(csr, CSR1212_CONFIG_ROM_SPACE_BASE + i,
+					 sizeof(csr1212_quad_t),
+					 &csr->cache_head->data[bytes_to_quads(i)],
+					 csr->private);
+		if (ret != CSR1212_SUCCESS)
+			return ret;
+	}
+
+	if (bytes_to_quads(csr->bus_info_len - sizeof(csr1212_quad_t)) != bi->length)
+		return CSR1212_EINVAL;
+
+#if 0
+        /* Apparently there are too many differnt wrong implementations of the
+         * CRC algorithm that verifying them is moot. */
+	if ((csr1212_crc16(bi->data, bi->crc_length) != bi->crc) &&
+	    (csr1212_msft_crc16(bi->data, bi->crc_length) != bi->crc))
+		return CSR1212_EINVAL;
+#endif
+
+	cr = CSR1212_MALLOC(sizeof(struct csr1212_cache_region));
+	if (!cr)
+		return CSR1212_ENOMEM;
+
+	cr->next = NULL;
+	cr->prev = NULL;
+	cr->offset_start = 0;
+	cr->offset_end = csr->crc_len + 4;
+
+	csr->cache_head->filled_head = cr;
+	csr->cache_head->filled_tail = cr;
+
+	return CSR1212_SUCCESS;
+}
+
+static inline int csr1212_parse_dir_entry(struct csr1212_keyval *dir,
+					  csr1212_quad_t ki,
+					  u_int32_t kv_pos,
+					  struct csr1212_csr_rom_cache *cache)
+{
+	int ret = CSR1212_SUCCESS;
+	struct csr1212_keyval *k = NULL;
+	u_int32_t offset;
+
+	switch(CSR1212_KV_KEY_TYPE(ki)) {
+	case CSR1212_KV_TYPE_IMMEDIATE:
+		k = csr1212_new_immediate(CSR1212_KV_KEY_ID(ki),
+					  CSR1212_KV_VAL(ki));
+		if (!k) {
+			ret = CSR1212_ENOMEM;
+			goto fail;
+		}
+		
+		k->refcnt = 0;	/* Don't keep local reference when parsing. */
+		break;
+
+	case CSR1212_KV_TYPE_CSR_OFFSET:
+		k = csr1212_new_csr_offset(CSR1212_KV_KEY_ID(ki),
+					   CSR1212_KV_VAL(ki));
+		if (!k) {
+			ret = CSR1212_ENOMEM;
+			goto fail;
+		}
+		k->refcnt = 0;	/* Don't keep local reference when parsing. */
+		break;
+
+	default:
+		/* Compute the offset from 0xffff f000 0000. */
+		offset = quads_to_bytes(CSR1212_KV_VAL(ki)) + kv_pos;
+		if (offset == kv_pos) {
+			/* Uh-oh.  Can't have a relative offset of 0 for Leaves
+			 * or Directories.  The Config ROM image is most likely
+			 * messed up, so we'll just abort here. */
+			ret = CSR1212_EIO;
+			goto fail;
+		}
+
+		k = csr1212_find_keyval_offset(cache->layout_head, offset);
+
+		if (k)
+			break;		/* Found it. */
+
+		if (CSR1212_KV_KEY_TYPE(ki) == CSR1212_KV_TYPE_DIRECTORY) {
+			k = csr1212_new_directory(CSR1212_KV_KEY_ID(ki));
+		} else {
+			k = csr1212_new_leaf(CSR1212_KV_KEY_ID(ki), NULL, 0);
+		}
+		if (!k) {
+			ret = CSR1212_ENOMEM;
+			goto fail;
+		}
+		k->refcnt = 0;	/* Don't keep local reference when parsing. */
+		k->valid = 0;	/* Contents not read yet so it's not valid. */
+		k->offset = offset;
+
+		k->prev = cache->layout_tail;
+		k->next = NULL;
+		if (cache->layout_tail)
+			cache->layout_tail->next = k;
+		cache->layout_tail = k;
+	}
+	ret = csr1212_attach_keyval_to_directory(dir, k);
+
+fail:
+	if (ret != CSR1212_SUCCESS) {
+		if (k)
+			free_keyval(k);
+	}
+	return ret;
+}
+
+int csr1212_parse_keyval(struct csr1212_keyval *kv,
+			 struct csr1212_csr_rom_cache *cache)
+{
+	struct csr1212_keyval_img *kvi;
+	int i;
+	int ret = CSR1212_SUCCESS;
+	int kvi_len;
+
+	kvi = (struct csr1212_keyval_img*)&cache->data[bytes_to_quads(kv->offset -
+								      cache->offset)];
+	kvi_len = CSR1212_BE16_TO_CPU(kvi->length);
+
+#if 0
+        /* Apparently there are too many differnt wrong implementations of the
+         * CRC algorithm that verifying them is moot. */
+	if ((csr1212_crc16(kvi->data, kvi_len) != kvi->crc) &&
+	    (csr1212_msft_crc16(kvi->data, kvi_len) != kvi->crc)) {
+		ret = CSR1212_EINVAL;
+		goto fail;
+	}
+#endif
+
+	switch(kv->key.type) {
+	case CSR1212_KV_TYPE_DIRECTORY:
+		for (i = 0; i < kvi_len; i++) {
+			csr1212_quad_t ki = kvi->data[i];
+			ret = csr1212_parse_dir_entry(kv, ki,
+						      (kv->offset +
+						       quads_to_bytes(i + 1)),
+						      cache);
+		}
+		kv->value.directory.len = kvi_len;
+		break;
+
+	case CSR1212_KV_TYPE_LEAF:
+		if (kv->key.id == CSR1212_KV_ID_EXTENDED_ROM) {
+			kv->value.leaf.data = cache->data;
+		} else {
+			kv->value.leaf.data = CSR1212_MALLOC(quads_to_bytes(kvi_len));
+			if (!kv->value.leaf.data)
+			{
+				ret = CSR1212_ENOMEM;
+				goto fail;
+			}
+
+			kv->value.leaf.len = kvi_len;
+			memcpy(kv->value.leaf.data, kvi->data, quads_to_bytes(kvi_len));
+		}
+		break;
+	}
+
+	kv->valid = 1;
+
+fail:
+	return ret;
+}
+
+
+int _csr1212_read_keyval(struct csr1212_csr *csr, struct csr1212_keyval *kv)
+{
+	struct csr1212_cache_region *cr, *ncr, *newcr = NULL;
+	struct csr1212_keyval_img *kvi = NULL;
+	struct csr1212_csr_rom_cache *cache;
+	int cache_index;
+	u_int64_t addr;
+	u_int32_t *cache_ptr;
+	u_int16_t kv_len = 0;
+
+
+	if (!csr || !kv)
+		return CSR1212_EINVAL;
+
+	/* First find which cache the data should be in (or go in if not read
+	 * yet). */
+	for (cache = csr->cache_head; cache; cache = cache->next) {
+		if (kv->offset >= cache->offset &&
+		    kv->offset < (cache->offset + cache->size))
+			break;
+	}
+
+	if (!cache) {
+		csr1212_quad_t q;
+		struct csr1212_csr_rom_cache *nc;
+
+		/* Only create a new cache for Extended ROM leaves. */
+		if (kv->key.id != CSR1212_KV_ID_EXTENDED_ROM)
+			return CSR1212_EINVAL;
+
+		if (csr->ops->bus_read(csr,
+				       CSR1212_REGISTER_SPACE_BASE + kv->offset,
+				       sizeof(csr1212_quad_t), &q, csr->private)) {
+			return CSR1212_EIO;
+		}
+
+		kv->value.leaf.len = quads_to_bytes(CSR1212_BE32_TO_CPU(q)>>16);
+
+		nc = csr1212_rom_cache_malloc(kv->offset, kv->value.leaf.len);
+		cache->next = nc;
+		nc->prev = cache;
+		csr->cache_tail = nc;
+		cache->filled_head =
+			CSR1212_MALLOC(sizeof(struct csr1212_cache_region));
+		if (!cache->filled_head) {
+			return CSR1212_ENOMEM;
+		}
+
+		cache->filled_head->offset_start = 0;
+		cache->filled_head->offset_end = sizeof(csr1212_quad_t);
+		cache->filled_tail = cache->filled_head;
+		cache->filled_head->next = NULL;
+		cache->filled_head->prev = NULL;
+		cache->data[0] = q;
+	}
+
+	cache_index = kv->offset - cache->offset;
+
+	/* Now seach read portions of the cache to see if it is there. */
+	for (cr = cache->filled_head; cr; cr = cr->next) {
+		if (cache_index < cr->offset_start) {
+			newcr = CSR1212_MALLOC(sizeof(struct csr1212_cache_region));
+			if (!newcr)
+				return CSR1212_ENOMEM;
+			
+			newcr->offset_start = cache_index & ~(csr->max_rom - 1);
+			newcr->offset_end = newcr->offset_start;
+			newcr->next = cr;
+			newcr->prev = cr->prev;
+			cr->prev = newcr;
+			cr = newcr;
+			break;
+		} else if ((cache_index >= cr->offset_start) &&
+			   (cache_index < cr->offset_end)) {
+			kvi = (struct csr1212_keyval_img*)
+				(&cache->data[bytes_to_quads(cache_index)]);
+			kv_len = quads_to_bytes(CSR1212_BE16_TO_CPU(kvi->length) +
+						1);
+			break;
+		} else if (cache_index == cr->offset_end)
+			break;
+	}
+
+	if (!cr) {
+		cr = cache->filled_tail;
+		newcr = CSR1212_MALLOC(sizeof(struct csr1212_cache_region));
+		if (!newcr)
+			return CSR1212_ENOMEM;
+			
+		newcr->offset_start = cache_index & ~(csr->max_rom - 1);
+		newcr->offset_end = newcr->offset_start;
+		newcr->prev = cr;
+		newcr->next = cr->next;
+		cr->next = newcr;
+		cr = newcr;
+		cache->filled_tail = newcr;
+	}
+
+	while(!kvi || cr->offset_end < cache_index + kv_len) {
+		cache_ptr = &cache->data[bytes_to_quads(cr->offset_end &
+							~(csr->max_rom - 1))];
+
+		addr = (CSR1212_CSR_ARCH_REG_SPACE_BASE + cache->offset +
+			cr->offset_end) & ~(csr->max_rom - 1);
+
+		if (csr->ops->bus_read(csr, addr, csr->max_rom, cache_ptr,
+				       csr->private)) {
+			if (csr->max_rom == 4)
+				/* We've got problems! */
+				return CSR1212_EIO;
+
+			/* Apperently the max_rom value was a lie, set it to
+			 * do quadlet reads and try again. */
+			csr->max_rom = 4;
+			continue;
+		}
+
+		cr->offset_end += csr->max_rom - (cr->offset_end &
+						  (csr->max_rom - 1));
+
+		if (!kvi && (cr->offset_end > cache_index)) {
+			kvi = (struct csr1212_keyval_img*)
+				(&cache->data[bytes_to_quads(cache_index)]);
+			kv_len = quads_to_bytes(CSR1212_BE16_TO_CPU(kvi->length) +
+						1);
+		}
+
+		if ((kv_len + (kv->offset - cache->offset)) > cache->size) {
+			/* The Leaf or Directory claims its length extends
+			 * beyond the ConfigROM image region and thus beyond the
+			 * end of our cache region.  Therefore, we abort now
+			 * rather than seg faulting later. */
+			return CSR1212_EIO;
+		}
+
+		ncr = cr->next;
+
+		if (ncr && (cr->offset_end >= ncr->offset_start)) {
+			/* consolidate region entries */
+			ncr->offset_start = cr->offset_start;
+
+			if (cr->prev)
+				cr->prev->next = cr->next;
+			ncr->prev = cr->prev;
+			if (cache->filled_head == cr)
+				cache->filled_head = ncr;
+			CSR1212_FREE(cr);
+			cr = ncr;
+		}
+	}
+
+	return csr1212_parse_keyval(kv, cache);
+}
+
+
+
+int csr1212_parse_csr(struct csr1212_csr *csr)
+{
+	static const int mr_map[] = { 4, 64, 1024, 0 };
+	int ret;
+
+	if (!csr || !csr->ops->bus_read)
+		return CSR1212_EINVAL;
+
+	ret = csr1212_parse_bus_info_block(csr);
+	if (ret != CSR1212_SUCCESS)
+		return ret;
+
+	if (!csr->ops->get_max_rom)
+		csr->max_rom = mr_map[0];	/* default value */
+	else
+		csr->max_rom = mr_map[csr->ops->get_max_rom(csr->bus_info_data,
+							    csr->private)];
+
+	csr->cache_head->layout_head = csr->root_kv;
+	csr->cache_head->layout_tail = csr->root_kv;
+
+	csr->root_kv->offset = (CSR1212_CONFIG_ROM_SPACE_BASE & 0xffff) +
+		csr->bus_info_len;
+
+	csr->root_kv->valid = 0;
+	csr1212_get_keyval(csr, csr->root_kv);
+
+	return CSR1212_SUCCESS;
+}
diff -Nru a/drivers/ieee1394/csr1212.h b/drivers/ieee1394/csr1212.h
--- /dev/null	Wed Dec 31 16:00:00 1969
+++ b/drivers/ieee1394/csr1212.h	Wed Feb 11 22:28:46 2004
@@ -0,0 +1,724 @@
+/*
+ * csr1212.h -- IEEE 1212 Control and Status Register support for Linux
+ * 
+ * Copyright (C) 2003 Francois Retief <fgretief@sun.ac.za>
+ *                    Steve Kinneberg <kinnebergsteve@acmsystems.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ *    1. Redistributions of source code must retain the above copyright notice,
+ *       this list of conditions and the following disclaimer.
+ *    2. Redistributions in binary form must reproduce the above copyright
+ *       notice, this list of conditions and the following disclaimer in the
+ *       documentation and/or other materials provided with the distribution.
+ *    3. The name of the author may not be used to endorse or promote products
+ *       derived from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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.
+ */
+
+#ifndef __CSR1212_H__
+#define __CSR1212_H__
+
+
+/* Compatibility layer */
+#ifdef __KERNEL__
+
+#include <linux/types.h>
+#include <linux/slab.h>
+#include <linux/interrupt.h>
+
+#define CSR1212_MALLOC(size)		kmalloc((size), in_interrupt() ? GFP_ATOMIC : GFP_KERNEL)
+#define CSR1212_FREE(ptr)		kfree(ptr)
+#define CSR1212_BE16_TO_CPU(quad)	be16_to_cpu(quad)
+#define CSR1212_CPU_TO_BE16(quad)	cpu_to_be16(quad)
+#define CSR1212_BE32_TO_CPU(quad)	be32_to_cpu(quad)
+#define CSR1212_CPU_TO_BE32(quad)	cpu_to_be32(quad)
+#define CSR1212_BE64_TO_CPU(quad)	be64_to_cpu(quad)
+#define CSR1212_CPU_TO_BE64(quad)	cpu_to_be64(quad)
+
+#define CSR1212_LE16_TO_CPU(quad)	le16_to_cpu(quad)
+#define CSR1212_CPU_TO_LE16(quad)	cpu_to_le16(quad)
+#define CSR1212_LE32_TO_CPU(quad)	le32_to_cpu(quad)
+#define CSR1212_CPU_TO_LE32(quad)	cpu_to_le32(quad)
+#define CSR1212_LE64_TO_CPU(quad)	le64_to_cpu(quad)
+#define CSR1212_CPU_TO_LE64(quad)	cpu_to_le64(quad)
+
+#include <linux/errno.h>
+#define CSR1212_SUCCESS (0)
+#define CSR1212_EINVAL	(-EINVAL)
+#define CSR1212_ENOMEM	(-ENOMEM)
+#define CSR1212_ENOENT	(-ENOENT)
+#define CSR1212_EIO	(-EIO)
+#define CSR1212_EBUSY	(-EBUSY)
+
+#else	/* Userspace */
+
+#include <sys/types.h>
+#include <malloc.h>
+#define CSR1212_MALLOC(size)		malloc(size)
+#define CSR1212_FREE(ptr)		free(ptr)
+#include <endian.h>
+#if __BYTE_ORDER == __LITTLE_ENDIAN
+#include <byteswap.h>
+#define CSR1212_BE16_TO_CPU(quad)	bswap_16(quad)
+#define CSR1212_CPU_TO_BE16(quad)	bswap_16(quad)
+#define CSR1212_BE32_TO_CPU(quad)	bswap_32(quad)
+#define CSR1212_CPU_TO_BE32(quad)	bswap_32(quad)
+#define CSR1212_BE64_TO_CPU(quad)	bswap_64(quad)
+#define CSR1212_CPU_TO_BE64(quad)	bswap_64(quad)
+
+#define CSR1212_LE16_TO_CPU(quad)	(quad)
+#define CSR1212_CPU_TO_LE16(quad)	(quad)
+#define CSR1212_LE32_TO_CPU(quad)	(quad)
+#define CSR1212_CPU_TO_LE32(quad)	(quad)
+#define CSR1212_LE64_TO_CPU(quad)	(quad)
+#define CSR1212_CPU_TO_LE64(quad)	(quad)
+#else
+#define CSR1212_BE16_TO_CPU(quad)	(quad)
+#define CSR1212_CPU_TO_BE16(quad)	(quad)
+#define CSR1212_BE32_TO_CPU(quad)	(quad)
+#define CSR1212_CPU_TO_BE32(quad)	(quad)
+#define CSR1212_BE64_TO_CPU(quad)	(quad)
+#define CSR1212_CPU_TO_BE64(quad)	(quad)
+
+#define CSR1212_LE16_TO_CPU(quad)	bswap_16(quad)
+#define CSR1212_CPU_TO_LE16(quad)	bswap_16(quad)
+#define CSR1212_LE32_TO_CPU(quad)	bswap_32(quad)
+#define CSR1212_CPU_TO_LE32(quad)	bswap_32(quad)
+#define CSR1212_LE64_TO_CPU(quad)	bswap_64(quad)
+#define CSR1212_CPU_TO_LE64(quad)	bswap_64(quad)
+#endif
+
+#include <errno.h>
+#define CSR1212_SUCCESS (0)
+#define CSR1212_EINVAL	(EINVAL)
+#define CSR1212_ENOMEM	(ENOMEM)
+#define CSR1212_ENOENT	(ENOENT)
+#define CSR1212_EIO	(EIO)
+#define CSR1212_EBUSY	(EBUSY)
+
+#endif
+
+
+#define CSR1212_KV_VAL_MASK			0xffffff
+#define CSR1212_KV_KEY_SHIFT			24
+#define CSR1212_KV_KEY_TYPE_SHIFT		6
+#define CSR1212_KV_KEY_ID_MASK			0x3f
+#define CSR1212_KV_KEY_TYPE_MASK		0x3		/* After shift */
+
+
+/* CSR 1212 key types */
+#define CSR1212_KV_TYPE_IMMEDIATE		0
+#define CSR1212_KV_TYPE_CSR_OFFSET		1
+#define CSR1212_KV_TYPE_LEAF			2
+#define CSR1212_KV_TYPE_DIRECTORY		3
+
+
+/* CSR 1212 key ids */
+#define CSR1212_KV_ID_DESCRIPTOR		0x01
+#define CSR1212_KV_ID_BUS_DEPENDENT_INFO	0x02
+#define CSR1212_KV_ID_VENDOR			0x03
+#define CSR1212_KV_ID_HARDWARE_VERSION		0x04
+#define CSR1212_KV_ID_MODULE			0x07
+#define CSR1212_KV_ID_NODE_CAPABILITIES		0x0C
+#define CSR1212_KV_ID_EUI_64			0x0D
+#define CSR1212_KV_ID_UNIT			0x11
+#define CSR1212_KV_ID_SPECIFIER_ID		0x12
+#define CSR1212_KV_ID_VERSION			0x13
+#define CSR1212_KV_ID_DEPENDENT_INFO		0x14
+#define CSR1212_KV_ID_UNIT_LOCATION		0x15
+#define CSR1212_KV_ID_MODEL			0x17
+#define CSR1212_KV_ID_INSTANCE			0x18
+#define CSR1212_KV_ID_KEYWORD			0x19
+#define CSR1212_KV_ID_FEATURE			0x1A
+#define CSR1212_KV_ID_EXTENDED_ROM		0x1B
+#define CSR1212_KV_ID_EXTENDED_KEY_SPECIFIER_ID	0x1C
+#define CSR1212_KV_ID_EXTENDED_KEY		0x1D
+#define CSR1212_KV_ID_EXTENDED_DATA		0x1E
+#define CSR1212_KV_ID_MODIFIABLE_DESCRIPTOR	0x1F
+#define CSR1212_KV_ID_DIRECTORY_ID		0x20
+#define CSR1212_KV_ID_REVISION			0x21
+
+
+/* IEEE 1212 Address space map */
+#define CSR1212_ALL_SPACE_BASE			(0x000000000000ULL)
+#define CSR1212_ALL_SPACE_SIZE			(1ULL << 48)
+#define CSR1212_ALL_SPACE_END			(CSR1212_ALL_SPACE_BASE + CSR1212_ALL_SPACE_SIZE)
+
+#define  CSR1212_MEMORY_SPACE_BASE		(0x000000000000ULL)
+#define  CSR1212_MEMORY_SPACE_SIZE		((256ULL * (1ULL << 40)) - (512ULL * (1ULL << 20)))
+#define  CSR1212_MEMORY_SPACE_END		(CSR1212_MEMORY_SPACE_BASE + CSR1212_MEMORY_SPACE_SIZE)
+
+#define  CSR1212_PRIVATE_SPACE_BASE		(0xffffe0000000ULL)
+#define  CSR1212_PRIVATE_SPACE_SIZE		(256ULL * (1ULL << 20))
+#define  CSR1212_PRIVATE_SPACE_END		(CSR1212_PRIVATE_SPACE_BASE + CSR1212_PRIVATE_SPACE_SIZE)
+
+#define  CSR1212_REGISTER_SPACE_BASE		(0xfffff0000000ULL)
+#define  CSR1212_REGISTER_SPACE_SIZE		(256ULL * (1ULL << 20))
+#define  CSR1212_REGISTER_SPACE_END		(CSR1212_REGISTER_SPACE_BASE + CSR1212_REGISTER_SPACE_SIZE)
+
+#define  CSR1212_CSR_ARCH_REG_SPACE_BASE	(0xfffff0000000ULL)
+#define  CSR1212_CSR_ARCH_REG_SPACE_SIZE	(512)
+#define  CSR1212_CSR_ARCH_REG_SPACE_END		(CSR1212_CSR_ARCH_REG_SPACE_BASE + CSR1212_CSR_ARCH_REG_SPACE_SIZE)
+#define  CSR1212_CSR_ARCH_REG_SPACE_OFFSET	(CSR1212_CSR_ARCH_REG_SPACE_BASE - CSR1212_REGISTER_SPACE_BASE)
+
+#define  CSR1212_CSR_BUS_DEP_REG_SPACE_BASE	(0xfffff0000200ULL)
+#define  CSR1212_CSR_BUS_DEP_REG_SPACE_SIZE	(512)
+#define  CSR1212_CSR_BUS_DEP_REG_SPACE_END	(CSR1212_CSR_BUS_DEP_REG_SPACE_BASE + CSR1212_CSR_BUS_DEP_REG_SPACE_SIZE)
+#define  CSR1212_CSR_BUS_DEP_REG_SPACE_OFFSET	(CSR1212_CSR_BUS_DEP_REG_SPACE_BASE - CSR1212_REGISTER_SPACE_BASE)
+
+#define  CSR1212_CONFIG_ROM_SPACE_BASE		(0xfffff0000400ULL)
+#define  CSR1212_CONFIG_ROM_SPACE_SIZE		(1024)
+#define  CSR1212_CONFIG_ROM_SPACE_END		(CSR1212_CONFIG_ROM_SPACE_BASE + CSR1212_CONFIG_ROM_SPACE_SIZE)
+#define  CSR1212_CONFIG_ROM_SPACE_OFFSET	(CSR1212_CONFIG_ROM_SPACE_BASE - CSR1212_REGISTER_SPACE_BASE)
+
+#define  CSR1212_UNITS_SPACE_BASE		(0xfffff0000800ULL)
+#define  CSR1212_UNITS_SPACE_SIZE		((256ULL * (1ULL << 20)) - 2048)
+#define  CSR1212_UNITS_SPACE_END		(CSR1212_UNITS_SPACE_BASE + CSR1212_UNITS_SPACE_SIZE)
+#define  CSR1212_UNITS_SPACE_OFFSET		(CSR1212_UNITS_SPACE_BASE - CSR1212_REGISTER_SPACE_BASE)
+
+#define  CSR1212_EXTENDED_ROM_SIZE		(0x10000 * sizeof(u_int32_t))
+
+
+/* Config ROM image structures */
+struct csr1212_bus_info_block_img {
+	u_int8_t length;
+	u_int8_t crc_length;
+	u_int16_t crc;
+
+	/* Must be last */
+	u_int32_t data[0];	/* older gcc can't handle [] which is standard */
+};
+
+#define CSR1212_KV_KEY(quad)		(CSR1212_BE32_TO_CPU(quad) >> CSR1212_KV_KEY_SHIFT)
+#define CSR1212_KV_KEY_TYPE(quad)	(CSR1212_KV_KEY(quad) >> CSR1212_KV_KEY_TYPE_SHIFT)
+#define CSR1212_KV_KEY_ID(quad)		(CSR1212_KV_KEY(quad) & CSR1212_KV_KEY_ID_MASK)
+#define CSR1212_KV_VAL(quad)		(CSR1212_BE32_TO_CPU(quad) & CSR1212_KV_VAL_MASK)
+
+#define CSR1212_SET_KV_KEY(quad, key)	((quad) = \
+	CSR1212_CPU_TO_BE32(CSR1212_KV_VAL(quad) | ((key) << CSR1212_KV_KEY_SHIFT)))
+#define CSR1212_SET_KV_VAL(quad, val)	((quad) = \
+	CSR1212_CPU_TO_BE32((CSR1212_KV_KEY(quad) << CSR1212_KV_KEY_SHIFT) | (val)))
+#define CSR1212_SET_KV_TYPEID(quad, type, id)	((quad) = \
+	CSR1212_CPU_TO_BE32(CSR1212_KV_VAL(quad) | \
+	(((((type) & CSR1212_KV_KEY_TYPE_MASK) << CSR1212_KV_KEY_TYPE_SHIFT) | \
+	  ((id) & CSR1212_KV_KEY_ID_MASK)) << CSR1212_KV_KEY_SHIFT)))
+
+typedef u_int32_t csr1212_quad_t;
+
+
+struct csr1212_keyval_img {
+	u_int16_t length;
+	u_int16_t crc;
+
+	/* Must be last */
+	csr1212_quad_t data[0];	/* older gcc can't handle [] which is standard */
+};
+
+struct csr1212_leaf {
+	int len;
+	u_int32_t *data;
+};
+
+struct csr1212_dentry {
+	struct csr1212_dentry *next, *prev;
+	struct csr1212_keyval *kv;
+};
+
+struct csr1212_directory {
+	int len;
+	struct csr1212_dentry *dentries_head, *dentries_tail;
+};
+
+struct csr1212_keyval {
+	struct {
+		u_int8_t type;
+		u_int8_t id;
+	} key;
+	union {
+		u_int32_t immediate;
+		u_int32_t csr_offset;
+		struct csr1212_leaf leaf;
+		struct csr1212_directory directory;
+	} value;
+	struct csr1212_keyval *associate;
+	int refcnt;
+
+	/* used in generating and/or parsing CSR image */
+	struct csr1212_keyval *next, *prev;	/* flat list of CSR elements */
+	u_int32_t offset;	/* position in CSR from 0xffff f000 0000 */
+	u_int8_t valid;		/* flag indicating keyval has valid data*/
+};
+
+
+struct csr1212_cache_region {
+	struct csr1212_cache_region *next, *prev;
+	u_int32_t offset_start;		/* inclusive */
+	u_int32_t offset_end;		/* exclusive */
+};
+
+struct csr1212_csr_rom_cache {
+	struct csr1212_csr_rom_cache *next, *prev;
+	struct csr1212_cache_region *filled_head, *filled_tail;
+	struct csr1212_keyval *layout_head, *layout_tail;
+	size_t size;
+	u_int32_t offset;
+	struct csr1212_keyval *ext_rom;
+	size_t len;
+
+	/* Must be last */
+	u_int32_t data[0];	/* older gcc can't handle [] which is standard */
+};
+
+struct csr1212_csr {
+	size_t bus_info_len;	/* bus info block length in bytes */
+	size_t crc_len;		/* crc length in bytes */
+	u_int32_t *bus_info_data;	/* bus info data incl bus name and EUI */
+
+	void *private;		/* private, bus specific data */
+	struct csr1212_bus_ops *ops;
+
+	struct csr1212_keyval *root_kv;
+
+	int max_rom;		/* max bytes readable in Config ROM region */
+
+	/* Items below used for image parsing and generation */
+	struct csr1212_csr_rom_cache *cache_head, *cache_tail;
+};
+
+struct csr1212_bus_ops {
+	/* This function is used by csr1212 to read additional information
+	 * from remote nodes when parsing a Config ROM (i.e., read Config ROM
+	 * entries located in the Units Space.  Must return 0 on success
+	 * anything else indicates an error. */
+	int (*bus_read) (struct csr1212_csr *csr, u_int64_t addr,
+			 u_int16_t length, void *buffer, void *private);
+
+	/* This function is used by csr1212 to allocate a region in units space
+	 * in the event that Config ROM entries don't all fit in the predefined
+	 * 1K region.  The void *private parameter is private member of struct
+	 * csr1212_csr. */
+	u_int64_t (*allocate_addr_range) (u_int64_t size, u_int32_t alignment,
+					  void *private);
+
+
+	/* This function is used by csr1212 to release a region in units space
+	 * that is no longer needed. */
+	void (*release_addr) (u_int64_t addr, void *private);
+
+	/* This function is used by csr1212 to determine the max read request
+	 * supported by a remote node when reading the ConfigROM space.  Must
+	 * return 0, 1, or 2 per IEEE 1212.  */
+	int (*get_max_rom) (u_int32_t *bus_info, void *private);
+};
+
+
+
+
+/* Descriptor Leaf manipulation macros */
+#define CSR1212_DESCRIPTOR_LEAF_TYPE_SHIFT 24
+#define CSR1212_DESCRIPTOR_LEAF_SPECIFIER_ID_MASK 0xffffff
+#define CSR1212_DESCRIPTOR_LEAF_OVERHEAD (1 * sizeof(u_int32_t))
+
+#define CSR1212_DESCRIPTOR_LEAF_TYPE(kv) \
+	(CSR1212_BE32_TO_CPU((kv)->value.leaf.data[0]) >> CSR1212_DESCRIPTOR_LEAF_TYPE_SHIFT)
+#define CSR1212_DESCRIPTOR_LEAF_SPECIFIER_ID(kv) \
+	(CSR1212_BE32_TO_CPU((kv)->value.leaf.data[0]) & \
+	 CSR1212_DESCRIPTOR_LEAF_SPECIFIER_ID_MASK)
+#define CSR1212_DESCRIPTOR_LEAF_DATA(kv) \
+	(&((kv)->value.leaf.data[1]))
+
+#define CSR1212_DESCRIPTOR_LEAF_SET_TYPE(kv, type) \
+	((kv)->value.leaf.data[0] = \
+	 CSR1212_CPU_TO_BE32(CSR1212_DESCRIPTOR_LEAF_SPECIFIER_ID(kv) | \
+			     ((type) << CSR1212_DESCRIPTOR_LEAF_TYPE_SHIFT)))
+#define CSR1212_DESCRIPTOR_LEAF_SET_SPECIFIER_ID(kv, spec_id) \
+	((kv)->value.leaf.data[0] = \
+	 CSR1212_CPU_TO_BE32((CSR1212_DESCRIPTOR_LEAF_TYPE(kv) << \
+			      CSR1212_DESCRIPTOR_LEAF_TYPE_SHIFT) | \
+			     ((spec_id) & CSR1212_DESCRIPTOR_LEAF_SPECIFIER_ID_MASK)))
+
+/* Text Descriptor Leaf manipulation macros */
+#define CSR1212_TEXTUAL_DESCRIPTOR_LEAF_WIDTH_SHIFT 28
+#define CSR1212_TEXTUAL_DESCRIPTOR_LEAF_WIDTH_MASK 0xf /* after shift */
+#define CSR1212_TEXTUAL_DESCRIPTOR_LEAF_CHAR_SET_SHIFT 16
+#define CSR1212_TEXTUAL_DESCRIPTOR_LEAF_CHAR_SET_MASK 0xfff  /* after shift */
+#define CSR1212_TEXTUAL_DESCRIPTOR_LEAF_LANGUAGE_MASK 0xffff
+#define CSR1212_TEXTUAL_DESCRIPTOR_LEAF_OVERHEAD (1 * sizeof(u_int32_t))
+
+#define CSR1212_TEXTUAL_DESCRIPTOR_LEAF_WIDTH(kv) \
+	(CSR1212_BE32_TO_CPU((kv)->value.leaf.data[1]) >> \
+	 CSR1212_TEXTUAL_DESCRIPTOR_LEAF_WIDTH_SHIFT)
+#define CSR1212_TEXTUAL_DESCRIPTOR_LEAF_CHAR_SET(kv) \
+	((CSR1212_BE32_TO_CPU((kv)->value.leaf.data[1]) >> \
+			     CSR1212_TEXTUAL_DESCRIPTOR_LEAF_CHAR_SET_SHIFT) & \
+			    CSR1212_TEXTUAL_DESCRIPTOR_LEAF_CHAR_SET_MASK)
+#define CSR1212_TEXTUAL_DESCRIPTOR_LEAF_LANGUAGE(kv) \
+	(CSR1212_BE32_TO_CPU((kv)->value.leaf.data[1]) & \
+	 CSR1212_TEXTUAL_DESCRIPTOR_LEAF_LANGUAGE_MASK)
+#define CSR1212_TEXTUAL_DESCRIPTOR_LEAF_DATA(kv) \
+	(&((kv)->value.leaf.data[2]))
+
+#define CSR1212_TEXTUAL_DESCRIPTOR_LEAF_SET_WIDTH(kv, width) \
+	((kv)->value.leaf.data[1] = \
+	 ((kv)->value.leaf.data[1] & \
+	  CSR1212_CPU_TO_BE32(~(CSR1212_TEXTUAL_DESCRIPTOR_LEAF_WIDTH_MASK << \
+				CSR1212_TEXTUAL_DESCRIPTOR_LEAF_WIDTH_SHIFT))) | \
+	 CSR1212_CPU_TO_BE32(((width) & \
+			      CSR1212_TEXTUAL_DESCRIPTOR_LEAF_WIDTH_MASK) << \
+			     CSR1212_TEXTUAL_DESCRIPTOR_LEAF_WIDTH_SHIFT))
+#define CSR1212_TEXTUAL_DESCRIPTOR_LEAF_SET_CHAR_SET(kv, char_set) \
+	((kv)->value.leaf.data[1] = \
+	 ((kv)->value.leaf.data[1] & \
+	  CSR1212_CPU_TO_BE32(~(CSR1212_TEXTUAL_DESCRIPTOR_LEAF_CHAR_SET_MASK << \
+				CSR1212_TEXTUAL_DESCRIPTOR_LEAF_CHAR_SET_SHIFT))) | \
+	 CSR1212_CPU_TO_BE32(((char_set) & \
+			      CSR1212_TEXTUAL_DESCRIPTOR_LEAF_CHAR_SET_MASK) << \
+			     CSR1212_TEXTUAL_DESCRIPTOR_LEAF_CHAR_SET_SHIFT))
+#define CSR1212_TEXTUAL_DESCRIPTOR_LEAF_SET_LANGUAGE(kv, language) \
+	((kv)->value.leaf.data[1] = \
+	 ((kv)->value.leaf.data[1] & \
+	  CSR1212_CPU_TO_BE32(~(CSR1212_TEXTUAL_DESCRIPTOR_LEAF_LANGUAGE_MASK))) | \
+	 CSR1212_CPU_TO_BE32(((language) & \
+			      CSR1212_TEXTUAL_DESCRIPTOR_LEAF_LANGUAGE_MASK)))
+
+
+/* Icon Descriptor Leaf manipulation macros */
+#define CSR1212_ICON_DESCRIPTOR_LEAF_VERSION_MASK 0xffffff
+#define CSR1212_ICON_DESCRIPTOR_LEAF_PALETTE_DEPTH_SHIFT 30
+#define CSR1212_ICON_DESCRIPTOR_LEAF_PALETTE_DEPTH_MASK 0x3 /* after shift */
+#define CSR1212_ICON_DESCRIPTOR_LEAF_COLOR_SPACE_SHIFT 16
+#define CSR1212_ICON_DESCRIPTOR_LEAF_COLOR_SPACE_MASK 0xf /* after shift */
+#define CSR1212_ICON_DESCRIPTOR_LEAF_LANGUAGE_MASK 0xffff
+#define CSR1212_ICON_DESCRIPTOR_LEAF_HSCAN_SHIFT 16
+#define CSR1212_ICON_DESCRIPTOR_LEAF_HSCAN_MASK 0xffff /* after shift */
+#define CSR1212_ICON_DESCRIPTOR_LEAF_VSCAN_MASK 0xffff
+#define CSR1212_ICON_DESCRIPTOR_LEAF_OVERHEAD (3 * sizeof(u_int32_t))
+
+#define CSR1212_ICON_DESCRIPTOR_LEAF_VERSION(kv) \
+	(CSR1212_BE32_TO_CPU((kv)->value.leaf.data[2]) & \
+	 CSR1212_ICON_DESCRIPTOR_LEAF_VERSION_MASK)
+
+#define CSR1212_ICON_DESCRIPTOR_LEAF_PALETTE_DEPTH(kv) \
+	(CSR1212_BE32_TO_CPU((kv)->value.leaf.data[3]) >> \
+	 CSR1212_ICON_DESCRIPTOR_LEAF_PALETTE_DEPTH_SHIFT)
+
+#define CSR1212_ICON_DESCRIPTOR_LEAF_COLOR_SPACE(kv) \
+	((CSR1212_BE32_TO_CPU((kv)->value.leaf.data[3]) >> \
+	  CSR1212_ICON_DESCRIPTOR_LEAF_COLOR_SPACE_SHIFT) & \
+	 CSR1212_ICON_DESCRIPTOR_LEAF_COLOR_SPACE_MASK)
+
+#define CSR1212_ICON_DESCRIPTOR_LEAF_LANGUAGE(kv) \
+	(CSR1212_BE32_TO_CPU((kv)->value.leaf.data[3]) & \
+	 CSR1212_ICON_DESCRIPTOR_LEAF_LANGUAGE_MASK)
+
+#define CSR1212_ICON_DESCRIPTOR_LEAF_HSCAN(kv) \
+	((CSR1212_BE32_TO_CPU((kv)->value.leaf.data[4]) >> \
+	  CSR1212_ICON_DESCRIPTOR_LEAF_COLOR_HSCAN_SHIFT) & \
+	 CSR1212_ICON_DESCRIPTOR_LEAF_COLOR_HSCAN_MASK)
+
+#define CSR1212_ICON_DESCRIPTOR_LEAF_VSCAN(kv) \
+	(CSR1212_BE32_TO_CPU((kv)->value.leaf.data[4]) & \
+	 CSR1212_ICON_DESCRIPTOR_LEAF_VSCAN_MASK)
+
+#define CSR1212_ICON_DESCRIPTOR_LEAF_PALETTE(kv) \
+	(&((kv)->value.leaf.data[5]))
+
+static inline u_int32_t *CSR1212_ICON_DESCRIPTOR_LEAF_PIXELS(struct csr1212_keyval *kv)
+{
+	static const int pd[4] = { 0, 4, 16, 256 };
+	static const int cs[16] = { 4, 2 };
+	int ps = pd[CSR1212_ICON_DESCRIPTOR_LEAF_PALETTE_DEPTH(kv)];
+	
+	return &kv->value.leaf.data[5 +
+				    (ps * cs[CSR1212_ICON_DESCRIPTOR_LEAF_COLOR_SPACE(kv)]) /
+			   sizeof(u_int32_t)];
+}
+
+#define CSR1212_ICON_DESCRIPTOR_LEAF_SET_VERSION(kv, version) \
+	((kv)->value.leaf.data[2] = \
+	 ((kv)->value.leaf.data[2] & \
+	  CSR1212_CPU_TO_BE32(~(CSR1212_ICON_DESCRIPTOR_LEAF_VERSION_MASK))) | \
+	 CSR1212_CPU_TO_BE32(((version) & \
+			      CSR1212_ICON_DESCRIPTOR_LEAF_VERSION_MASK)))
+
+#define CSR1212_ICON_DESCRIPTOR_LEAF_SET_PALETTE_DEPTH(kv, palette_depth) \
+	((kv)->value.leaf.data[3] = \
+	 ((kv)->value.leaf.data[3] & \
+	  CSR1212_CPU_TO_BE32(~(CSR1212_ICON_DESCRIPTOR_LEAF_PALETTE_DEPTH_MASK << \
+				CSR1212_ICON_DESCRIPTOR_LEAF_PALETTE_DEPTH_SHIFT))) | \
+	 CSR1212_CPU_TO_BE32(((palette_depth) & \
+			      CSR1212_ICON_DESCRIPTOR_LEAF_PALETTE_DEPTH_MASK) << \
+			     CSR1212_ICON_DESCRIPTOR_LEAF_PALETTE_DEPTH_SHIFT))
+
+#define CSR1212_ICON_DESCRIPTOR_LEAF_SET_COLOR_SPACE(kv, color_space) \
+	((kv)->value.leaf.data[3] = \
+	 ((kv)->value.leaf.data[3] & \
+	  CSR1212_CPU_TO_BE32(~(CSR1212_ICON_DESCRIPTOR_LEAF_COLOR_SPACE_MASK << \
+				CSR1212_ICON_DESCRIPTOR_LEAF_COLOR_SPACE_SHIFT))) | \
+	 CSR1212_CPU_TO_BE32(((color_space) & \
+			      CSR1212_ICON_DESCRIPTOR_LEAF_COLOR_SPACE_MASK) << \
+			     CSR1212_ICON_DESCRIPTOR_LEAF_COLOR_SPACE_SHIFT))
+
+#define CSR1212_ICON_DESCRIPTOR_LEAF_SET_LANGUAGE(kv, language) \
+	((kv)->value.leaf.data[3] = \
+	 ((kv)->value.leaf.data[3] & \
+	  CSR1212_CPU_TO_BE32(~(CSR1212_ICON_DESCRIPTOR_LEAF_LANGUAGE_MASK))) | \
+	 CSR1212_CPU_TO_BE32(((language) & \
+			      CSR1212_ICON_DESCRIPTOR_LEAF_LANGUAGE_MASK)))
+
+#define CSR1212_ICON_DESCRIPTOR_LEAF_SET_HSCAN(kv, hscan) \
+	((kv)->value.leaf.data[4] = \
+	 ((kv)->value.leaf.data[4] & \
+	  CSR1212_CPU_TO_BE32(~(CSR1212_ICON_DESCRIPTOR_LEAF_HSCAN_MASK << \
+				CSR1212_ICON_DESCRIPTOR_LEAF_HSCAN_SHIFT))) | \
+	 CSR1212_CPU_TO_BE32(((hscan) & \
+			      CSR1212_ICON_DESCRIPTOR_LEAF_HSCAN_MASK) << \
+			     CSR1212_ICON_DESCRIPTOR_LEAF_HSCAN_SHIFT))
+
+#define CSR1212_ICON_DESCRIPTOR_LEAF_SET_VSCAN(kv, vscan) \
+	((kv)->value.leaf.data[4] = \
+	 (((kv)->value.leaf.data[4] & \
+	  CSR1212_CPU_TO_BE32(~CSR1212_ICON_DESCRIPTOR_LEAF_VSCAN_MASK))) | \
+	 CSR1212_CPU_TO_BE32(((vscan) & \
+			      CSR1212_ICON_DESCRIPTOR_LEAF_VSCAN_MASK)))
+
+
+/* Modifiable Descriptor Leaf manipulation macros */
+#define CSR1212_MODIFIABLE_DESCRIPTOR_LEAF_MAX_SIZE_SHIFT 16
+#define CSR1212_MODIFIABLE_DESCRIPTOR_LEAF_MAX_SIZE_MASK 0xffff
+#define CSR1212_MODIFIABLE_DESCRIPTOR_LEAF_ADDR_HI_SHIFT 32
+#define CSR1212_MODIFIABLE_DESCRIPTOR_LEAF_ADDR_HI_MASK 0xffff
+#define CSR1212_MODIFIABLE_DESCRIPTOR_LEAF_ADDR_LO_MASK 0xffffffffULL
+
+#define CSR1212_MODIFIABLE_DESCRIPTOR_MAX_SIZE(kv) \
+	CSR1212_BE16_TO_CPU((kv)->value.leaf.data[0] >> CSR1212_MODIFIABLE_DESCRIPTOR_MAX_SIZE_SHIFT)
+
+#define CSR1212_MODIFIABLE_DESCRIPTOR_ADDRESS(kv) \
+	(CSR1212_BE16_TO_CPU(((u_int64_t)((kv)->value.leaf.data[0])) << \
+			     CSR1212_MODIFIABLE_DESCRIPTOR_ADDR_HI_SHIFT) | \
+	 CSR1212_BE32_TO_CPU((kv)->value.leaf.data[1]))
+
+#define CSR1212_MODIFIABLE_DESCRIPTOR_SET_MAX_SIZE(kv, size) \
+	((kv)->value.leaf.data[0] = \
+	 ((kv)->value.leaf.data[0] & \
+	  CSR1212_CPU_TO_BE32(~(CSR1212_MODIFIABLE_DESCRIPTOR_LEAF_MAX_SIZE_MASK << \
+				CSR1212_MODIFIABLE_DESCRIPTOR_LEAF_MAX_SIZE_SHIFT))) | \
+	 CSR1212_CPU_TO_BE32(((size) & \
+			      CSR1212_MODIFIABLE_DESCRIPTOR_LEAF_MAX_SIZE_MASK) << \
+			     CSR1212_MODIFIABLE_DESCRIPTOR_LEAF_MAX_SIZE_SHIFT))
+
+#define CSR1212_MODIFIABLE_DESCRIPTOR_SET_ADDRESS_HI(kv, addr) \
+	((kv)->value.leaf.data[0] = \
+	 ((kv)->value.leaf.data[0] & \
+	  CSR1212_CPU_TO_BE32(~(CSR1212_MODIFIABLE_DESCRIPTOR_LEAF_ADDR_HI_MASK))) | \
+	  CSR1212_CPU_TO_BE32(((addr) & \
+			       CSR1212_MODIFIABLE_DESCRIPTOR_LEAF_ADDR_HI_MASK)))
+
+#define CSR1212_MODIFIABLE_DESCRIPTOR_SET_ADDRESS_LO(kv, addr) \
+	((kv)->value.leaf.data[1] = \
+	 CSR1212_CPU_TO_BE32(addr & CSR1212_MODIFIABLE_DESCRIPTOR_LEAF_ADDR_LO_MASK))
+
+
+
+/* The following 2 function are for creating new Configuration ROM trees.  The
+ * first function is used for both creating local trees and parsing remote
+ * trees.  The second function adds pertinent information to local Configuration
+ * ROM trees - namely data for the bus information block. */
+extern struct csr1212_csr *csr1212_create_csr(struct csr1212_bus_ops *ops,
+					      size_t bus_info_size,
+					      void *private);
+extern void csr1212_init_local_csr(struct csr1212_csr *csr,
+				   const u_int32_t *bus_info_data, int max_rom);
+
+
+/* The following function destroys a Configuration ROM tree and release all
+ * memory taken by the tree. */
+extern void csr1212_destroy_csr(struct csr1212_csr *csr);
+
+
+/* The following set of functions are fore creating new keyvals for placement in
+ * a Configuration ROM tree.  Code that creates new keyvals with these functions
+ * must release those keyvals with csr1212_release_keyval() when they are no
+ * longer needed. */
+extern struct csr1212_keyval *csr1212_new_immediate(u_int8_t key, u_int32_t value);
+extern struct csr1212_keyval *csr1212_new_leaf(u_int8_t key, const void *data,
+					       size_t data_len);
+extern struct csr1212_keyval *csr1212_new_csr_offset(u_int8_t key,
+						     u_int32_t csr_offset);
+extern struct csr1212_keyval *csr1212_new_directory(u_int8_t key);
+extern struct csr1212_keyval *csr1212_new_extended_immediate(u_int32_t spec,
+							     u_int32_t key,
+							     u_int32_t value);
+extern struct csr1212_keyval *csr1212_new_extended_leaf(u_int32_t spec,
+							u_int32_t key,
+							const void *data,
+							size_t data_len);
+extern struct csr1212_keyval *csr1212_new_descriptor_leaf(u_int8_t dtype,
+							  u_int32_t specifier_id,
+							  const void *data,
+							  size_t data_len);
+extern struct csr1212_keyval *csr1212_new_textual_descriptor_leaf(u_int8_t cwidth,
+								  u_int16_t cset,
+								  u_int16_t language,
+								  const void *data,
+								  size_t data_len);
+extern struct csr1212_keyval *csr1212_new_string_descriptor_leaf(const char *s);
+extern struct csr1212_keyval *csr1212_new_icon_descriptor_leaf(u_int32_t version,
+							       u_int8_t palette_depth,
+							       u_int8_t color_space,
+							       u_int16_t language,
+							       u_int16_t hscan,
+							       u_int16_t vscan,
+							       u_int32_t *palette,
+							       u_int32_t *pixels);
+extern struct csr1212_keyval *csr1212_new_modifiable_descriptor_leaf(u_int16_t max_size,
+								     u_int64_t address);
+extern struct csr1212_keyval *csr1212_new_keyword_leaf(int strc,
+						       const char *strv[]);
+
+
+/* The following functions manage association between keyvals.  Typically,
+ * Descriptor Leaves and Directories will be associated with another keyval and
+ * it is desirable for the Descriptor keyval to be place immediately after the
+ * keyval that it is associated with.*/
+extern int csr1212_associate_keyval(struct csr1212_keyval *kv,
+				    struct csr1212_keyval *associate);
+extern void csr1212_disassociate_keyval(struct csr1212_keyval *kv);
+
+
+/* The following functions manage the association of a keyval and directories.
+ * A keyval may be attached to more than one directory. */
+extern int csr1212_attach_keyval_to_directory(struct csr1212_keyval *dir,
+					      struct csr1212_keyval *kv);
+extern void csr1212_detach_keyval_from_directory(struct csr1212_keyval *dir,
+						 struct csr1212_keyval *kv);
+
+
+/* The following functions create a Configuration ROM image from the tree of
+ * keyvals provided.  csr1212_generate_csr_image() creates a complete image in
+ * the list of caches available via csr->cache_head.  The other functions are
+ * provided should there be a need to create a flat image without restrictions
+ * placed by IEEE 1212. */
+extern struct csr1212_keyval *csr1212_generate_positions(struct csr1212_csr_rom_cache *cache,
+							 struct csr1212_keyval *start_kv,
+							 int start_pos);
+extern size_t csr1212_generate_layout_order(struct csr1212_keyval *kv);
+extern void csr1212_fill_cache(struct csr1212_csr_rom_cache *cache);
+extern int csr1212_generate_csr_image(struct csr1212_csr *csr);
+
+
+/* This is a convience function for reading a block of data out of one of the
+ * caches in the csr->cache_head list. */
+extern int csr1212_read(struct csr1212_csr *csr, u_int32_t offset, void *buffer,
+			u_int32_t len);
+
+
+/* The following functions are in place for parsing Configuration ROM images.
+ * csr1212_parse_keyval() is used should there be a need to directly parse a
+ * Configuration ROM directly. */
+extern int csr1212_parse_keyval(struct csr1212_keyval *kv,
+				struct csr1212_csr_rom_cache *cache);
+extern int csr1212_parse_csr(struct csr1212_csr *csr);
+
+/* These are internal functions referenced by inline functions below. */
+extern int _csr1212_read_keyval(struct csr1212_csr *csr, struct csr1212_keyval *kv);
+extern void _csr1212_destroy_keyval(struct csr1212_keyval *kv);
+
+
+/* This function allocates a new cache which may be used for either parsing or
+ * generating sub-sets of Configuration ROM images. */
+static inline struct csr1212_csr_rom_cache *csr1212_rom_cache_malloc(u_int32_t offset,
+								     size_t size)
+{
+	struct csr1212_csr_rom_cache *cache;
+
+	cache = CSR1212_MALLOC(sizeof(struct csr1212_csr_rom_cache) + size);
+	if (!cache)
+		return NULL;
+
+	cache->next = NULL;
+	cache->prev = NULL;
+	cache->filled_head = NULL;
+	cache->filled_tail = NULL;
+	cache->layout_head = NULL;
+	cache->layout_tail = NULL;
+	cache->offset = offset;
+	cache->size = size;
+	cache->ext_rom = NULL;
+
+	return cache;
+}
+
+
+/* This function ensures that a keyval contains data when referencing a keyval
+ * created by parsing a Configuration ROM. */
+static inline struct csr1212_keyval *csr1212_get_keyval(struct csr1212_csr *csr,
+							struct csr1212_keyval *kv)
+{
+	if (!kv)
+		return NULL;
+	if (!kv->valid)
+		if (_csr1212_read_keyval(csr, kv) != CSR1212_SUCCESS)
+			return NULL;
+	return kv;
+}
+
+
+/* This function increments the reference count for a keyval should there be a
+ * need for code to retain a keyval that has been parsed. */
+static inline void csr1212_keep_keyval(struct csr1212_keyval *kv)
+{
+	kv->refcnt++;
+}
+
+
+/* This function decrements a keyval's reference count and will destroy the
+ * keyval when there are no more users of the keyval.  This should be called by
+ * any code that calls csr1212_keep_keyval() or any of the keyval creation
+ * routines csr1212_new_*(). */
+static inline void csr1212_release_keyval(struct csr1212_keyval *kv)
+{
+	if (kv->refcnt > 1)
+		kv->refcnt--;
+	else
+		_csr1212_destroy_keyval(kv);
+}
+
+
+/*
+ * This macro allows for looping over the keyval entries in a directory and it
+ * ensures that keyvals from remote ConfigROMs are parsed properly.
+ *
+ * _csr is a struct csr1212_csr * that points to CSR associated with dir.
+ * _kv is a struct csr1212_keyval * that'll point to the current keyval (loop index).
+ * _dir is a struct csr1212_keyval * that points to the directory to be looped.
+ * _pos is a struct csr1212_dentry * that is used internally for indexing.
+ * 
+ * kv will be NULL upon exit of the loop.
+ */
+#define csr1212_for_each_dir_entry(_csr, _kv, _dir, _pos)			\
+	for (csr1212_get_keyval((_csr), (_dir)),				\
+	     _pos = (_dir)->value.directory.dentries_head,			\
+	     _kv = (_pos) ? csr1212_get_keyval((_csr), _pos->kv) : NULL;	\
+	     (_kv) && (_pos);							\
+	     (_kv->associate == NULL) ?						\
+		     ((_pos = _pos->next), 					\
+		      (_kv = (_pos) ? csr1212_get_keyval((_csr), _pos->kv) :	\
+                          NULL)) :						\
+		     (_kv = csr1212_get_keyval((_csr), _kv->associate)))
+
+
+
+#endif /* __CSR1212_H__ */
diff -Nru a/drivers/ieee1394/eth1394.c b/drivers/ieee1394/eth1394.c
--- a/drivers/ieee1394/eth1394.c	Wed Feb 11 22:28:46 2004
+++ b/drivers/ieee1394/eth1394.c	Wed Feb 11 22:28:46 2004
@@ -29,7 +29,6 @@
  *
  * TODO:
  * RFC 2734 related:
- * - Add Config ROM entry
  * - Add MCAP. Limited Multicast exists only to 224.0.0.1 and 224.0.0.2.
  *
  * Non-RFC 2734 related:
@@ -38,7 +37,6 @@
  * - Convert kmalloc/kfree for link fragments to use kmem_cache_* instead
  * - Stability improvements
  * - Performance enhancements
- * - Change hardcoded 1394 bus address region to a dynamic memory space allocation
  * - Consider garbage collecting old partial datagrams after X amount of time
  */
 
@@ -69,6 +67,7 @@
 #include <asm/semaphore.h>
 #include <net/arp.h>
 
+#include "csr1212.h"
 #include "ieee1394_types.h"
 #include "ieee1394_core.h"
 #include "ieee1394_transactions.h"
@@ -89,7 +88,7 @@
 #define TRACE() printk(KERN_ERR "%s:%s[%d] ---- TRACE\n", driver_name, __FUNCTION__, __LINE__)
 
 static char version[] __devinitdata =
-	"$Rev: 1096 $ Ben Collins <bcollins@debian.org>";
+	"$Rev: 1118 $ Ben Collins <bcollins@debian.org>";
 
 struct fragment_info {
 	struct list_head list;
@@ -107,8 +106,35 @@
 	struct list_head frag_info;
 };
 
+static struct csr1212_keyval *eth1394_ud = NULL;
+
+struct pdg_list {
+	struct list_head list;		/* partial datagram list per node	*/
+	unsigned int sz;		/* partial datagram list size per node	*/
+	spinlock_t lock;		/* partial datagram lock		*/
+};
+
+struct eth1394_host_info {
+	struct hpsb_host *host;
+	struct net_device *dev;
+};
+
+struct eth1394_node_ref {
+	struct unit_directory *ud;
+	struct list_head list;
+};
+
+struct eth1394_node_info {
+	u16 maxpayload;			/* Max payload			*/
+	u8 sspd;			/* Max speed			*/
+	u64 fifo;			/* FIFO address			*/
+	struct pdg_list pdg;		/* partial RX datagram lists	*/
+	int dgl;			/* Outgoing datagram label	*/
+};
+
 /* Our ieee1394 highlevel driver */
-static const char driver_name[] = "eth1394";
+#define ETH1394_DRIVER_NAME "IP/1394"
+static const char driver_name[] = ETH1394_DRIVER_NAME;
 
 static kmem_cache_t *packet_task_cache;
 
@@ -188,94 +214,36 @@
 };
 
 
-static void eth1394_iso_shutdown(struct eth1394_priv *priv)
-{
-	priv->bc_state = ETHER1394_BC_CLOSED;
-
-	if (priv->iso != NULL) {
-		if (!in_interrupt())
-			hpsb_iso_shutdown(priv->iso);
-		priv->iso = NULL;
-	}
-}
-
-static int ether1394_init_bc(struct net_device *dev)
-{
-	struct eth1394_priv *priv = (struct eth1394_priv *)dev->priv;
-
-	/* First time sending?  Need a broadcast channel for ARP and for
-	 * listening on */
-	if (priv->bc_state == ETHER1394_BC_CHECK) {
-		quadlet_t bc;
-
-		/* Get the local copy of the broadcast channel and check its
-		 * validity (the IRM should validate it for us) */
-
-		bc = priv->host->csr.broadcast_channel;
-
-		if ((bc & 0xc0000000) != 0xc0000000) {
-			/* broadcast channel not validated yet */
-			ETH1394_PRINT(KERN_WARNING, dev->name,
-				      "Error BROADCAST_CHANNEL register valid "
-				      "bit not set, can't send IP traffic\n");
-
-			eth1394_iso_shutdown(priv);
-
-			return -EAGAIN;
-		}
-		if (priv->broadcast_channel != (bc & 0x3f)) {
-			/* This really shouldn't be possible, but just in case
-			 * the IEEE 1394 spec changes regarding broadcast
-			 * channels in the future. */
-
-			eth1394_iso_shutdown(priv);
-
-			if (in_interrupt())
-				return -EAGAIN;
-
-			priv->broadcast_channel = bc & 0x3f;
-			ETH1394_PRINT(KERN_INFO, dev->name,
-				      "Changing to broadcast channel %d...\n",
-				      priv->broadcast_channel);
-
-			priv->iso = hpsb_iso_recv_init(priv->host, 16 * 4096,
-						       16, priv->broadcast_channel,
-						       HPSB_ISO_DMA_PACKET_PER_BUFFER, 1, ether1394_iso);
-			if (priv->iso == NULL) {
-				ETH1394_PRINT(KERN_ERR, dev->name,
-					      "failed to change broadcast "
-					      "channel\n");
-				return -EAGAIN;
-			}
-		}
-		if (hpsb_iso_recv_start(priv->iso, -1, (1 << 3), -1) < 0) {
-			ETH1394_PRINT(KERN_ERR, dev->name,
-				      "Could not start data stream reception\n");
-
-			eth1394_iso_shutdown(priv);
-
-			return -EAGAIN;
-		}
-		priv->bc_state = ETHER1394_BC_OPENED;
-	}
-    
-	return 0;
-}
-
 /* This is called after an "ifup" */
 static int ether1394_open (struct net_device *dev)
 {
 	struct eth1394_priv *priv = (struct eth1394_priv *)dev->priv;
-	unsigned long flags;
-	int ret;
+	int ret = 0;
 
 	/* Something bad happened, don't even try */
-	if (priv->bc_state == ETHER1394_BC_CLOSED)
-		return -EAGAIN;
-
-	spin_lock_irqsave(&priv->lock, flags);
-	ret = ether1394_init_bc(dev);
-	spin_unlock_irqrestore(&priv->lock, flags);
+	if (priv->bc_state == ETHER1394_BC_ERROR) {
+		/* we'll try again */
+		priv->iso = hpsb_iso_recv_init(priv->host,
+					       ETHER1394_GASP_BUFFERS * 2 *
+					       (1 << (priv->host->csr.max_rec +
+						      1)),
+					       ETHER1394_GASP_BUFFERS,
+					       priv->broadcast_channel,
+					       HPSB_ISO_DMA_PACKET_PER_BUFFER,
+					       1, ether1394_iso);
+		if (priv->iso == NULL) {
+			ETH1394_PRINT(KERN_ERR, dev->name,
+				      "Could not allocate isochronous receive "
+				      "context for the broadcast channel\n");
+			priv->bc_state = ETHER1394_BC_ERROR;
+			ret = -EAGAIN;
+		} else {
+			if (hpsb_iso_recv_start(priv->iso, -1, (1 << 3), -1) < 0)
+				priv->bc_state = ETHER1394_BC_STOPPED;
+			else
+				priv->bc_state = ETHER1394_BC_RUNNING;
+		}
+	}
 
 	if (ret)
 		return ret;
@@ -312,66 +280,227 @@
 static int ether1394_change_mtu(struct net_device *dev, int new_mtu)
 {
 	struct eth1394_priv *priv = (struct eth1394_priv *)dev->priv;
-	int phy_id = NODEID_TO_NODE(priv->host->node_id);
 
-	if ((new_mtu < 68) || (new_mtu > min(ETH1394_DATA_LEN, (int)(priv->maxpayload[phy_id] -
-					     (sizeof(union eth1394_hdr) + ETHER1394_GASP_OVERHEAD)))))
+	if ((new_mtu < 68) ||
+	    (new_mtu > min(ETH1394_DATA_LEN,
+			   (int)((1 << (priv->host->csr.max_rec + 1)) -
+				 (sizeof(union eth1394_hdr) +
+				  ETHER1394_GASP_OVERHEAD)))))
 		return -EINVAL;
 	dev->mtu = new_mtu;
 	return 0;
 }
 
-static inline void ether1394_register_limits(int nodeid, u16 maxpayload,
-					     unsigned char sspd, u64 eui, u64 fifo,
-					     struct eth1394_priv *priv)
+
+/******************************************
+ * 1394 bus activity functions
+ ******************************************/
+
+static struct eth1394_node_ref *eth1394_find_node(struct list_head *inl,
+						  struct unit_directory *ud)
 {
-	if (nodeid < 0 || nodeid >= ALL_NODES) {
-		ETH1394_PRINT_G (KERN_ERR, "Cannot register invalid nodeid %d\n", nodeid);
-		return;
+	struct eth1394_node_ref *node;
+
+	list_for_each_entry(node, inl, list)
+		if (node->ud == ud)
+			return node;
+
+	return NULL;
+}
+
+static struct eth1394_node_ref *eth1394_find_node_guid(struct list_head *inl,
+						       u64 guid)
+{
+	struct eth1394_node_ref *node;
+
+	list_for_each_entry(node, inl, list)
+		if (node->ud->ne->guid == guid)
+			return node;
+
+	return NULL;
+}
+
+static struct eth1394_node_ref *eth1394_find_node_nodeid(struct list_head *inl,
+							 nodeid_t nodeid)
+{
+	struct eth1394_node_ref *node;
+	list_for_each_entry(node, inl, list) {
+		if (node->ud->ne->nodeid == nodeid)
+			return node;
 	}
 
-	priv->maxpayload[nodeid]	= maxpayload;
-	priv->sspd[nodeid]		= sspd;
-	priv->fifo[nodeid]		= fifo;
-	priv->eui[nodeid]		= eui;
+	return NULL;
+}
 
-	priv->maxpayload[ALL_NODES] = min(priv->maxpayload[ALL_NODES], maxpayload);
-	priv->sspd[ALL_NODES] = min(priv->sspd[ALL_NODES], sspd);
+static int eth1394_probe(struct device *dev)
+{
+	struct unit_directory *ud;
+	struct eth1394_host_info *hi;
+	struct eth1394_priv *priv;
+	struct eth1394_node_ref *new_node;
+	struct eth1394_node_info *node_info;
 
-	return;
+	ud = container_of(dev, struct unit_directory, device);
+
+	hi = hpsb_get_hostinfo(&eth1394_highlevel, ud->ne->host);
+	if (!hi)
+		return -ENOENT;
+
+	new_node = kmalloc(sizeof(struct eth1394_node_ref),
+			   in_interrupt() ? GFP_ATOMIC : GFP_KERNEL);
+	if (!new_node)
+		return -ENOMEM;
+
+	node_info = kmalloc(sizeof(struct eth1394_node_info),
+			    in_interrupt() ? GFP_ATOMIC : GFP_KERNEL);
+	if (!node_info) {
+		kfree(new_node);
+		return -ENOMEM;
+	}
+
+	spin_lock_init(&node_info->pdg.lock);
+	INIT_LIST_HEAD(&node_info->pdg.list);
+	node_info->pdg.sz = 0;
+	node_info->fifo = ETHER1394_INVALID_ADDR;
+
+	ud->device.driver_data = node_info;
+	new_node->ud = ud;
+
+	priv = (struct eth1394_priv *)hi->dev->priv;
+	list_add_tail(&new_node->list, &priv->ip_node_list);
+
+	return 0;
 }
 
+static int eth1394_remove(struct device *dev)
+{
+	struct unit_directory *ud;
+	struct eth1394_host_info *hi;
+	struct eth1394_priv *priv;
+	struct eth1394_node_ref *old_node;
+	struct eth1394_node_info *node_info;
+	struct list_head *lh, *n;
+	unsigned long flags;
+
+	ud = container_of(dev, struct unit_directory, device);
+	hi = hpsb_get_hostinfo(&eth1394_highlevel, ud->ne->host);
+	if (!hi)
+		return -ENOENT;
+
+	priv = (struct eth1394_priv *)hi->dev->priv;
+
+	old_node = eth1394_find_node(&priv->ip_node_list, ud);
+
+	if (old_node) {
+		list_del(&old_node->list);
+		kfree(old_node);
+
+		node_info = (struct eth1394_node_info*)ud->device.driver_data;
+
+		spin_lock_irqsave(&node_info->pdg.lock, flags);
+		/* The partial datagram list should be empty, but we'll just
+		 * make sure anyway... */
+		list_for_each_safe(lh, n, &node_info->pdg.list) {
+			purge_partial_datagram(lh);
+		}
+		spin_unlock_irqrestore(&node_info->pdg.lock, flags);
+
+		kfree(node_info);
+		ud->device.driver_data = NULL;
+	}
+	return 0;
+}
+
+static void eth1394_update(struct unit_directory *ud)
+{
+	struct eth1394_host_info *hi;
+	struct eth1394_priv *priv;
+	struct eth1394_node_ref *node;
+	struct eth1394_node_info *node_info;
+
+	hi = hpsb_get_hostinfo(&eth1394_highlevel, ud->ne->host);
+	if (!hi)
+		return;
+
+	priv = (struct eth1394_priv *)hi->dev->priv;
+
+	node = eth1394_find_node(&priv->ip_node_list, ud);
+
+	if (!node) {
+		node = kmalloc(sizeof(struct eth1394_node_ref),
+			       in_interrupt() ? GFP_ATOMIC : GFP_KERNEL);
+		if (!node)
+			return;
+
+
+		node_info = kmalloc(sizeof(struct eth1394_node_info),
+				    in_interrupt() ? GFP_ATOMIC : GFP_KERNEL);
+
+		spin_lock_init(&node_info->pdg.lock);
+		INIT_LIST_HEAD(&node_info->pdg.list);
+		node_info->pdg.sz = 0;
+
+		ud->device.driver_data = node_info;
+		node->ud = ud;
+
+		priv = (struct eth1394_priv *)hi->dev->priv;
+		list_add_tail(&node->list, &priv->ip_node_list);
+	}
+}
+
+
+static struct ieee1394_device_id eth1394_id_table[] = {
+	{
+		.match_flags = (IEEE1394_MATCH_SPECIFIER_ID |
+				IEEE1394_MATCH_VERSION),
+		.specifier_id =	ETHER1394_GASP_SPECIFIER_ID,
+		.version = ETHER1394_GASP_VERSION,
+	},
+	{}
+};
+
+static struct hpsb_protocol_driver eth1394_proto_driver = {
+	.name		= "IPv4 over 1394 Driver",
+	.id_table	= eth1394_id_table,
+	.update		= eth1394_update,
+	.driver		= {
+		.name		= ETH1394_DRIVER_NAME,
+		.bus		= &ieee1394_bus_type,
+		.probe		= eth1394_probe,
+		.remove		= eth1394_remove,
+	},
+};
+
+
 static void ether1394_reset_priv (struct net_device *dev, int set_mtu)
 {
 	unsigned long flags;
 	int i;
 	struct eth1394_priv *priv = (struct eth1394_priv *)dev->priv;
 	struct hpsb_host *host = priv->host;
-	int phy_id = NODEID_TO_NODE(host->node_id);
-	u64 guid = *((u64*)&(host->csr.rom[3]));
-	u16 maxpayload = 1 << (((be32_to_cpu(host->csr.rom[2]) >> 12) & 0xf) + 1);
+	u64 guid = *((u64*)&(host->csr.rom->bus_info_data[3]));
+	u16 maxpayload = 1 << (host->csr.max_rec + 1);
+	int max_speed = IEEE1394_SPEED_MAX;
 
 	spin_lock_irqsave (&priv->lock, flags);
 
-	/* Clear the speed/payload/offset tables */
-	memset (priv->maxpayload, 0, sizeof (priv->maxpayload));
-	memset (priv->sspd, 0, sizeof (priv->sspd));
-	memset (priv->fifo, 0, sizeof (priv->fifo));
-
-	priv->sspd[ALL_NODES] = ETH1394_SPEED_DEF;
-	priv->maxpayload[ALL_NODES] = eth1394_speedto_maxpayload[priv->sspd[ALL_NODES]];
-
-	priv->bc_state = ETHER1394_BC_CHECK;
-
-	/* Register our limits now */
-	ether1394_register_limits(phy_id, maxpayload,
-				  host->speed_map[(phy_id << 6) + phy_id],
-				  guid, ETHER1394_REGION_ADDR, priv);
+	memset(priv->ud_list, 0, sizeof(struct node_entry*) * ALL_NODES);
+	priv->bc_maxpayload = 512;
+
+	/* Determine speed limit */
+	for (i = 0; i < host->node_count; i++)
+		if (max_speed > host->speed_map[NODEID_TO_NODE(host->node_id) *
+						64 + i])
+			max_speed = host->speed_map[NODEID_TO_NODE(host->node_id) *
+						    64 + i];
+	priv->bc_sspd = max_speed;
 
 	/* We'll use our maxpayload as the default mtu */
 	if (set_mtu) {
-		dev->mtu = min(ETH1394_DATA_LEN, (int)(priv->maxpayload[phy_id] -
-			       (sizeof(union eth1394_hdr) + ETHER1394_GASP_OVERHEAD)));
+		dev->mtu = min(ETH1394_DATA_LEN,
+			       (int)(maxpayload -
+				     (sizeof(union eth1394_hdr) +
+				      ETHER1394_GASP_OVERHEAD)));
 
 		/* Set our hardware address while we're at it */
 		*(u64*)dev->dev_addr = guid;
@@ -379,20 +508,6 @@
 	}
 
 	spin_unlock_irqrestore (&priv->lock, flags);
-
-	for (i = 0; i < ALL_NODES; i++) {
-		struct list_head *lh, *n;
-
-		spin_lock_irqsave(&priv->pdg[i].lock, flags);
-		if (!set_mtu) {
-			list_for_each_safe(lh, n, &priv->pdg[i].list) {
-				purge_partial_datagram(lh);
-			}
-		}
-		INIT_LIST_HEAD(&(priv->pdg[i].list));
-		priv->pdg[i].sz = 0;
-		spin_unlock_irqrestore(&priv->pdg[i].lock, flags);
-	}
 }
 
 /* This function is called right before register_netdev */
@@ -432,15 +547,21 @@
  */
 static void ether1394_add_host (struct hpsb_host *host)
 {
-	int i;
-	struct host_info *hi = NULL;
+	struct eth1394_host_info *hi = NULL;
 	struct net_device *dev = NULL;
 	struct eth1394_priv *priv;
 	static int version_printed = 0;
 
-	hpsb_register_addrspace(&eth1394_highlevel, host, &addr_ops,
-				ETHER1394_REGION_ADDR,
-				ETHER1394_REGION_ADDR_END);
+	u64 fifo_addr;
+
+	fifo_addr = hpsb_allocate_and_register_addrspace(&eth1394_highlevel,
+							 host,
+							 &addr_ops,
+							 ETHER1394_REGION_ADDR_LEN,
+							 ETHER1394_REGION_ADDR_LEN,
+							 -1, -1);
+	if (fifo_addr == ~0ULL)
+		goto out;
 
 	if (version_printed++ == 0)
 		ETH1394_PRINT_G (KERN_INFO, "%s\n", version);
@@ -461,14 +582,11 @@
 
 	priv = (struct eth1394_priv *)dev->priv;
 
+	INIT_LIST_HEAD(&priv->ip_node_list);
+
 	spin_lock_init(&priv->lock);
 	priv->host = host;
-
-	for (i = 0; i < ALL_NODES; i++) {
-                spin_lock_init(&priv->pdg[i].lock);
-		INIT_LIST_HEAD(&priv->pdg[i].list);
-		priv->pdg[i].sz = 0;
-	}
+	priv->local_fifo = fifo_addr;
 
 	hi = hpsb_create_hostinfo(&eth1394_highlevel, host, sizeof(*hi));
 
@@ -496,10 +614,30 @@
 	 * be checked when the eth device is opened. */
 	priv->broadcast_channel = host->csr.broadcast_channel & 0x3f;
 
-	priv->iso = hpsb_iso_recv_init(host, 16 * 4096, 16, priv->broadcast_channel,
-					HPSB_ISO_DMA_PACKET_PER_BUFFER, 1, ether1394_iso);
+	priv->iso = hpsb_iso_recv_init(host, (ETHER1394_GASP_BUFFERS * 2 *
+					      (1 << (host->csr.max_rec + 1))),
+				       ETHER1394_GASP_BUFFERS,
+				       priv->broadcast_channel,
+				       HPSB_ISO_DMA_PACKET_PER_BUFFER,
+				       1, ether1394_iso);
 	if (priv->iso == NULL) {
-		priv->bc_state = ETHER1394_BC_CLOSED;
+		ETH1394_PRINT(KERN_ERR, dev->name,
+			      "Could not allocate isochronous receive context "
+			      "for the broadcast channel\n");
+		priv->bc_state = ETHER1394_BC_ERROR;
+	} else {
+		if (hpsb_iso_recv_start(priv->iso, -1, (1 << 3), -1) < 0)
+			priv->bc_state = ETHER1394_BC_STOPPED;
+		else
+			priv->bc_state = ETHER1394_BC_RUNNING;
+	}
+
+	if (csr1212_attach_keyval_to_directory(host->csr.rom->root_kv,
+					       eth1394_ud) != CSR1212_SUCCESS) {
+		ETH1394_PRINT (KERN_ERR, dev->name,
+			       "Cannot attach IP 1394 Unit Directory to "
+			       "Config ROM\n");
+		goto out;
 	}
 	return;
 
@@ -515,12 +653,21 @@
 /* Remove a card from our list */
 static void ether1394_remove_host (struct hpsb_host *host)
 {
-	struct host_info *hi = hpsb_get_hostinfo(&eth1394_highlevel, host);
-
+	struct eth1394_host_info *hi;
+	
+	hi = hpsb_get_hostinfo(&eth1394_highlevel, host);
 	if (hi != NULL) {
 		struct eth1394_priv *priv = (struct eth1394_priv *)hi->dev->priv;
 
-		eth1394_iso_shutdown(priv);
+		hpsb_unregister_addrspace(&eth1394_highlevel, host,
+					  priv->local_fifo);
+
+		if (priv->iso != NULL) 
+			hpsb_iso_shutdown(priv->iso);
+
+		csr1212_detach_keyval_from_directory(hi->host->csr.rom->root_kv,
+						     eth1394_ud);
+		hi->host->update_config_rom = 1;
 
 		if (hi->dev) {
 			unregister_netdev (hi->dev);
@@ -534,18 +681,42 @@
 /* A reset has just arisen */
 static void ether1394_host_reset (struct hpsb_host *host)
 {
-	struct host_info *hi = hpsb_get_hostinfo(&eth1394_highlevel, host);
+	struct eth1394_host_info *hi;
+	struct eth1394_priv *priv;
 	struct net_device *dev;
+	struct list_head *lh, *n;
+	struct eth1394_node_ref *node;
+	struct eth1394_node_info *node_info;
+	unsigned long flags;
+
+	hi = hpsb_get_hostinfo(&eth1394_highlevel, host);
 
 	/* This can happen for hosts that we don't use */
 	if (hi == NULL)
 		return;
 
 	dev = hi->dev;
+	priv = (struct eth1394_priv *)dev->priv;
 
 	/* Reset our private host data, but not our mtu */
 	netif_stop_queue (dev);
 	ether1394_reset_priv (dev, 0);
+
+	list_for_each_entry(node, &priv->ip_node_list, list) {
+		node_info = (struct eth1394_node_info*)node->ud->device.driver_data;
+
+		spin_lock_irqsave(&node_info->pdg.lock, flags);
+
+		list_for_each_safe(lh, n, &node_info->pdg.list) {
+			purge_partial_datagram(lh);
+		}
+
+		INIT_LIST_HEAD(&(node_info->pdg.list));
+		node_info->pdg.sz = 0;
+
+		spin_unlock_irqrestore(&node_info->pdg.lock, flags);
+	}
+
 	netif_wake_queue (dev);
 }
 
@@ -622,7 +793,8 @@
 static int ether1394_header_cache(struct neighbour *neigh, struct hh_cache *hh)
 {
 	unsigned short type = hh->hh_type;
-	struct eth1394hdr *eth = (struct eth1394hdr*)(((u8*)hh->hh_data) + 6);
+	struct eth1394hdr *eth = (struct eth1394hdr*)(((u8*)hh->hh_data) +
+						      (16 - ETH1394_HLEN));
 	struct net_device *dev = neigh->dev;
 
 	if (type == __constant_htons(ETH_P_802_3)) {
@@ -641,7 +813,7 @@
 					  struct net_device *dev,
 					  unsigned char * haddr)
 {
-	memcpy(((u8*)hh->hh_data) + 6, haddr, dev->addr_len);
+	memcpy(((u8*)hh->hh_data) + (16 - ETH1394_HLEN), haddr, dev->addr_len);
 }
 
 static int ether1394_mac_addr(struct net_device *dev, void *p)
@@ -650,7 +822,7 @@
 		return -EBUSY;
 
 	/* Not going to allow setting the MAC address, we really need to use
-	 * the real one suppliled by the hardware */
+	 * the real one supplied by the hardware */
 	 return -EINVAL;
  }
 
@@ -710,31 +882,37 @@
 	if (destid == (LOCAL_BUS | ALL_NODES))
 		dest_hw = ~0ULL;  /* broadcast */
 	else
-		dest_hw = priv->eui[NODEID_TO_NODE(destid)];
+		dest_hw = cpu_to_be64((((u64)priv->host->csr.guid_hi) << 32) |
+				      priv->host->csr.guid_lo);
 
 	/* If this is an ARP packet, convert it. First, we want to make
 	 * use of some of the fields, since they tell us a little bit
 	 * about the sending machine.  */
 	if (ether_type == __constant_htons (ETH_P_ARP)) {
-		unsigned long flags;
 		struct eth1394_arp *arp1394 = (struct eth1394_arp*)skb->data;
 		struct arphdr *arp = (struct arphdr *)skb->data;
 		unsigned char *arp_ptr = (unsigned char *)(arp + 1);
 		u64 fifo_addr = (u64)ntohs(arp1394->fifo_hi) << 32 |
 			ntohl(arp1394->fifo_lo);
-		u8 host_max_rec = (be32_to_cpu(priv->host->csr.rom[2]) >>
-				   12) & 0xf;
-		u8 max_rec = min(host_max_rec, (u8)(arp1394->max_rec));
+		u8 max_rec = min(priv->host->csr.max_rec,
+				 (u8)(arp1394->max_rec));
 		u16 maxpayload = min(eth1394_speedto_maxpayload[arp1394->sspd],
 				     (u16)(1 << (max_rec + 1)));
+		struct eth1394_node_ref *node;
+		struct eth1394_node_info *node_info;
+
+		node = eth1394_find_node_guid(&priv->ip_node_list,
+					      be64_to_cpu(arp1394->s_uniq_id));
+		if (!node) {
+			return 0;
+		}
 
+		node_info = (struct eth1394_node_info*)node->ud->device.driver_data;
 
 		/* Update our speed/payload/fifo_offset table */
-		spin_lock_irqsave (&priv->lock, flags);
-		ether1394_register_limits(NODEID_TO_NODE(srcid), maxpayload,
-					  arp1394->sspd, arp1394->s_uniq_id,
-					  fifo_addr, priv);
-		spin_unlock_irqrestore (&priv->lock, flags);
+		node_info->maxpayload =	maxpayload;
+		node_info->sspd =	arp1394->sspd;
+		node_info->fifo =	fifo_addr;
 
 		/* Now that we're done with the 1394 specific stuff, we'll
 		 * need to alter some of the data.  Believe it or not, all
@@ -743,9 +921,8 @@
 		 * in and the hardware address length set to 8.
 		 *
 		 * IMPORTANT: The code below overwrites 1394 specific data
-		 * needed above data so keep the call to
-		 * ether1394_register_limits() before munging the data for the
-		 * higher level IP stack. */
+		 * needed above so keep the munging of the data for the
+		 * higher level IP stack last. */
 
 		arp->ar_hln = 8;
 		arp_ptr += arp->ar_hln;		/* skip over sender unique id */
@@ -754,9 +931,9 @@
 
 		if (arp->ar_op == 1)
 			/* just set ARP req target unique ID to 0 */
-			memset(arp_ptr, 0, ETH1394_ALEN);
+			*((u64*)arp_ptr) = 0;
 		else
-			memcpy(arp_ptr, dev->dev_addr, ETH1394_ALEN);
+			*((u64*)arp_ptr) = *((u64*)dev->dev_addr);
 	}
 
 	/* Now add the ethernet header. */
@@ -939,12 +1116,29 @@
 {
 	struct sk_buff *skb;
 	unsigned long flags;
-	struct eth1394_priv *priv;
+	struct eth1394_priv *priv = (struct eth1394_priv *)dev->priv;
 	union eth1394_hdr *hdr = (union eth1394_hdr *)buf;
 	u16 ether_type = 0;  /* initialized to clear warning */
 	int hdr_len;
+	struct unit_directory *ud = priv->ud_list[NODEID_TO_NODE(srcid)];
+	struct eth1394_node_info *node_info;
 
-	priv = (struct eth1394_priv *)dev->priv;
+	if (!ud) {
+		struct eth1394_node_ref *node;
+		node = eth1394_find_node_nodeid(&priv->ip_node_list, srcid);
+		if (!node) {
+			HPSB_PRINT(KERN_ERR, "ether1394 rx: sender nodeid "
+				   "lookup failure: " NODE_BUS_FMT,
+				   NODE_BUS_ARGS(priv->host, srcid));
+			priv->stats.rx_dropped++;
+			return -1;
+		}
+		ud = node->ud;
+
+		priv->ud_list[NODEID_TO_NODE(srcid)] = ud;
+	}
+
+	node_info = (struct eth1394_node_info*)ud->device.driver_data;
 
 	/* First, did we receive a fragmented or unfragmented datagram? */
 	hdr->words.word1 = ntohs(hdr->words.word1);
@@ -975,8 +1169,7 @@
 		int dg_size;
 		int dgl;
 		int retval;
-		int sid = NODEID_TO_NODE(srcid);
-                struct pdg_list *pdg = &(priv->pdg[sid]);
+		struct pdg_list *pdg = &(node_info->pdg);
 
 		hdr->words.word3 = ntohs(hdr->words.word3);
 		/* The 4th header word is reserved so no need to do ntohs() */
@@ -1110,8 +1303,9 @@
 static int ether1394_write(struct hpsb_host *host, int srcid, int destid,
 			   quadlet_t *data, u64 addr, size_t len, u16 flags)
 {
-	struct host_info *hi = hpsb_get_hostinfo(&eth1394_highlevel, host);
+	struct eth1394_host_info *hi;
 
+	hi = hpsb_get_hostinfo(&eth1394_highlevel, host);
 	if (hi == NULL) {
 		ETH1394_PRINT_G(KERN_ERR, "Could not find net device for host %s\n",
 				host->driver->name);
@@ -1128,7 +1322,7 @@
 {
 	quadlet_t *data;
 	char *buf;
-	struct host_info *hi = hpsb_get_hostinfo(&eth1394_highlevel, iso->host);
+	struct eth1394_host_info *hi;
 	struct net_device *dev;
 	struct eth1394_priv *priv;
 	unsigned int len;
@@ -1137,6 +1331,7 @@
 	int i;
 	int nready;
 
+	hi = hpsb_get_hostinfo(&eth1394_highlevel, iso->host);
 	if (hi == NULL) {
 		ETH1394_PRINT_G(KERN_ERR, "Could not find net device for host %s\n",
 				iso->host->driver->name);
@@ -1193,7 +1388,6 @@
 					    struct net_device *dev)
 {
 	struct eth1394_priv *priv = (struct eth1394_priv *)(dev->priv);
-	u16 phy_id = NODEID_TO_NODE(priv->host->node_id);
 
 	struct arphdr *arp = (struct arphdr *)skb->data;
 	unsigned char *arp_ptr = (unsigned char *)(arp + 1);
@@ -1203,10 +1397,10 @@
 	 * and set hw_addr_len, max_rec, sspd, fifo_hi and fifo_lo.  */
 	arp1394->hw_addr_len	= 16;
 	arp1394->sip		= *(u32*)(arp_ptr + ETH1394_ALEN);
-	arp1394->max_rec	= (be32_to_cpu(priv->host->csr.rom[2]) >> 12) & 0xf;
-	arp1394->sspd		= priv->sspd[phy_id];
-	arp1394->fifo_hi	= htons (priv->fifo[phy_id] >> 32);
-	arp1394->fifo_lo	= htonl (priv->fifo[phy_id] & ~0x0);
+	arp1394->max_rec	= priv->host->csr.max_rec;
+	arp1394->sspd		= priv->host->csr.lnk_spd;
+	arp1394->fifo_hi	= htons (priv->local_fifo >> 32);
+	arp1394->fifo_lo	= htonl (priv->local_fifo & ~0x0);
 
 	return;
 }
@@ -1333,15 +1527,15 @@
 	p->data_size = length;
 	p->data = ((quadlet_t*)skb->data) - 2;
 	p->data[0] = cpu_to_be32((priv->host->node_id << 16) |
-				      ETHER1394_GASP_SPECIFIER_ID_HI);
-	p->data[1] = cpu_to_be32((ETHER1394_GASP_SPECIFIER_ID_LO << 24) |
-				      ETHER1394_GASP_VERSION);
+				 ETHER1394_GASP_SPECIFIER_ID_HI);
+	p->data[1] = __constant_cpu_to_be32((ETHER1394_GASP_SPECIFIER_ID_LO << 24) |
+					    ETHER1394_GASP_VERSION);
 
 	/* Setting the node id to ALL_NODES (not LOCAL_BUS | ALL_NODES)
 	 * prevents hpsb_send_packet() from setting the speed to an arbitrary
 	 * value based on packet->node_id if packet->node_id is not set. */
 	p->node_id = ALL_NODES;
-	p->speed_code = priv->sspd[ALL_NODES];
+	p->speed_code = priv->bc_sspd;
 }
 
 static inline void ether1394_free_packet(struct hpsb_packet *packet)
@@ -1458,7 +1652,8 @@
 	u16 dg_size;
 	u16 dgl;
 	struct packet_task *ptask;
-	struct node_entry *ne;
+	struct eth1394_node_ref *node;
+	struct eth1394_node_info *node_info = NULL;
 
 	ptask = kmem_cache_alloc(packet_task_cache, kmflags);
 	if (ptask == NULL) {
@@ -1466,22 +1661,11 @@
 		goto fail;
 	}
 
-	spin_lock_irqsave (&priv->lock, flags);
-	if (priv->bc_state == ETHER1394_BC_CLOSED) {
-		ETH1394_PRINT(KERN_ERR, dev->name,
-			      "Cannot send packet, no broadcast channel available.\n");
+	if ((priv->host->csr.broadcast_channel & 0xc0000000) != 0xc0000000) {
 		ret = -EAGAIN;
-		spin_unlock_irqrestore (&priv->lock, flags);
 		goto fail;
 	}
 
-	if ((ret = ether1394_init_bc(dev))) {
-		spin_unlock_irqrestore (&priv->lock, flags);
-		goto fail;
-	}
-
-	spin_unlock_irqrestore (&priv->lock, flags);
-
 	if ((skb = skb_share_check (skb, kmflags)) == NULL) {
 		ret = -ENOMEM;
 		goto fail;
@@ -1491,28 +1675,8 @@
 	eth = (struct eth1394hdr*)skb->data;
 	skb_pull(skb, ETH1394_HLEN);
 
-	ne = hpsb_guid_get_entry(be64_to_cpu(*(u64*)eth->h_dest));
-	if (!ne)
-		dest_node = LOCAL_BUS | ALL_NODES;
-	else
-		dest_node = ne->nodeid;
-
 	proto = eth->h_proto;
-
-	/* If this is an ARP packet, convert it */
-	if (proto == __constant_htons (ETH_P_ARP))
-		ether1394_arp_to_1394arp (skb, dev);
-
-	max_payload = priv->maxpayload[NODEID_TO_NODE(dest_node)];
-
-	/* This check should be unnecessary, but we'll keep it for safety for
-	 * a while longer. */
-	if (max_payload < 512) {
-		ETH1394_PRINT(KERN_WARNING, dev->name,
-			      "max_payload too small: %d   (setting to 512)\n",
-			      max_payload);
-		max_payload = 512;
-	}
+	dg_size = skb->len;
 
 	/* Set the transmission type for the packet.  ARP packets and IP
 	 * broadcast packets are sent via GASP. */
@@ -1521,18 +1685,38 @@
 	    (proto == __constant_htons(ETH_P_IP) &&
 	     IN_MULTICAST(__constant_ntohl(skb->nh.iph->daddr)))) {
 		tx_type = ETH1394_GASP;
-                max_payload -= ETHER1394_GASP_OVERHEAD;
+		dest_node = LOCAL_BUS | ALL_NODES;
+		max_payload = priv->bc_maxpayload - ETHER1394_GASP_OVERHEAD;
+		BUG_ON(max_payload < (512 - ETHER1394_GASP_OVERHEAD));
+		dgl = priv->bc_dgl;
+		if (max_payload < dg_size + hdr_type_len[ETH1394_HDR_LF_UF])
+			priv->bc_dgl++;
 	} else {
+		node = eth1394_find_node_guid(&priv->ip_node_list,
+					      be64_to_cpu(*(u64*)eth->h_dest));
+		if (!node) {
+			ret = -EAGAIN;
+			goto fail;
+		}
+		node_info = (struct eth1394_node_info*)node->ud->device.driver_data;
+		if (node_info->fifo == ETHER1394_INVALID_ADDR) {
+			ret = -EAGAIN;
+			goto fail;
+		}
+
+		dest_node = node->ud->ne->nodeid;
+		max_payload = node_info->maxpayload;
+		BUG_ON(max_payload < (512 - ETHER1394_GASP_OVERHEAD));
+
+		dgl = node_info->dgl;
+		if (max_payload < dg_size + hdr_type_len[ETH1394_HDR_LF_UF])
+			node_info->dgl++;
 		tx_type = ETH1394_WRREQ;
 	}
 
-	dg_size = skb->len;
-
-	spin_lock_irqsave (&priv->lock, flags);
-	dgl = priv->dgl[NODEID_TO_NODE(dest_node)];
-	if (max_payload < dg_size + hdr_type_len[ETH1394_HDR_LF_UF])
-		priv->dgl[NODEID_TO_NODE(dest_node)]++;
-	spin_unlock_irqrestore (&priv->lock, flags);
+	/* If this is an ARP packet, convert it */
+	if (proto == __constant_htons (ETH_P_ARP))
+		ether1394_arp_to_1394arp (skb, dev);
 
 	ptask->hdr.words.word1 = 0;
 	ptask->hdr.words.word2 = 0;
@@ -1545,17 +1729,8 @@
 	if (tx_type != ETH1394_GASP) {
 		u64 addr;
 
-		/* This test is just temporary until ConfigROM support has
-		 * been added to eth1394.  Until then, we need an ARP packet
-		 * after a bus reset from the current destination node so that
-		 * we can get FIFO information. */
-		if (priv->fifo[NODEID_TO_NODE(dest_node)] == 0ULL) {
-			ret = -EAGAIN;
-			goto fail;
-		}
-
 		spin_lock_irqsave(&priv->lock, flags);
-		addr = priv->fifo[NODEID_TO_NODE(dest_node)];
+		addr = node_info->fifo;
 		spin_unlock_irqrestore(&priv->lock, flags);
 
 		ptask->addr = addr;
@@ -1621,7 +1796,7 @@
 		case ETHTOOL_GDRVINFO: {
 			struct ethtool_drvinfo info = { ETHTOOL_GDRVINFO };
 			strcpy (info.driver, driver_name);
-			strcpy (info.version, "$Rev: 1096 $");
+			strcpy (info.version, "$Rev: 1118 $");
 			/* FIXME XXX provide sane businfo */
 			strcpy (info.bus_info, "ieee1394");
 			if (copy_to_user (useraddr, &info, sizeof (info)))
@@ -1644,19 +1819,78 @@
 
 static int __init ether1394_init_module (void)
 {
+	int ret;
+	struct csr1212_keyval *spec_id = NULL;
+	struct csr1212_keyval *spec_desc = NULL;
+	struct csr1212_keyval *ver = NULL;
+	struct csr1212_keyval *ver_desc = NULL;
+
 	packet_task_cache = kmem_cache_create("packet_task", sizeof(struct packet_task),
 					      0, 0, NULL, NULL);
 
+	eth1394_ud = csr1212_new_directory(CSR1212_KV_ID_UNIT);
+	spec_id = csr1212_new_immediate(CSR1212_KV_ID_SPECIFIER_ID,
+					ETHER1394_GASP_SPECIFIER_ID);
+	spec_desc = csr1212_new_string_descriptor_leaf("IANA");
+	ver = csr1212_new_immediate(CSR1212_KV_ID_VERSION,
+				    ETHER1394_GASP_VERSION);
+	ver_desc = csr1212_new_string_descriptor_leaf("IPv4");
+
+	if ((!eth1394_ud) ||
+	    (!spec_id) ||
+	    (!spec_desc) ||
+	    (!ver) ||
+	    (!ver_desc)) {
+		ret = -ENOMEM;
+		goto out;
+	}
+
+	ret = csr1212_associate_keyval(spec_id, spec_desc);
+	if (ret != CSR1212_SUCCESS)
+		goto out;
+
+	ret = csr1212_associate_keyval(ver, ver_desc);
+	if (ret != CSR1212_SUCCESS)
+		goto out;
+
+	ret = csr1212_attach_keyval_to_directory(eth1394_ud, spec_id);
+	if (ret != CSR1212_SUCCESS)
+		goto out;
+
+	ret = csr1212_attach_keyval_to_directory(eth1394_ud, ver);
+	if (ret != CSR1212_SUCCESS)
+		goto out;
+
 	/* Register ourselves as a highlevel driver */
 	hpsb_register_highlevel(&eth1394_highlevel);
 
-	return 0;
+	ret = hpsb_register_protocol(&eth1394_proto_driver);
+
+out:
+	if ((ret != 0) && eth1394_ud) {
+		csr1212_release_keyval(eth1394_ud);
+	}
+	if (spec_id)
+		csr1212_release_keyval(spec_id);
+	if (spec_desc)
+		csr1212_release_keyval(spec_desc);
+	if (ver)
+		csr1212_release_keyval(ver);
+	if (ver_desc)
+		csr1212_release_keyval(ver_desc);
+
+	return ret;
 }
 
 static void __exit ether1394_exit_module (void)
 {
+	hpsb_unregister_protocol(&eth1394_proto_driver);
 	hpsb_unregister_highlevel(&eth1394_highlevel);
 	kmem_cache_destroy(packet_task_cache);
+
+	if (eth1394_ud) {
+		csr1212_release_keyval(eth1394_ud);
+	}
 }
 
 module_init(ether1394_init_module);
diff -Nru a/drivers/ieee1394/eth1394.h b/drivers/ieee1394/eth1394.h
--- a/drivers/ieee1394/eth1394.h	Wed Feb 11 22:28:46 2004
+++ b/drivers/ieee1394/eth1394.h	Wed Feb 11 22:28:46 2004
@@ -29,8 +29,8 @@
 /* Register for incoming packets. This is 4096 bytes, which supports up to
  * S3200 (per Table 16-3 of IEEE 1394b-2002). */
 #define ETHER1394_REGION_ADDR_LEN	4096
-#define ETHER1394_REGION_ADDR		0xfffff0200000ULL
-#define ETHER1394_REGION_ADDR_END	(ETHER1394_REGION_ADDR + ETHER1394_REGION_ADDR_LEN)
+
+#define ETHER1394_INVALID_ADDR		~0ULL
 
 /* GASP identifier numbers for IPv4 over IEEE 1394 */
 #define ETHER1394_GASP_SPECIFIER_ID	0x00005E
@@ -40,37 +40,30 @@
 
 #define ETHER1394_GASP_OVERHEAD (2 * sizeof(quadlet_t))  /* GASP header overhead */
 
+#define ETHER1394_GASP_BUFFERS 16
+
 /* Node set == 64 */
 #define NODE_SET			(ALL_NODES + 1)
 
-enum eth1394_bc_states { ETHER1394_BC_CLOSED, ETHER1394_BC_OPENED,
-			 ETHER1394_BC_CHECK };
+enum eth1394_bc_states { ETHER1394_BC_ERROR,
+			 ETHER1394_BC_RUNNING,
+			 ETHER1394_BC_STOPPED };
 
-struct pdg_list {
-	struct list_head list;		/* partial datagram list per node */
-	unsigned int sz;		/* partial datagram list size per node	*/
-	spinlock_t lock;		/* partial datagram lock		*/
-};
 
 /* Private structure for our ethernet driver */
 struct eth1394_priv {
 	struct net_device_stats stats;	/* Device stats			 */
 	struct hpsb_host *host;		/* The card for this dev	 */
-	u16 maxpayload[NODE_SET];	/* Max payload per node		 */
-	unsigned char sspd[NODE_SET];	/* Max speed per node		 */
-	u64 fifo[ALL_NODES];		/* FIFO offset per node		 */
-	u64 eui[ALL_NODES];		/* EUI-64 per node		 */
+	u16 bc_maxpayload;		/* Max broadcast payload	 */
+	u8 bc_sspd;			/* Max broadcast speed		 */
+	u64 local_fifo;			/* Local FIFO Address		 */
 	spinlock_t lock;		/* Private lock			 */
 	int broadcast_channel;		/* Async stream Broadcast Channel */
 	enum eth1394_bc_states bc_state; /* broadcast channel state	 */
 	struct hpsb_iso *iso;		/* Async stream recv handle	 */
-	struct pdg_list pdg[ALL_NODES]; /* partial RX datagram lists     */
-	int dgl[NODE_SET];              /* Outgoing datagram label per node */
-};
-
-struct host_info {
-	struct hpsb_host *host;
-	struct net_device *dev;
+	int bc_dgl;			/* Outgoing broadcast datagram label */
+	struct list_head ip_node_list;	/* List of IP capable nodes	 */
+	struct unit_directory *ud_list[ALL_NODES]; /* Cached unit dir list */
 };
 
 
diff -Nru a/drivers/ieee1394/highlevel.c b/drivers/ieee1394/highlevel.c
--- a/drivers/ieee1394/highlevel.c	Wed Feb 11 22:28:46 2004
+++ b/drivers/ieee1394/highlevel.c	Wed Feb 11 22:28:46 2004
@@ -20,6 +20,7 @@
 #include <linux/config.h>
 #include <linux/slab.h>
 #include <linux/list.h>
+#include <linux/bitops.h>
 
 #include "ieee1394.h"
 #include "ieee1394_types.h"
@@ -44,7 +45,6 @@
 static LIST_HEAD(hl_irqs);
 static rwlock_t hl_irqs_lock = RW_LOCK_UNLOCKED;
 
-static LIST_HEAD(addr_space);
 static rwlock_t addr_space_lock = RW_LOCK_UNLOCKED;
 
 /* addr_space list will have zero and max already included as bounds */
@@ -237,6 +237,13 @@
 
 	hl->add_host(host);
 
+        if (host->update_config_rom) {
+		if (hpsb_update_config_rom_image(host) < 0) {
+			HPSB_ERR("Failed to generate Configuration ROM image for host "
+				 "%s-%d", hl->name, host->id);
+		}
+	}
+
 	return 0;
 }
 
@@ -261,12 +268,20 @@
         return;
 }
 
-static void __unregister_host(struct hpsb_highlevel *hl, struct hpsb_host *host)
+static void __delete_addr(struct hpsb_address_serve *as)
+{
+	list_del(&as->host_list);
+	list_del(&as->hl_list);
+	kfree(as);
+}
+
+static void __unregister_host(struct hpsb_highlevel *hl, struct hpsb_host *host, int update_cr)
 {
 	unsigned long flags;
 	struct list_head *lh, *next;
 	struct hpsb_address_serve *as;
 
+	/* First, let the highlevel driver unreg */
 	if (hl->remove_host)
 		hl->remove_host(host);
 
@@ -274,19 +289,24 @@
 	 * and this particular host. */
 	write_lock_irqsave(&addr_space_lock, flags);
 	list_for_each_safe (lh, next, &hl->addr_list) {
-		as = list_entry(lh, struct hpsb_address_serve, addr_list);
+		as = list_entry(lh, struct hpsb_address_serve, hl_list);
 
-		if (as->host != host)
-			continue;
+		if (as->host == host)
+			__delete_addr(as);
+	}
+	write_unlock_irqrestore(&addr_space_lock, flags);
 
-		if (!list_empty(&as->addr_list)) {
-			list_del(&as->as_list);
-			list_del(&as->addr_list);
-			kfree(as);
+	/* Now update the config-rom to reflect anything removed by the
+	 * highlevel driver. */
+	if (update_cr && host->update_config_rom) {
+		if (hpsb_update_config_rom_image(host) < 0) {
+			HPSB_ERR("Failed to generate Configuration ROM image for host "
+				 "%s-%d", hl->name, host->id);
 		}
 	}
-	write_unlock_irqrestore(&addr_space_lock, flags);
 
+	/* And finally, remove all the host info associated between these
+	 * two. */
 	hpsb_destroy_hostinfo(hl, host);
 }
 
@@ -294,7 +314,7 @@
 {
 	struct hpsb_highlevel *hl = __data;
 
-	__unregister_host(hl, host);
+	__unregister_host(hl, host, 1);
 
 	return 0;
 }
@@ -312,11 +332,85 @@
 	nodemgr_for_each_host(hl, highlevel_for_each_host_unreg);
 }
 
+u64 hpsb_allocate_and_register_addrspace(struct hpsb_highlevel *hl,
+					 struct hpsb_host *host,
+					 struct hpsb_address_ops *ops,
+					 u64 size, u64 alignment,
+					 u64 start, u64 end)
+{
+	struct hpsb_address_serve *as, *a1, *a2;
+	struct list_head *entry;
+	u64 retval = ~0ULL;
+	unsigned long flags;
+	u64 align_mask = ~(alignment - 1);
+
+	if ((alignment & 3) || (alignment > 0x800000000000ULL) ||
+	    ((hweight32(alignment >> 32) +
+	      hweight32(alignment & 0xffffffff) != 1))) {
+		HPSB_ERR("%s called with invalid alignment: 0x%048llx",
+			 __FUNCTION__, (unsigned long long)alignment);
+		return retval;
+	}
+
+	if (start == ~0ULL && end == ~0ULL) {
+		start = CSR1212_ALL_SPACE_BASE + 0xffff00000000ULL;  /* ohci1394.c limit */
+		end = CSR1212_ALL_SPACE_END;
+	}
+
+	if (((start|end) & ~align_mask) || (start >= end) || (end > 0x1000000000000ULL)) {
+		HPSB_ERR("%s called with invalid addresses (start = %012Lx    end = %012Lx)",
+			 __FUNCTION__, (unsigned long long)start, (unsigned long long)end);
+		return retval;
+	}
+
+	as = (struct hpsb_address_serve *)
+		kmalloc(sizeof(struct hpsb_address_serve), GFP_KERNEL);
+	if (as == NULL) {
+		return retval;
+	}
+
+	INIT_LIST_HEAD(&as->host_list);
+	INIT_LIST_HEAD(&as->hl_list);
+	as->op = ops;
+
+	write_lock_irqsave(&addr_space_lock, flags);
+
+	list_for_each(entry, &host->addr_space) {
+		u64 a1sa, a1ea;
+		u64 a2sa, a2ea;
+
+		a1 = list_entry(entry, struct hpsb_address_serve, host_list);
+		a2 = list_entry(entry->next, struct hpsb_address_serve, host_list);
+
+		a1sa = a1->start & align_mask;
+		a1ea = (a1->end + alignment -1) & align_mask;
+		a2sa = a2->start & align_mask;
+		a2ea = (a2->end + alignment -1) & align_mask;
+
+		if ((a2sa - a1ea >= size) && (a2sa - start >= size) && (end - a1ea >= size)) {
+			as->start = max(start, a1ea);
+			as->end = as->start + size;
+			list_add(&as->host_list, entry);
+			list_add_tail(&as->hl_list, &hl->addr_list);
+			retval = as->start;
+			break;
+		}
+	}
+
+	write_unlock_irqrestore(&addr_space_lock, flags);
+
+	if (retval == ~0ULL) {
+		kfree(as);
+	}
+
+	return retval;
+}
+
 int hpsb_register_addrspace(struct hpsb_highlevel *hl, struct hpsb_host *host,
                             struct hpsb_address_ops *ops, u64 start, u64 end)
 {
         struct hpsb_address_serve *as;
-        struct list_head *entry;
+	struct list_head *lh;
         int retval = 0;
         unsigned long flags;
 
@@ -331,31 +425,35 @@
                 return 0;
         }
 
-        INIT_LIST_HEAD(&as->as_list);
-        INIT_LIST_HEAD(&as->addr_list);
+        INIT_LIST_HEAD(&as->host_list);
+        INIT_LIST_HEAD(&as->hl_list);
         as->op = ops;
         as->start = start;
         as->end = end;
+	as->host = host;
 
-        write_lock_irqsave(&addr_space_lock, flags);
-        entry = host->addr_space.next;
+	write_lock_irqsave(&addr_space_lock, flags);
 
-        while (list_entry(entry, struct hpsb_address_serve, as_list)->end
-               <= start) {
-                if (list_entry(entry->next, struct hpsb_address_serve, as_list)
-                    ->start >= end) {
-                        list_add(&as->as_list, entry);
-                        list_add_tail(&as->addr_list, &hl->addr_list);
-                        retval = 1;
-                        break;
-                }
-                entry = entry->next;
-        }
-        write_unlock_irqrestore(&addr_space_lock, flags);
+	list_for_each(lh, &host->addr_space) {
+		struct hpsb_address_serve *as_this =
+			list_entry(lh, struct hpsb_address_serve, host_list);
+		struct hpsb_address_serve *as_next =
+			list_entry(lh->next, struct hpsb_address_serve, host_list);
 
-        if (retval == 0) {
-                kfree(as);
-        }
+		if (as_this->end > as->start)
+			break;
+
+		if (as_next->start >= as->end) {
+			list_add(&as->host_list, lh);
+			list_add_tail(&as->hl_list, &hl->addr_list);
+			retval = 1;
+			break;
+		}
+	}
+	write_unlock_irqrestore(&addr_space_lock, flags);
+
+	if (retval == 0)
+		kfree(as);
 
         return retval;
 }
@@ -365,20 +463,15 @@
 {
         int retval = 0;
         struct hpsb_address_serve *as;
-        struct list_head *entry;
+        struct list_head *lh, *next;
         unsigned long flags;
 
         write_lock_irqsave(&addr_space_lock, flags);
 
-        entry = hl->addr_list.next;
-
-        while (entry != &hl->addr_list) {
-                as = list_entry(entry, struct hpsb_address_serve, addr_list);
-                entry = entry->next;
+	list_for_each_safe (lh, next, &hl->addr_list) {
+                as = list_entry(lh, struct hpsb_address_serve, hl_list);
                 if (as->start == start && as->host == host) {
-                        list_del(&as->as_list);
-                        list_del(&as->addr_list);
-                        kfree(as);
+			__delete_addr(as);
                         retval = 1;
                         break;
                 }
@@ -419,18 +512,18 @@
 
 static void init_hpsb_highlevel(struct hpsb_host *host)
 {
-	INIT_LIST_HEAD(&dummy_zero_addr.as_list);
-	INIT_LIST_HEAD(&dummy_zero_addr.addr_list);
-	INIT_LIST_HEAD(&dummy_max_addr.as_list);
-	INIT_LIST_HEAD(&dummy_max_addr.addr_list);
+	INIT_LIST_HEAD(&dummy_zero_addr.host_list);
+	INIT_LIST_HEAD(&dummy_zero_addr.hl_list);
+	INIT_LIST_HEAD(&dummy_max_addr.host_list);
+	INIT_LIST_HEAD(&dummy_max_addr.hl_list);
 
 	dummy_zero_addr.op = dummy_max_addr.op = &dummy_ops;
 
 	dummy_zero_addr.start = dummy_zero_addr.end = 0;
 	dummy_max_addr.start = dummy_max_addr.end = ((u64) 1) << 48;
 
-	list_add_tail(&dummy_zero_addr.as_list, &host->addr_space);
-	list_add_tail(&dummy_max_addr.as_list, &host->addr_space);
+	list_add_tail(&dummy_zero_addr.host_list, &host->addr_space);
+	list_add_tail(&dummy_max_addr.host_list, &host->addr_space);
 }
 
 void highlevel_add_host(struct hpsb_host *host)
@@ -445,6 +538,11 @@
 			hl->add_host(host);
         }
 	up_read(&hl_drivers_sem);
+	if (host->update_config_rom) {
+		if (hpsb_update_config_rom_image(host) < 0)
+			HPSB_ERR("Failed to generate Configuration ROM image for "
+				 "host %s-%d", hl->name, host->id);
+	}
 }
 
 void highlevel_remove_host(struct hpsb_host *host)
@@ -453,7 +551,7 @@
 
 	down_read(&hl_drivers_sem);
 	list_for_each_entry(hl, &hl_drivers, hl_list)
-		__unregister_host(hl, host);
+		__unregister_host(hl, host, 0);
 	up_read(&hl_drivers_sem);
 }
 
@@ -501,16 +599,15 @@
                    u64 addr, unsigned int length, u16 flags)
 {
         struct hpsb_address_serve *as;
-        struct list_head *entry;
         unsigned int partlength;
         int rcode = RCODE_ADDRESS_ERROR;
 
         read_lock(&addr_space_lock);
 
-        entry = host->addr_space.next;
-        as = list_entry(entry, struct hpsb_address_serve, as_list);
+	list_for_each_entry(as, &host->addr_space, host_list) {
+		if (as->start > addr)
+			break;
 
-        while (as->start <= addr) {
                 if (as->end > addr) {
                         partlength = min(as->end - addr, (u64) length);
 
@@ -529,9 +626,6 @@
                                 break;
                         }
                 }
-
-                entry = entry->next;
-                as = list_entry(entry, struct hpsb_address_serve, as_list);
         }
 
         read_unlock(&addr_space_lock);
@@ -547,16 +641,15 @@
 		    void *data, u64 addr, unsigned int length, u16 flags)
 {
         struct hpsb_address_serve *as;
-        struct list_head *entry;
         unsigned int partlength;
         int rcode = RCODE_ADDRESS_ERROR;
 
         read_lock(&addr_space_lock);
 
-        entry = host->addr_space.next;
-        as = list_entry(entry, struct hpsb_address_serve, as_list);
+	list_for_each_entry(as, &host->addr_space, host_list) {
+		if (as->start > addr)
+			break;
 
-        while (as->start <= addr) {
                 if (as->end > addr) {
                         partlength = min(as->end - addr, (u64) length);
 
@@ -575,9 +668,6 @@
                                 break;
                         }
                 }
-
-                entry = entry->next;
-                as = list_entry(entry, struct hpsb_address_serve, as_list);
         }
 
         read_unlock(&addr_space_lock);
@@ -594,15 +684,14 @@
                    u64 addr, quadlet_t data, quadlet_t arg, int ext_tcode, u16 flags)
 {
         struct hpsb_address_serve *as;
-        struct list_head *entry;
         int rcode = RCODE_ADDRESS_ERROR;
 
         read_lock(&addr_space_lock);
 
-        entry = host->addr_space.next;
-        as = list_entry(entry, struct hpsb_address_serve, as_list);
+	list_for_each_entry(as, &host->addr_space, host_list) {
+		if (as->start > addr)
+			break;
 
-        while (as->start <= addr) {
                 if (as->end > addr) {
                         if (as->op->lock) {
                                 rcode = as->op->lock(host, nodeid, store, addr,
@@ -613,9 +702,6 @@
 
                         break;
                 }
-
-                entry = entry->next;
-                as = list_entry(entry, struct hpsb_address_serve, as_list);
         }
 
         read_unlock(&addr_space_lock);
@@ -627,15 +713,14 @@
                      u64 addr, octlet_t data, octlet_t arg, int ext_tcode, u16 flags)
 {
         struct hpsb_address_serve *as;
-        struct list_head *entry;
         int rcode = RCODE_ADDRESS_ERROR;
 
         read_lock(&addr_space_lock);
 
-        entry = host->addr_space.next;
-        as = list_entry(entry, struct hpsb_address_serve, as_list);
+	list_for_each_entry(as, &host->addr_space, host_list) {
+		if (as->start > addr)
+			break;
 
-        while (as->start <= addr) {
                 if (as->end > addr) {
                         if (as->op->lock64) {
                                 rcode = as->op->lock64(host, nodeid, store,
@@ -647,9 +732,6 @@
 
                         break;
                 }
-
-                entry = entry->next;
-                as = list_entry(entry, struct hpsb_address_serve, as_list);
         }
 
         read_unlock(&addr_space_lock);
diff -Nru a/drivers/ieee1394/highlevel.h b/drivers/ieee1394/highlevel.h
--- a/drivers/ieee1394/highlevel.h	Wed Feb 11 22:28:46 2004
+++ b/drivers/ieee1394/highlevel.h	Wed Feb 11 22:28:46 2004
@@ -4,9 +4,9 @@
 
 
 struct hpsb_address_serve {
-        struct list_head as_list; /* global list */
+        struct list_head host_list; /* per host list */
         
-        struct list_head addr_list; /* hpsb_highlevel list */
+        struct list_head hl_list; /* hpsb_highlevel list */
 
         struct hpsb_address_ops *op;
 
@@ -140,6 +140,11 @@
  * It returns true for successful allocation.  There is no unregister function,
  * all address spaces are deallocated together with the hpsb_highlevel.
  */
+u64 hpsb_allocate_and_register_addrspace(struct hpsb_highlevel *hl,
+					 struct hpsb_host *host,
+					 struct hpsb_address_ops *ops,
+					 u64 size, u64 alignment,
+					 u64 start, u64 end);
 int hpsb_register_addrspace(struct hpsb_highlevel *hl, struct hpsb_host *host,
                             struct hpsb_address_ops *ops, u64 start, u64 end);
 
diff -Nru a/drivers/ieee1394/hosts.c b/drivers/ieee1394/hosts.c
--- a/drivers/ieee1394/hosts.c	Wed Feb 11 22:28:46 2004
+++ b/drivers/ieee1394/hosts.c	Wed Feb 11 22:28:46 2004
@@ -17,14 +17,47 @@
 #include <linux/init.h>
 #include <linux/slab.h>
 #include <linux/pci.h>
+#include <linux/timer.h>
 
+#include "csr1212.h"
+#include "ieee1394.h"
 #include "ieee1394_types.h"
 #include "hosts.h"
 #include "ieee1394_core.h"
 #include "highlevel.h"
 #include "nodemgr.h"
+#include "csr.h"
 
 
+
+static void delayed_reset_bus(unsigned long __reset_info)
+{
+	struct hpsb_host *host = (struct hpsb_host*)__reset_info;
+	int generation = host->csr.generation + 1;
+
+	/* The generation field rolls over to 2 rather than 0 per IEEE
+	 * 1394a-2000. */
+	if (generation > 0xf || generation < 2)
+		generation = 2;
+
+	CSR_SET_BUS_INFO_GENERATION(host->csr.rom, generation);
+	if (csr1212_generate_csr_image(host->csr.rom) != CSR1212_SUCCESS) {
+		/* CSR image creation failed, reset generation field and do not
+		 * issue a bus reset. */
+		CSR_SET_BUS_INFO_GENERATION(host->csr.rom, host->csr.generation);
+		return;
+	}
+
+	host->csr.generation = generation;
+
+	host->update_config_rom = 0;
+	if (host->driver->set_hw_config_rom)
+		host->driver->set_hw_config_rom(host, host->csr.rom->bus_info_data);
+
+	host->csr.gen_timestamp[host->csr.generation] = jiffies;
+	hpsb_reset_bus(host, SHORT_RESET);
+}
+
 static int dummy_transmit_packet(struct hpsb_host *h, struct hpsb_packet *p)
 {
         return 0;
@@ -83,6 +116,12 @@
         if (!h) return NULL;
         memset(h, 0, sizeof(struct hpsb_host) + extra);
 
+	h->csr.rom = csr1212_create_csr(&csr_bus_ops, CSR_BUS_INFO_SIZE, h);
+	if (!h->csr.rom) {
+		kfree(h);
+		return NULL;
+	}
+
 	h->hostdata = h + 1;
         h->driver = drv;
 
@@ -91,6 +130,12 @@
 
 	INIT_LIST_HEAD(&h->addr_space);
 
+	init_timer(&h->delayed_reset);
+	h->delayed_reset.function = delayed_reset_bus;
+	h->delayed_reset.data = (unsigned long)h;
+	for (i = 2; i < 16; i++)
+		h->csr.gen_timestamp[i] = jiffies - 60 * HZ;
+
 	for (i = 0; i < ARRAY_SIZE(h->tpool); i++)
 		HPSB_TPOOL_INIT(&h->tpool[i]);
 
@@ -124,7 +169,6 @@
 void hpsb_add_host(struct hpsb_host *host)
 {
         highlevel_add_host(host);
-        host->driver->devctl(host, RESET_BUS, LONG_RESET);
 }
 
 void hpsb_remove_host(struct hpsb_host *host)
@@ -135,4 +179,36 @@
         highlevel_remove_host(host);
 
 	device_unregister(&host->device);
+}
+
+int hpsb_update_config_rom_image(struct hpsb_host *host)
+{
+	unsigned long reset_time;
+	int next_gen = host->csr.generation + 1;
+
+	if (!host->update_config_rom)
+		return -EINVAL;
+
+	if (next_gen > 0xf)
+		next_gen = 2;
+
+	/* Stop the delayed interrupt, we're about to change the config rom and
+	 * it would be a waste to do a bus reset twice. */
+	del_timer_sync(&host->delayed_reset);
+
+	/* IEEE 1394a-2000 prohibits using the same generation number
+	 * twice in a 60 second period. */
+	if (jiffies - host->csr.gen_timestamp[next_gen] < 60 * HZ)
+		/* Wait 60 seconds from the last time this generation number was
+		 * used. */
+		reset_time = (60 * HZ) + host->csr.gen_timestamp[next_gen];
+	else
+		/* Wait 1 second in case some other code wants to change the
+		 * Config ROM in the near future. */
+		reset_time = jiffies + HZ;
+
+	/* This will add the timer as well as modify it */
+	mod_timer(&host->delayed_reset, reset_time);
+
+	return 0;
 }
diff -Nru a/drivers/ieee1394/hosts.h b/drivers/ieee1394/hosts.h
--- a/drivers/ieee1394/hosts.h	Wed Feb 11 22:28:46 2004
+++ b/drivers/ieee1394/hosts.h	Wed Feb 11 22:28:46 2004
@@ -10,14 +10,6 @@
 #include "ieee1394_types.h"
 #include "csr.h"
 
-/* size of the array used to store config rom (in quadlets)
-   maximum is 0x100. About 0x40 is needed for the default
-   entries. So 0x80 should provide enough space for additional
-   directories etc. 
-   Note: All lowlevel drivers are required to allocate at least
-         this amount of memory for the configuration rom!
-*/
-#define CSR_CONFIG_ROM_SIZE       0x100
 
 struct hpsb_packet;
 struct hpsb_iso;
@@ -70,6 +62,9 @@
 
 	struct device device;
 
+	int update_config_rom;
+	struct timer_list delayed_reset;
+
 	struct list_head addr_space;
 };
 
@@ -153,12 +148,10 @@
 	struct module *owner;
 	const char *name;
 
-        /* This function must store a pointer to the configuration ROM into the
-         * location referenced to by pointer and return the size of the ROM. It
-         * may not fail.  If any allocation is required, it must be done
-         * earlier.
-         */
-        size_t (*get_rom) (struct hpsb_host *host, quadlet_t **pointer);
+	/* The hardware driver may optionally support a function that is used
+	 * to set the hardware ConfigROM if the hardware supports handling
+	 * reads to the ConfigROM on its own. */
+	void (*set_hw_config_rom) (struct hpsb_host *host, quadlet_t *config_rom);
 
         /* This function shall implement packet transmission based on
          * packet->type.  It shall CRC both parts of the packet (unless
@@ -200,24 +193,18 @@
 void hpsb_add_host(struct hpsb_host *host);
 void hpsb_remove_host(struct hpsb_host *h);
 
-/* updates the configuration rom of a host.
- * rom_version must be the current version,
- * otherwise it will fail with return value -1.
- * Return value -2 indicates that the new
- * rom version is too big.
- * Return value 0 indicates success
- */
+/* The following 2 functions are deprecated and will be removed when the
+ * raw1394/libraw1394 update is complete. */
 int hpsb_update_config_rom(struct hpsb_host *host,
       const quadlet_t *new_rom, size_t size, unsigned char rom_version);
-
-/* reads the current version of the configuration rom of a host.
- * buffersize is the size of the buffer, rom_size
- * returns the size of the current rom image.
- * rom_version is the version number of the fetched rom.
- * return value -1 indicates, that the buffer was
- * too small, 0 indicates success.
- */
 int hpsb_get_config_rom(struct hpsb_host *host, quadlet_t *buffer,
       size_t buffersize, size_t *rom_size, unsigned char *rom_version);
+
+/* Updates the configuration rom image of a host.  rom_version must be the
+ * current version, otherwise it will fail with return value -1. If this
+ * host does not support config-rom-update, it will return -EINVAL.
+ * Return value 0 indicates success.
+ */
+int hpsb_update_config_rom_image(struct hpsb_host *host);
 
 #endif /* _IEEE1394_HOSTS_H */
diff -Nru a/drivers/ieee1394/ieee1394_core.c b/drivers/ieee1394/ieee1394_core.c
--- a/drivers/ieee1394/ieee1394_core.c	Wed Feb 11 22:28:46 2004
+++ b/drivers/ieee1394/ieee1394_core.c	Wed Feb 11 22:28:46 2004
@@ -1009,7 +1009,8 @@
 
 	bus_register(&ieee1394_bus_type);
 
-	init_csr();
+	if (init_csr())
+		return -ENOMEM;
 
 	if (!disable_nodemgr)
 		init_ieee1394_nodemgr();
@@ -1043,6 +1044,7 @@
 EXPORT_SYMBOL(hpsb_alloc_host);
 EXPORT_SYMBOL(hpsb_add_host);
 EXPORT_SYMBOL(hpsb_remove_host);
+EXPORT_SYMBOL(hpsb_update_config_rom_image);
 
 /** ieee1394_core.c **/
 EXPORT_SYMBOL(hpsb_speedto_str);
@@ -1081,6 +1083,7 @@
 EXPORT_SYMBOL(hpsb_unregister_highlevel);
 EXPORT_SYMBOL(hpsb_register_addrspace);
 EXPORT_SYMBOL(hpsb_unregister_addrspace);
+EXPORT_SYMBOL(hpsb_allocate_and_register_addrspace);
 EXPORT_SYMBOL(hpsb_listen_channel);
 EXPORT_SYMBOL(hpsb_unlisten_channel);
 EXPORT_SYMBOL(hpsb_get_hostinfo);
@@ -1113,7 +1116,6 @@
 
 /** csr.c **/
 EXPORT_SYMBOL(hpsb_update_config_rom);
-EXPORT_SYMBOL(hpsb_get_config_rom);
 
 /** dma.c **/
 EXPORT_SYMBOL(dma_prog_region_init);
@@ -1144,3 +1146,34 @@
 EXPORT_SYMBOL(hpsb_iso_packet_received);
 EXPORT_SYMBOL(hpsb_iso_wake);
 EXPORT_SYMBOL(hpsb_iso_recv_flush);
+
+/** csr1212.c **/
+EXPORT_SYMBOL(csr1212_create_csr);
+EXPORT_SYMBOL(csr1212_init_local_csr);
+EXPORT_SYMBOL(csr1212_new_immediate);
+EXPORT_SYMBOL(csr1212_new_leaf);
+EXPORT_SYMBOL(csr1212_new_csr_offset);
+EXPORT_SYMBOL(csr1212_new_directory);
+EXPORT_SYMBOL(csr1212_associate_keyval);
+EXPORT_SYMBOL(csr1212_attach_keyval_to_directory);
+EXPORT_SYMBOL(csr1212_new_extended_immediate);
+EXPORT_SYMBOL(csr1212_new_extended_leaf);
+EXPORT_SYMBOL(csr1212_new_descriptor_leaf);
+EXPORT_SYMBOL(csr1212_new_textual_descriptor_leaf);
+EXPORT_SYMBOL(csr1212_new_string_descriptor_leaf);
+EXPORT_SYMBOL(csr1212_new_icon_descriptor_leaf);
+EXPORT_SYMBOL(csr1212_new_modifiable_descriptor_leaf);
+EXPORT_SYMBOL(csr1212_new_keyword_leaf);
+EXPORT_SYMBOL(csr1212_detach_keyval_from_directory);
+EXPORT_SYMBOL(csr1212_disassociate_keyval);
+EXPORT_SYMBOL(csr1212_release_keyval);
+EXPORT_SYMBOL(csr1212_destroy_csr);
+EXPORT_SYMBOL(csr1212_read);
+EXPORT_SYMBOL(csr1212_generate_positions);
+EXPORT_SYMBOL(csr1212_generate_layout_order);
+EXPORT_SYMBOL(csr1212_fill_cache);
+EXPORT_SYMBOL(csr1212_generate_csr_image);
+EXPORT_SYMBOL(csr1212_parse_keyval);
+EXPORT_SYMBOL(csr1212_parse_csr);
+EXPORT_SYMBOL(_csr1212_read_keyval);
+EXPORT_SYMBOL(_csr1212_destroy_keyval);
diff -Nru a/drivers/ieee1394/nodemgr.c b/drivers/ieee1394/nodemgr.c
--- a/drivers/ieee1394/nodemgr.c	Wed Feb 11 22:28:46 2004
+++ b/drivers/ieee1394/nodemgr.c	Wed Feb 11 22:28:46 2004
@@ -28,6 +28,11 @@
 #include "csr.h"
 #include "nodemgr.h"
 
+struct nodemgr_csr_info {
+	struct hpsb_host *host;
+	nodeid_t nodeid;
+	unsigned int generation;
+};
 
 
 static char *nodemgr_find_oui_name(int oui)
@@ -47,6 +52,37 @@
 }
 
 
+static int nodemgr_bus_read(struct csr1212_csr *csr, u64 addr, u16 length,
+                            void *buffer, void *__ci)
+{
+	struct nodemgr_csr_info *ci = (struct nodemgr_csr_info*)__ci;
+	int i, ret = 0;
+
+	for (i = 0; i < 3; i++) {
+		ret = hpsb_read(ci->host, ci->nodeid, ci->generation, addr,
+				buffer, length);
+		if (!ret)
+			break;
+
+		set_current_state(TASK_INTERRUPTIBLE);
+		if (schedule_timeout (HZ/3))
+			return -EINTR;
+	}
+
+	return ret;
+}
+
+static int nodemgr_get_max_rom(quadlet_t *bus_info_data, void *__ci)
+{
+	return (bus_info_data[2] >> 8) & 0x3;
+}
+
+static struct csr1212_bus_ops nodemgr_csr_ops = {
+	.bus_read =	nodemgr_bus_read,
+	.get_max_rom =	nodemgr_get_max_rom
+};
+
+
 /* 
  * Basically what we do here is start off retrieving the bus_info block.
  * From there will fill in some info about the node, verify it is of IEEE
@@ -107,6 +143,26 @@
 	.show   = fw_show_##class##_##field,				\
 };
 
+#define fw_attr_td(class, class_type, td_kv)				\
+static ssize_t fw_show_##class##_##td_kv (struct device *dev, char *buf)\
+{									\
+	int len;							\
+	class_type *class = container_of(dev, class_type, device);	\
+	len = (class->td_kv->value.leaf.len - 2) * sizeof(quadlet_t);	\
+	memcpy(buf,							\
+	       CSR1212_TEXTUAL_DESCRIPTOR_LEAF_DATA(class->td_kv),	\
+	       len);							\
+	while ((buf + len - 1) == '\0')					\
+		len--;							\
+	buf[len++] = '\n';						\
+	buf[len] = '\0';						\
+	return len;							\
+}									\
+static struct device_attribute dev_attr_##class##_##td_kv = {		\
+	.attr = {.name = __stringify(td_kv), .mode = S_IRUGO },		\
+	.show   = fw_show_##class##_##td_kv,				\
+};
+
 
 #define fw_drv_attr(field, type, format_string)			\
 static ssize_t fw_drv_show_##field (struct device_driver *drv, char *buf) \
@@ -126,10 +182,13 @@
 	struct node_entry *ne = container_of(dev, struct node_entry, device);
 
 	return sprintf(buf, "IRMC(%d) CMC(%d) ISC(%d) BMC(%d) PMC(%d) GEN(%d) "
-			"LSPD(%d) MAX_REC(%d) CYC_CLK_ACC(%d)\n", ne->busopt.irmc,
-			ne->busopt.cmc, ne->busopt.isc, ne->busopt.bmc,
-			ne->busopt.pmc, ne->busopt.generation, ne->busopt.lnkspd,
-			ne->busopt.max_rec, ne->busopt.cyc_clk_acc);
+		       "LSPD(%d) MAX_REC(%d) MAX_ROM(%d) CYC_CLK_ACC(%d)\n",
+		       ne->busopt.irmc,
+		       ne->busopt.cmc, ne->busopt.isc, ne->busopt.bmc,
+		       ne->busopt.pmc, ne->busopt.generation, ne->busopt.lnkspd,
+		       ne->busopt.max_rec, 
+		       ne->busopt.max_rom,
+		       ne->busopt.cyc_clk_acc);
 }
 static DEVICE_ATTR(bus_options,S_IRUGO,fw_show_ne_bus_options,NULL);
 
@@ -166,7 +225,7 @@
 fw_attr(ne, struct node_entry, nodeid, unsigned int, "0x%04x\n")
 
 fw_attr(ne, struct node_entry, vendor_id, unsigned int, "0x%06x\n")
-fw_attr(ne, struct node_entry, vendor_name, const char *, "%s\n")
+fw_attr_td(ne, struct node_entry, vendor_name_kv)
 fw_attr(ne, struct node_entry, vendor_oui, const char *, "%s\n")
 
 fw_attr(ne, struct node_entry, guid, unsigned long long, "0x%016Lx\n")
@@ -194,9 +253,9 @@
 fw_attr(ud, struct unit_directory, model_id, unsigned int, "0x%06x\n")
 fw_attr(ud, struct unit_directory, specifier_id, unsigned int, "0x%06x\n")
 fw_attr(ud, struct unit_directory, version, unsigned int, "0x%06x\n")
-fw_attr(ud, struct unit_directory, vendor_name, const char *, "%s\n")
+fw_attr_td(ud, struct unit_directory, vendor_name_kv)
 fw_attr(ud, struct unit_directory, vendor_oui, const char *, "%s\n")
-fw_attr(ud, struct unit_directory, model_name, const char *, "%s\n")
+fw_attr_td(ud, struct unit_directory, model_name_kv)
 
 static struct device_attribute *const fw_ud_attrs[] = {
 	&dev_attr_ud_address,
@@ -358,14 +417,14 @@
 
 	if (ud->flags & UNIT_DIRECTORY_VENDOR_ID) {
 		device_create_file(dev, &dev_attr_ud_vendor_id);
-		if (ud->flags & UNIT_DIRECTORY_VENDOR_TEXT)
-			device_create_file(dev, &dev_attr_ud_vendor_name);
+		if (ud->vendor_name_kv)
+			device_create_file(dev, &dev_attr_ud_vendor_name_kv);
 	}
 
 	if (ud->flags & UNIT_DIRECTORY_MODEL_ID) {
 		device_create_file(dev, &dev_attr_ud_model_id);
-		if (ud->flags & UNIT_DIRECTORY_MODEL_TEXT)
-			device_create_file(dev, &dev_attr_ud_model_name);
+		if (ud->model_name_kv)
+			device_create_file(dev, &dev_attr_ud_model_name_kv);
 	}
 }
 
@@ -410,18 +469,28 @@
 
 static void nodemgr_release_ud(struct device *dev)
 {
+	struct unit_directory *ud = container_of(dev, struct unit_directory, device);
+	if (ud->vendor_name_kv)
+		csr1212_release_keyval(ud->vendor_name_kv);
+	if (ud->model_name_kv)
+		csr1212_release_keyval(ud->model_name_kv);
 	kfree(container_of(dev, struct unit_directory, device));
 }
 
 
 static void nodemgr_release_ne(struct device *dev)
 {
+	struct node_entry *ne = container_of(dev, struct node_entry, device);
+	if (ne->vendor_name_kv)
+		csr1212_release_keyval(ne->vendor_name_kv);
 	kfree(container_of(dev, struct node_entry, device));
 }
 
 
 static void nodemgr_release_host(struct device *dev)
 {
+	struct hpsb_host *host = container_of(dev, struct hpsb_host, device);
+	csr1212_destroy_csr(host->csr.rom);
 	kfree(container_of(dev, struct hpsb_host, device));
 }
 
@@ -444,10 +513,10 @@
 	device_remove_file(dev, &dev_attr_ud_specifier_id);
 	device_remove_file(dev, &dev_attr_ud_version);
 	device_remove_file(dev, &dev_attr_ud_vendor_id);
-	device_remove_file(dev, &dev_attr_ud_vendor_name);
+	device_remove_file(dev, &dev_attr_ud_vendor_name_kv);
 	device_remove_file(dev, &dev_attr_ud_vendor_oui);
 	device_remove_file(dev, &dev_attr_ud_model_id);
-	device_remove_file(dev, &dev_attr_ud_model_name);
+	device_remove_file(dev, &dev_attr_ud_model_name_kv);
 
 	device_unregister(dev);
 }
@@ -476,7 +545,7 @@
 		device_remove_file(dev, fw_ne_attrs[i]);
 
 	device_remove_file(dev, &dev_attr_ne_guid_vendor_oui);
-	device_remove_file(dev, &dev_attr_ne_vendor_name);
+	device_remove_file(dev, &dev_attr_ne_vendor_name_kv);
 	device_remove_file(dev, &dev_attr_ne_vendor_oui);
 
 	device_unregister(dev);
@@ -535,156 +604,13 @@
 };
 
 
-static int nodemgr_read_quadlet(struct hpsb_host *host,
-				nodeid_t nodeid, unsigned int generation,
-				octlet_t address, quadlet_t *quad)
+static void nodemgr_update_bus_options(struct node_entry *ne)
 {
-	int i;
-	int ret = 0;
-
-	for (i = 0; i < 3; i++) {
-		ret = hpsb_read(host, nodeid, generation, address, quad, 4);
-		if (!ret)
-			break;
-
-		set_current_state(TASK_INTERRUPTIBLE);
-		if (schedule_timeout (HZ/3))
-			return -1;
-	}
-	*quad = be32_to_cpu(*quad);
-
-	return ret;
-}
-
-static int nodemgr_size_text_leaf(struct hpsb_host *host,
-				  nodeid_t nodeid, unsigned int generation,
-				  octlet_t address)
-{
-	quadlet_t quad;
-	int size = 0;
-
-	if (nodemgr_read_quadlet(host, nodeid, generation, address, &quad))
-		return -1;
-
-	if (CONFIG_ROM_KEY(quad) == CONFIG_ROM_DESCRIPTOR_LEAF) {
-		/* This is the offset.  */
-		address += 4 * CONFIG_ROM_VALUE(quad); 
-		if (nodemgr_read_quadlet(host, nodeid, generation, address, &quad))
-			return -1;
-		/* Now we got the size of the text descriptor leaf. */
-		size = CONFIG_ROM_LEAF_LENGTH(quad);
-	}
-
-	return size;
-}
-
-static int nodemgr_read_text_leaf(struct node_entry *ne,
-				  octlet_t address,
-				  quadlet_t *quadp)
-{
-	quadlet_t quad;
-	int i, size, ret;
-
-	if (nodemgr_read_quadlet(ne->host, ne->nodeid, ne->generation, address, &quad)
-	    || CONFIG_ROM_KEY(quad) != CONFIG_ROM_DESCRIPTOR_LEAF)
-		return -1;
-
-	/* This is the offset.  */
-	address += 4 * CONFIG_ROM_VALUE(quad);
-	if (nodemgr_read_quadlet(ne->host, ne->nodeid, ne->generation, address, &quad))
-		return -1;
-
-	/* Now we got the size of the text descriptor leaf. */
-	size = CONFIG_ROM_LEAF_LENGTH(quad) - 2;
-	if (size <= 0)
-		return -1;
-
-	address += 4;
-	for (i = 0; i < 2; i++, address += 4, quadp++) {
-		if (nodemgr_read_quadlet(ne->host, ne->nodeid, ne->generation, address, quadp))
-			return -1;
-	}
-
-	/* Now read the text string.  */
-	ret = -ENXIO;
-	for (; size > 0; size--, address += 4, quadp++) {
-		for (i = 0; i < 3; i++) {
-			ret = hpsb_node_read(ne, address, quadp, 4);
-			if (ret != -EAGAIN)
-				break;
-		}
-		if (ret)
-			break;
-	}
-
-	return ret;
-}
-
-static struct node_entry *nodemgr_scan_root_directory
-	(struct hpsb_host *host, nodeid_t nodeid, unsigned int generation)
-{
-	octlet_t address;
-	quadlet_t quad;
-	int length;
-	int code, size, total_size;
-	struct node_entry *ne;
-
-	address = CSR_REGISTER_BASE + CSR_CONFIG_ROM;
-	
-	if (nodemgr_read_quadlet(host, nodeid, generation, address, &quad))
-		return NULL;
-
-	if (CONFIG_ROM_BUS_INFO_LENGTH(quad) == 1)  /* minimal config rom */
-		return NULL;
-
-	address += 4 + CONFIG_ROM_BUS_INFO_LENGTH(quad) * 4;
-
-	if (nodemgr_read_quadlet(host, nodeid, generation, address, &quad))
-		return NULL;
-	length = CONFIG_ROM_ROOT_LENGTH(quad);
-	address += 4;
-
-	size = 0;
-	total_size = sizeof(struct node_entry);
-	for (; length > 0; length--, address += 4) {
-		if (nodemgr_read_quadlet(host, nodeid, generation, address, &quad))
-			return NULL;
-		code = CONFIG_ROM_KEY(quad);
-
-		if (code == CONFIG_ROM_VENDOR_ID && length > 0) {
-			/* Check if there is a text descriptor leaf
-			   immediately after this.  */
-			size = nodemgr_size_text_leaf(host, nodeid, generation,
-						      address + 4);
-			if (size > 0) {
-				address += 4;
-				length--;
-				total_size += (size + 1) * sizeof (quadlet_t);
-			} else if (size < 0)
-				return NULL;
-		}
-	}
-	ne = kmalloc(total_size, GFP_KERNEL);
-
-	if (!ne)
-		return NULL;
-
-	memset(ne, 0, total_size);
-
-	if (size != 0) {
-		ne->vendor_name = (const char *) &(ne->quadlets[2]);
-		ne->quadlets[size] = 0;
-	} else {
-		ne->vendor_name = NULL;
-	}
-
-	return ne; 
-}
-
+#ifdef CONFIG_IEEE1394_VERBOSEDEBUG
+	static const u16 mr[] = { 4, 64, 1024, 0};
+#endif
+	quadlet_t busoptions = be32_to_cpu(ne->csr->bus_info_data[2]);
 
-static void nodemgr_update_bus_options(struct node_entry *ne,
-                                       quadlet_t busoptions)
-{
 	ne->busopt.irmc         = (busoptions >> 31) & 1;
 	ne->busopt.cmc          = (busoptions >> 30) & 1;
 	ne->busopt.isc          = (busoptions >> 29) & 1;
@@ -692,28 +618,32 @@
 	ne->busopt.pmc          = (busoptions >> 27) & 1;
 	ne->busopt.cyc_clk_acc  = (busoptions >> 16) & 0xff;
 	ne->busopt.max_rec      = 1 << (((busoptions >> 12) & 0xf) + 1);
+	ne->busopt.max_rom	= (busoptions >> 8) & 0x3;
 	ne->busopt.generation   = (busoptions >> 4) & 0xf;
 	ne->busopt.lnkspd       = busoptions & 0x7;
 	
 	HPSB_VERBOSE("NodeMgr: raw=0x%08x irmc=%d cmc=%d isc=%d bmc=%d pmc=%d "
-		     "cyc_clk_acc=%d max_rec=%d gen=%d lspd=%d",
+		     "cyc_clk_acc=%d max_rec=%d max_rom=%d gen=%d lspd=%d",
 		     busoptions, ne->busopt.irmc, ne->busopt.cmc,
 		     ne->busopt.isc, ne->busopt.bmc, ne->busopt.pmc,
 		     ne->busopt.cyc_clk_acc, ne->busopt.max_rec,
+		     mr[ne->busopt.max_rom],
 		     ne->busopt.generation, ne->busopt.lnkspd);
 }
 
 
-static struct node_entry *nodemgr_create_node(octlet_t guid, quadlet_t busoptions,
+static struct node_entry *nodemgr_create_node(octlet_t guid, struct csr1212_csr *csr,
 					      struct host_info *hi, nodeid_t nodeid,
 					      unsigned int generation)
 {
 	struct hpsb_host *host = hi->host;
         struct node_entry *ne;
 
-	ne = nodemgr_scan_root_directory (host, nodeid, generation);
+	ne = kmalloc(sizeof(struct node_entry), GFP_KERNEL);
         if (!ne) return NULL;
 
+	memset(ne, 0, sizeof(struct node_entry));
+
 	ne->tpool = &host->tpool[nodeid & NODE_MASK];
 
         ne->host = host;
@@ -724,6 +654,7 @@
         ne->guid = guid;
 	ne->guid_vendor_id = (guid >> 40) & 0xffffff;
 	ne->guid_vendor_oui = nodemgr_find_oui_name(ne->guid_vendor_id);
+	ne->csr = csr;
 
 	memcpy(&ne->device, &nodemgr_dev_template_ne,
 	       sizeof(ne->device));
@@ -737,7 +668,7 @@
 		device_create_file(&ne->device, &dev_attr_ne_guid_vendor_oui);
 	nodemgr_create_ne_dev_files(ne);
 
-	nodemgr_update_bus_options(ne, busoptions);
+	nodemgr_update_bus_options(ne);
 
 	HPSB_DEBUG("%s added: ID:BUS[" NODE_BUS_FMT "]  GUID[%016Lx]",
 		   (host->node_id == nodeid) ? "Host" : "Node",
@@ -821,245 +752,127 @@
 	return search.ne;
 }
 
-static struct unit_directory *nodemgr_scan_unit_directory
-	(struct node_entry *ne, octlet_t address)
-{
-	struct unit_directory *ud;
-	quadlet_t quad;
-	u8 flags, todo;
-	int length, size, total_size, count;
-	int vendor_name_size, model_name_size;
-
-	if (nodemgr_read_quadlet(ne->host, ne->nodeid, ne->generation, address, &quad))
-		return NULL;
-
-	length = CONFIG_ROM_DIRECTORY_LENGTH(quad) ;
-	address += 4;
-
-	size = 0;
-	total_size = sizeof (struct unit_directory);
-	flags = 0;
-	count = 0;
-	vendor_name_size = 0;
-	model_name_size = 0;
-	for (; length > 0; length--, address += 4) {
-		int code;
-		quadlet_t value;
-
-		if (nodemgr_read_quadlet(ne->host, ne->nodeid, ne->generation,
-					 address, &quad))
-			return NULL;
-		code = CONFIG_ROM_KEY(quad);
-		value = CONFIG_ROM_VALUE(quad);
-
-		todo = 0;
-		switch (code) {
-		case CONFIG_ROM_VENDOR_ID:
-			todo = UNIT_DIRECTORY_VENDOR_TEXT;
-			break;
-
-		case CONFIG_ROM_MODEL_ID:
-			todo = UNIT_DIRECTORY_MODEL_TEXT;
-			break;
-
-		case CONFIG_ROM_SPECIFIER_ID:
-		case CONFIG_ROM_UNIT_SW_VERSION:
-			break;
-
-		case CONFIG_ROM_DESCRIPTOR_LEAF:
-		case CONFIG_ROM_DESCRIPTOR_DIRECTORY:
-			/* TODO: read strings... icons? */
-			break;
-
-		default:
-			/* Which types of quadlets do we want to
-			   store?  Only count immediate values and
-			   CSR offsets for now.  */
-			code &= CONFIG_ROM_KEY_TYPE_MASK;
-			if ((code & CONFIG_ROM_KEY_TYPE_LEAF) == 0)
-				count++;
-			break;
-		}
-
-		if (todo && length > 0) {
-			/* Check if there is a text descriptor leaf
-			   immediately after this.  */
-			size = nodemgr_size_text_leaf(ne->host,
-						      ne->nodeid,
-						      ne->generation,
-						      address + 4);
-
-			if (todo == UNIT_DIRECTORY_VENDOR_TEXT)
-				vendor_name_size = size;
-			else
-				model_name_size = size;
-
-			if (size > 0) {
-				address += 4;
-				length--;
-				flags |= todo;
-				total_size += (size + 1) * sizeof (quadlet_t);
-			}
-			else if (size < 0)
-				return NULL;
-		}
-	}
-
-	total_size += count * sizeof (quadlet_t);
-	ud = kmalloc (total_size, GFP_KERNEL);
 
-	if (ud != NULL) {
-		memset (ud, 0, total_size);
-		ud->flags = flags;
-		ud->length = count;
-		ud->vendor_name_size = vendor_name_size;
-		ud->model_name_size = model_name_size;
-	}
-
-	return ud;
-}
 
 
 /* This implementation currently only scans the config rom and its
  * immediate unit directories looking for software_id and
  * software_version entries, in order to get driver autoloading working. */
 static struct unit_directory *nodemgr_process_unit_directory
-	(struct host_info *hi, struct node_entry *ne, octlet_t address, unsigned int *id,
-	 struct unit_directory *parent)
+	(struct host_info *hi, struct node_entry *ne, struct csr1212_keyval *ud_kv,
+	 unsigned int *id, struct unit_directory *parent)
 {
 	struct unit_directory *ud;
-	quadlet_t quad;
-	quadlet_t *infop;
-	int length;
 	struct unit_directory *ud_temp = NULL;
+	struct csr1212_dentry *dentry;
+	struct csr1212_keyval *kv;
+	u8 last_key_id = 0;
 
-	if (!(ud = nodemgr_scan_unit_directory(ne, address)))
+	ud = kmalloc(sizeof(struct unit_directory), GFP_KERNEL);
+	if (!ud)
 		goto unit_directory_error;
 
+	memset (ud, 0, sizeof(struct unit_directory));
+
 	ud->ne = ne;
-	ud->address = address;
+	ud->address = ud_kv->offset + CSR1212_CONFIG_ROM_SPACE_BASE;
+	ud->ud_kv = ud_kv;
 	ud->id = (*id)++;
 
-	if (nodemgr_read_quadlet(ne->host, ne->nodeid, ne->generation,
-				 address, &quad))
-		goto unit_directory_error;
-	length = CONFIG_ROM_DIRECTORY_LENGTH(quad) ;
-	address += 4;
+	csr1212_for_each_dir_entry(ne->csr, kv, ud_kv, dentry) {
+		switch (kv->key.id) {
+		case CSR1212_KV_ID_VENDOR:
+			if (kv->key.type == CSR1212_KV_TYPE_IMMEDIATE) {
+				ud->vendor_id = kv->value.immediate;
+				ud->flags |= UNIT_DIRECTORY_VENDOR_ID;
 
-	infop = (quadlet_t *) ud->quadlets;
-	for (; length > 0; length--, address += 4) {
-		int code;
-		quadlet_t value;
-		quadlet_t *quadp;
-
-		if (nodemgr_read_quadlet(ne->host, ne->nodeid, ne->generation,
-					 address, &quad))
-			goto unit_directory_error;
-		code = CONFIG_ROM_KEY(quad) ;
-		value = CONFIG_ROM_VALUE(quad);
-
-		switch (code) {
-		case CONFIG_ROM_VENDOR_ID:
-			ud->vendor_id = value;
-			ud->flags |= UNIT_DIRECTORY_VENDOR_ID;
-
-			if (ud->vendor_id)
-				ud->vendor_oui = nodemgr_find_oui_name(ud->vendor_id);
-
-			if ((ud->flags & UNIT_DIRECTORY_VENDOR_TEXT) != 0) {
-				length--;
-				address += 4;
-				quadp = &(ud->quadlets[ud->length]);
-				if (nodemgr_read_text_leaf(ne, address, quadp) == 0
-				    && quadp[0] == 0 && quadp[1] == 0) {
-				    	/* We only support minimal
-					   ASCII and English. */
-					quadp[ud->vendor_name_size] = 0;
-					ud->vendor_name
-						= (const char *) &(quadp[2]);
-				}
+				if (ud->vendor_id)
+					ud->vendor_oui = nodemgr_find_oui_name(ud->vendor_id);
 			}
 			break;
 
-		case CONFIG_ROM_MODEL_ID:
-			ud->model_id = value;
+		case CSR1212_KV_ID_MODEL:
+			ud->model_id = kv->value.immediate;
 			ud->flags |= UNIT_DIRECTORY_MODEL_ID;
-			if ((ud->flags & UNIT_DIRECTORY_MODEL_TEXT) != 0) {
-				length--;
-				address += 4;
-				quadp = &(ud->quadlets[ud->length + ud->vendor_name_size + 1]);
-				if (nodemgr_read_text_leaf(ne, address, quadp) == 0
-				    && quadp[0] == 0 && quadp[1] == 0) {
-				    	/* We only support minimal
-					   ASCII and English. */
-					quadp[ud->model_name_size] = 0;
-					ud->model_name
-						= (const char *) &(quadp[2]);
-				}
-			}
 			break;
 
-		case CONFIG_ROM_SPECIFIER_ID:
-			ud->specifier_id = value;
+		case CSR1212_KV_ID_SPECIFIER_ID:
+			ud->specifier_id = kv->value.immediate;
 			ud->flags |= UNIT_DIRECTORY_SPECIFIER_ID;
 			break;
 
-		case CONFIG_ROM_UNIT_SW_VERSION:
-			ud->version = value;
+		case CSR1212_KV_ID_VERSION:
+			ud->version = kv->value.immediate;
 			ud->flags |= UNIT_DIRECTORY_VERSION;
 			break;
 
-		case CONFIG_ROM_DESCRIPTOR_LEAF:
-		case CONFIG_ROM_DESCRIPTOR_DIRECTORY:
-			/* TODO: read strings... icons? */
+		case CSR1212_KV_ID_DESCRIPTOR:
+			if (kv->key.type == CSR1212_KV_TYPE_LEAF &&
+			    CSR1212_DESCRIPTOR_LEAF_TYPE(kv) == 0 &&
+			    CSR1212_DESCRIPTOR_LEAF_SPECIFIER_ID(kv) == 0 &&
+			    CSR1212_TEXTUAL_DESCRIPTOR_LEAF_WIDTH(kv) == 0 &&
+			    CSR1212_TEXTUAL_DESCRIPTOR_LEAF_CHAR_SET(kv) == 0 &&
+			    CSR1212_TEXTUAL_DESCRIPTOR_LEAF_LANGUAGE(kv) == 0) {
+				switch (last_key_id) {
+				case CSR1212_KV_ID_VENDOR:
+					ud->vendor_name_kv = kv;
+					csr1212_keep_keyval(kv);
+					break;
+
+				case CSR1212_KV_ID_MODEL:
+					ud->model_name_kv = kv;
+					csr1212_keep_keyval(kv);
+					break;
+
+				}
+			} /* else if (kv->key.type == CSR1212_KV_TYPE_DIRECTORY) ... */
 			break;
 
-		case CONFIG_ROM_LOGICAL_UNIT_DIRECTORY:
-			ud->flags |= UNIT_DIRECTORY_HAS_LUN_DIRECTORY;
-			ud_temp = nodemgr_process_unit_directory(hi, ne, address + value * 4, id,
-								 parent);
-
-			if (ud_temp == NULL)
-				break;
-
-			/* inherit unspecified values */
-			if ((ud->flags & UNIT_DIRECTORY_VENDOR_ID) &&
-				!(ud_temp->flags & UNIT_DIRECTORY_VENDOR_ID))
-			{
-				ud_temp->flags |=  UNIT_DIRECTORY_VENDOR_ID;
-				ud_temp->vendor_id = ud->vendor_id;
-				ud_temp->vendor_oui = ud->vendor_oui;
-			}
-			if ((ud->flags & UNIT_DIRECTORY_MODEL_ID) &&
-				!(ud_temp->flags & UNIT_DIRECTORY_MODEL_ID))
-			{
-				ud_temp->flags |=  UNIT_DIRECTORY_MODEL_ID;
-				ud_temp->model_id = ud->model_id;
-			}
-			if ((ud->flags & UNIT_DIRECTORY_SPECIFIER_ID) &&
-				!(ud_temp->flags & UNIT_DIRECTORY_SPECIFIER_ID))
-			{
-				ud_temp->flags |=  UNIT_DIRECTORY_SPECIFIER_ID;
-				ud_temp->specifier_id = ud->specifier_id;
-			}
-			if ((ud->flags & UNIT_DIRECTORY_VERSION) &&
-				!(ud_temp->flags & UNIT_DIRECTORY_VERSION))
-			{
-				ud_temp->flags |=  UNIT_DIRECTORY_VERSION;
-				ud_temp->version = ud->version;
+		case CSR1212_KV_ID_DEPENDENT_INFO:
+			if (kv->key.type == CSR1212_KV_TYPE_DIRECTORY) {
+				/* This should really be done in SBP2 as this is
+				 * doing SBP2 specific parsing. */
+				ud->flags |= UNIT_DIRECTORY_HAS_LUN_DIRECTORY;
+				ud_temp = nodemgr_process_unit_directory(hi, ne, kv, id,
+									 parent);
+
+				if (ud_temp == NULL)
+					break;
+
+				/* inherit unspecified values */
+				if ((ud->flags & UNIT_DIRECTORY_VENDOR_ID) &&
+				    !(ud_temp->flags & UNIT_DIRECTORY_VENDOR_ID))
+				{
+					ud_temp->flags |=  UNIT_DIRECTORY_VENDOR_ID;
+					ud_temp->vendor_id = ud->vendor_id;
+					ud_temp->vendor_oui = ud->vendor_oui;
+				}
+				if ((ud->flags & UNIT_DIRECTORY_MODEL_ID) &&
+				    !(ud_temp->flags & UNIT_DIRECTORY_MODEL_ID))
+				{
+					ud_temp->flags |=  UNIT_DIRECTORY_MODEL_ID;
+					ud_temp->model_id = ud->model_id;
+				}
+				if ((ud->flags & UNIT_DIRECTORY_SPECIFIER_ID) &&
+				    !(ud_temp->flags & UNIT_DIRECTORY_SPECIFIER_ID))
+				{
+					ud_temp->flags |=  UNIT_DIRECTORY_SPECIFIER_ID;
+					ud_temp->specifier_id = ud->specifier_id;
+				}
+				if ((ud->flags & UNIT_DIRECTORY_VERSION) &&
+				    !(ud_temp->flags & UNIT_DIRECTORY_VERSION))
+				{
+					ud_temp->flags |=  UNIT_DIRECTORY_VERSION;
+					ud_temp->version = ud->version;
+				}
 			}
 
 			break;
 
 		default:
-			/* Which types of quadlets do we want to
-			   store?  Only count immediate values and
-			   CSR offsets for now.  */
-			code &= CONFIG_ROM_KEY_TYPE_MASK;
-			if ((code & CONFIG_ROM_KEY_TYPE_LEAF) == 0)
-				*infop++ = quad;
 			break;
 		}
+		last_key_id = kv->key.id;
 	}
 
 	memcpy(&ud->device, &nodemgr_dev_template_ud,
@@ -1091,76 +904,49 @@
 
 static void nodemgr_process_root_directory(struct host_info *hi, struct node_entry *ne)
 {
-	octlet_t address;
-	quadlet_t quad;
-	int length;
 	unsigned int ud_id = 0;
-
-	device_remove_file(&ne->device, &dev_attr_ne_vendor_oui);
-
-	address = CSR_REGISTER_BASE + CSR_CONFIG_ROM;
-	
-	if (nodemgr_read_quadlet(ne->host, ne->nodeid, ne->generation,
-				 address, &quad))
-		return;
-	address += 4 + CONFIG_ROM_BUS_INFO_LENGTH(quad) * 4;
-
-	if (nodemgr_read_quadlet(ne->host, ne->nodeid, ne->generation,
-				 address, &quad))
-		return;
-	length = CONFIG_ROM_ROOT_LENGTH(quad);
-	address += 4;
-
-	for (; length > 0; length--, address += 4) {
-		int code, value;
-
-		if (nodemgr_read_quadlet(ne->host, ne->nodeid, ne->generation,
-					 address, &quad))
-			return;
-		code = CONFIG_ROM_KEY(quad);
-		value = CONFIG_ROM_VALUE(quad);
-
-		switch (code) {
-		case CONFIG_ROM_VENDOR_ID:
-			ne->vendor_id = value;
+	struct csr1212_dentry *dentry;
+	struct csr1212_keyval *kv;
+	u8 last_key_id = 0;
+
+	csr1212_for_each_dir_entry(ne->csr, kv, ne->csr->root_kv, dentry) {
+		switch (kv->key.id) {
+		case CSR1212_KV_ID_VENDOR:
+			ne->vendor_id = kv->value.immediate;
 
 			if (ne->vendor_id)
 				ne->vendor_oui = nodemgr_find_oui_name(ne->vendor_id);
-
-			/* Now check if there is a vendor name text
-			   string.  */
-			if (ne->vendor_name != NULL) {
-				length--;
-				address += 4;
-				if (nodemgr_read_text_leaf(ne, address, ne->quadlets) != 0
-				    || ne->quadlets[0] != 0 || ne->quadlets[1] != 0)
-				    	/* We only support minimal
-					   ASCII and English. */
-					ne->vendor_name = NULL;
-				else
-					device_create_file(&ne->device,
-						&dev_attr_ne_vendor_name);
-			}
 			break;
 
-		case CONFIG_ROM_NODE_CAPABILITES:
-			ne->capabilities = value;
+		case CSR1212_KV_ID_NODE_CAPABILITIES:
+			ne->capabilities = kv->value.immediate;
 			break;
 
-		case CONFIG_ROM_UNIT_DIRECTORY:
-			nodemgr_process_unit_directory(hi, ne, address + value * 4, &ud_id,
-						       NULL);
+		case CSR1212_KV_ID_UNIT:
+			nodemgr_process_unit_directory(hi, ne, kv, &ud_id, NULL);
 			break;			
 
-		case CONFIG_ROM_DESCRIPTOR_LEAF:
-		case CONFIG_ROM_DESCRIPTOR_DIRECTORY:
-			/* TODO: read strings... icons? */
+		case CSR1212_KV_ID_DESCRIPTOR:
+			if (last_key_id == CSR1212_KV_ID_VENDOR) {
+				if (kv->key.type == CSR1212_KV_TYPE_LEAF &&
+				    CSR1212_DESCRIPTOR_LEAF_TYPE(kv) == 0 &&
+				    CSR1212_DESCRIPTOR_LEAF_SPECIFIER_ID(kv) == 0 &&
+				    CSR1212_TEXTUAL_DESCRIPTOR_LEAF_WIDTH(kv) == 0 &&
+				    CSR1212_TEXTUAL_DESCRIPTOR_LEAF_CHAR_SET(kv) == 0 &&
+				    CSR1212_TEXTUAL_DESCRIPTOR_LEAF_LANGUAGE(kv) == 0) {
+					ne->vendor_name_kv = kv;
+					csr1212_keep_keyval(kv);
+				}
+			}
 			break;
 		}
+		last_key_id = kv->key.id;
 	}
 
 	if (ne->vendor_oui)
 		device_create_file(&ne->device, &dev_attr_ne_vendor_oui);
+	if (ne->vendor_name_kv)
+		device_create_file(&ne->device, &dev_attr_ne_vendor_name_kv);
 }
 
 #ifdef CONFIG_HOTPLUG
@@ -1261,7 +1047,7 @@
  * informed that this device just went through a bus reset, to allow
  * the to take whatever actions required.
  */
-static void nodemgr_update_node(struct node_entry *ne, quadlet_t busoptions,
+static void nodemgr_update_node(struct node_entry *ne, struct csr1212_csr *csr,
 				struct host_info *hi, nodeid_t nodeid,
 				unsigned int generation)
 {
@@ -1272,12 +1058,16 @@
 		ne->nodeid = nodeid;
 	}
 
-	if (ne->busopt.generation != ((busoptions >> 4) & 0xf)) {
+	if (ne->busopt.generation != ((be32_to_cpu(csr->bus_info_data[2]) >> 4) & 0xf)) {
+		kfree(ne->csr->private);
+		csr1212_destroy_csr(ne->csr);
+		ne->csr = csr;
+
 		/* If the node's configrom generation has changed, we
 		 * unregister all the unit directories. */
 		nodemgr_remove_node_uds(ne);
 
-		nodemgr_update_bus_options(ne, busoptions);
+		nodemgr_update_bus_options(ne);
 
 		/* Mark the node as new, so it gets re-probed */
 		ne->needs_probe = 1;
@@ -1287,72 +1077,7 @@
 	ne->generation = generation;
 }
 
-static int read_businfo_block(struct hpsb_host *host, nodeid_t nodeid, unsigned int generation,
-			      quadlet_t *buffer, int buffer_length)
-{
-	octlet_t addr = CSR_REGISTER_BASE + CSR_CONFIG_ROM;
-	unsigned header_size;
-	int i;
-
-	/* IEEE P1212 says that devices should support 64byte block
-	 * reads, aligned on 64byte boundaries. That doesn't seem to
-	 * work though, and we are forced to doing quadlet sized
-	 * reads.  */
-
-	HPSB_VERBOSE("Initiating ConfigROM request for node " NODE_BUS_FMT,
-		     NODE_BUS_ARGS(host, nodeid));
-
-	/* 
-	 * Must retry a few times if config rom read returns zero (how long?). Will
-	 * not normally occur, but we should do the right thing. For example, with
-	 * some sbp2 devices, the bridge chipset cannot return valid config rom reads
-	 * immediately after power-on, since they need to detect the type of 
-	 * device attached (disk or CD-ROM).
-	 */
-	for (i = 0; i < 4; i++) {
-		if (nodemgr_read_quadlet(host, nodeid, generation,
-					 addr, &buffer[0]) < 0) {
-			HPSB_ERR("ConfigROM quadlet transaction error for node "
-				 NODE_BUS_FMT, NODE_BUS_ARGS(host, nodeid));
-			return -1;
-		}
-		if (buffer[0])
-			break;
-
-		set_current_state(TASK_INTERRUPTIBLE);
-		if (schedule_timeout (HZ/4))
-			return -1;
-	}
-
-	header_size = buffer[0] >> 24;
-	addr += 4;
-
-	if (header_size == 1) {
-		HPSB_INFO("Node " NODE_BUS_FMT " has a minimal ROM.  "
-			  "Vendor is %08x",
-			  NODE_BUS_ARGS(host, nodeid), buffer[0] & 0x00ffffff);
-		return -1;
-	}
-
-	if (header_size < 4) {
-		HPSB_INFO("Node " NODE_BUS_FMT " has non-standard ROM "
-			  "format (%d quads), cannot parse",
-			  NODE_BUS_ARGS(host, nodeid), header_size);
-		return -1;
-	}
-
-	for (i = 1; i < buffer_length; i++, addr += 4) {
-		if (nodemgr_read_quadlet(host, nodeid, generation,
-					 addr, &buffer[i]) < 0) {
-			HPSB_ERR("ConfigROM quadlet transaction "
-				 "error for node " NODE_BUS_FMT,
-				 NODE_BUS_ARGS(host, nodeid));
-			return -1;
-		}
-	}
-
-	return 0;
-}		
+		
 
 
 static void nodemgr_node_scan_one(struct host_info *hi,
@@ -1360,17 +1085,32 @@
 {
 	struct hpsb_host *host = hi->host;
 	struct node_entry *ne;
-	quadlet_t buffer[5];
 	octlet_t guid;
+	struct csr1212_csr *csr;
+	struct nodemgr_csr_info *ci;
+
+	ci = kmalloc(sizeof(struct nodemgr_csr_info), GFP_KERNEL);
+	if (!ci)
+		return;
+
+	ci->host = host;
+	ci->nodeid = nodeid;
+	ci->generation = generation;
 
 	/* We need to detect when the ConfigROM's generation has changed,
 	 * so we only update the node's info when it needs to be.  */
 
-	if (read_businfo_block (host, nodeid, generation,
-				buffer, sizeof(buffer) >> 2))
+	csr = csr1212_create_csr(&nodemgr_csr_ops, 5 * sizeof(quadlet_t), ci);
+	if (!csr || csr1212_parse_csr(csr) != CSR1212_SUCCESS) {
+		HPSB_ERR("Error parsing configrom for node " NODE_BUS_FMT,
+			 NODE_BUS_ARGS(host, nodeid));
+		if (csr)
+			csr1212_destroy_csr(csr);
+		kfree(ci);
 		return;
+	}
 
-	if (buffer[1] != IEEE1394_BUSID_MAGIC) {
+	if (csr->bus_info_data[1] != IEEE1394_BUSID_MAGIC) {
 		/* This isn't a 1394 device, but we let it slide. There
 		 * was a report of a device with broken firmware which
 		 * reported '2394' instead of '1394', which is obviously a
@@ -1379,16 +1119,16 @@
 		 * shouldn't be held responsible, so we'll allow it with a
 		 * warning.  */
 		HPSB_WARN("Node " NODE_BUS_FMT " has invalid busID magic [0x%08x]",
-			  NODE_BUS_ARGS(host, nodeid), buffer[1]);
+			  NODE_BUS_ARGS(host, nodeid), csr->bus_info_data[1]);
 	}
 
-	guid = ((u64)buffer[3] << 32) | buffer[4];
+	guid = ((u64)be32_to_cpu(csr->bus_info_data[3]) << 32) | be32_to_cpu(csr->bus_info_data[4]);
 	ne = find_entry_by_guid(guid);
 
 	if (!ne)
-		nodemgr_create_node(guid, buffer[2], hi, nodeid, generation);
+		nodemgr_create_node(guid, csr, hi, nodeid, generation);
 	else
-		nodemgr_update_node(ne, buffer[2], hi, nodeid, generation);
+		nodemgr_update_node(ne, csr, hi, nodeid, generation);
 
 	return;
 }
diff -Nru a/drivers/ieee1394/nodemgr.h b/drivers/ieee1394/nodemgr.h
--- a/drivers/ieee1394/nodemgr.h	Wed Feb 11 22:28:46 2004
+++ b/drivers/ieee1394/nodemgr.h	Wed Feb 11 22:28:46 2004
@@ -21,50 +21,12 @@
 #define _IEEE1394_NODEMGR_H
 
 #include <linux/device.h>
+#include "csr1212.h"
 #include "ieee1394_core.h"
 #include "ieee1394_hotplug.h"
 
-#define CONFIG_ROM_BUS_INFO_LENGTH(q)		((q) >> 24)
-#define CONFIG_ROM_BUS_CRC_LENGTH(q)		(((q) >> 16) & 0xff)
-#define CONFIG_ROM_BUS_CRC(q)			((q) & 0xffff)
-
-#define CONFIG_ROM_ROOT_LENGTH(q)		((q) >> 16)
-#define CONFIG_ROM_ROOT_CRC(q)			((q) & 0xffff)
-
-#define CONFIG_ROM_DIRECTORY_LENGTH(q)		((q) >> 16)
-#define CONFIG_ROM_DIRECTORY_CRC(q)		((q) & 0xffff)
-
-#define CONFIG_ROM_LEAF_LENGTH(q)		((q) >> 16)
-#define CONFIG_ROM_LEAF_CRC(q)			((q) & 0xffff)
-
-#define CONFIG_ROM_DESCRIPTOR_TYPE(q)		((q) >> 24)
-#define CONFIG_ROM_DESCRIPTOR_SPECIFIER_ID(q)	((q) & 0xffffff)
-#define CONFIG_ROM_DESCRIPTOR_WIDTH(q)		((q) >> 28)
-#define CONFIG_ROM_DESCRIPTOR_CHAR_SET(q)	(((q) >> 16) & 0xfff)
-#define CONFIG_ROM_DESCRIPTOR_LANG(q)		((q) & 0xffff)
-
-#define CONFIG_ROM_KEY_ID_MASK			0x3f
-#define CONFIG_ROM_KEY_TYPE_MASK		0xc0
-#define CONFIG_ROM_KEY_TYPE_IMMEDIATE		0x00
-#define CONFIG_ROM_KEY_TYPE_OFFSET		0x40
-#define CONFIG_ROM_KEY_TYPE_LEAF		0x80
-#define CONFIG_ROM_KEY_TYPE_DIRECTORY		0xc0
-
-#define CONFIG_ROM_KEY(q)			((q) >> 24)
-#define CONFIG_ROM_VALUE(q)			((q) & 0xffffff)
-
-#define CONFIG_ROM_VENDOR_ID			0x03
-#define CONFIG_ROM_MODEL_ID			0x17
-#define CONFIG_ROM_NODE_CAPABILITES		0x0C
-#define CONFIG_ROM_UNIT_DIRECTORY		0xd1
-#define CONFIG_ROM_LOGICAL_UNIT_DIRECTORY	0xd4
-#define CONFIG_ROM_SPECIFIER_ID			0x12 
-#define CONFIG_ROM_UNIT_SW_VERSION		0x13
-#define CONFIG_ROM_DESCRIPTOR_LEAF		0x81
-#define CONFIG_ROM_DESCRIPTOR_DIRECTORY		0xc1
-
 /* '1' '3' '9' '4' in ASCII */
-#define IEEE1394_BUSID_MAGIC	0x31333934
+#define IEEE1394_BUSID_MAGIC	__constant_cpu_to_be32(0x31333934)
 
 /* This is the start of a Node entry structure. It should be a stable API
  * for which to gather info from the Node Manager about devices attached
@@ -76,6 +38,7 @@
 	u8	bmc;		/* Bus Master Capable */
 	u8	pmc;		/* Power Manager Capable (PNP spec) */
 	u8	cyc_clk_acc;	/* Cycle clock accuracy */
+	u8	max_rom;	/* Maximum block read supported in the CSR */
 	u8	generation;	/* Incremented when configrom changes */
 	u8	lnkspd;		/* Link speed */
 	u16	max_rec;	/* Maximum packet size node can receive */
@@ -86,10 +49,8 @@
 #define UNIT_DIRECTORY_MODEL_ID			0x02
 #define UNIT_DIRECTORY_SPECIFIER_ID		0x04
 #define UNIT_DIRECTORY_VERSION			0x08
-#define UNIT_DIRECTORY_VENDOR_TEXT		0x10
-#define UNIT_DIRECTORY_MODEL_TEXT		0x20
-#define UNIT_DIRECTORY_HAS_LUN_DIRECTORY	0x40
-#define UNIT_DIRECTORY_LUN_DIRECTORY		0x80
+#define UNIT_DIRECTORY_HAS_LUN_DIRECTORY	0x10
+#define UNIT_DIRECTORY_LUN_DIRECTORY		0x20
 
 /*
  * A unit directory corresponds to a protocol supported by the
@@ -98,17 +59,15 @@
  */
 struct unit_directory {
 	struct node_entry *ne;  /* The node which this directory belongs to */
-	octlet_t address;	/* Address of the unit directory on the node */
+	octlet_t address;       /* Address of the unit directory on the node */
 	u8 flags;		/* Indicates which entries were read */
 
 	quadlet_t vendor_id;
-	const char *vendor_name;
+	struct csr1212_keyval *vendor_name_kv;
 	const char *vendor_oui;
 
-	int vendor_name_size;
 	quadlet_t model_id;
-	const char *model_name;
-	int model_name_size;
+	struct csr1212_keyval *model_name_kv;
 	quadlet_t specifier_id;
 	quadlet_t version;
 
@@ -118,8 +77,7 @@
 
 	struct device device;
 
-	/* XXX Must be last in the struct! */
-	quadlet_t quadlets[0];
+	struct csr1212_keyval *ud_kv;
 };
 
 struct node_entry {
@@ -135,7 +93,7 @@
 
 	/* The following is read from the config rom */
 	u32 vendor_id;
-	const char *vendor_name;
+	struct csr1212_keyval *vendor_name_kv;
 	const char *vendor_oui;
 
 	u32 capabilities;
@@ -143,8 +101,7 @@
 
 	struct device device;
 
-	/* XXX Must be last in the struct! */
-	quadlet_t quadlets[0];
+	struct csr1212_csr *csr;
 };
 
 struct hpsb_protocol_driver {
diff -Nru a/drivers/ieee1394/ohci1394.c b/drivers/ieee1394/ohci1394.c
--- a/drivers/ieee1394/ohci1394.c	Wed Feb 11 22:28:46 2004
+++ b/drivers/ieee1394/ohci1394.c	Wed Feb 11 22:28:46 2004
@@ -115,6 +115,7 @@
 #include <asm/pci-bridge.h>
 #endif
 
+#include "csr1212.h"
 #include "ieee1394.h"
 #include "ieee1394_types.h"
 #include "hosts.h"
@@ -161,7 +162,7 @@
 printk(level "%s: fw-host%d: " fmt "\n" , OHCI1394_DRIVER_NAME, card , ## args)
 
 static char version[] __devinitdata =
-	"$Rev: 1097 $ Ben Collins <bcollins@debian.org>";
+	"$Rev: 1118 $ Ben Collins <bcollins@debian.org>";
 
 /* Module Parameters */
 static int phys_dma = 1;
@@ -495,8 +496,6 @@
 	return ctx;
 }
 
-static void ohci_init_config_rom(struct ti_ohci *ohci);
-
 /* Global initialization */
 static void ohci_initialize(struct ti_ohci *ohci)
 {
@@ -540,9 +539,6 @@
 	/* Set the Config ROM mapping register */
 	reg_write(ohci, OHCI1394_ConfigROMmap, ohci->csr_config_rom_bus);
 
-	/* Initialize the Config ROM */
-	ohci_init_config_rom(ohci);
-
 	/* Now get our max packet size */
 	ohci->max_packet_size = 
 		1<<(((reg_read(ohci, OHCI1394_BusOptions)>>12)&0xf)+1);
@@ -3085,154 +3081,16 @@
 	return 0;
 }
 
-static u16 ohci_crc16 (u32 *ptr, int length)
-{
-	int shift;
-	u32 crc, sum, data;
-
-	crc = 0;
-	for (; length > 0; length--) {
-		data = be32_to_cpu(*ptr++);
-		for (shift = 28; shift >= 0; shift -= 4) {
-			sum = ((crc >> 12) ^ (data >> shift)) & 0x000f;
-			crc = (crc << 4) ^ (sum << 12) ^ (sum << 5) ^ sum;
-		}
-		crc &= 0xffff;
-	}
-	return crc;
-}
-
-/* Config ROM macro implementation influenced by NetBSD OHCI driver */
-
-struct config_rom_unit {
-	u32 *start;
-	u32 *refer;
-	int length;
-	int refunit;
-};
-
-struct config_rom_ptr {
-	u32 *data;
-	int unitnum;
-	struct config_rom_unit unitdir[10];
-};
-
-#define cf_put_1quad(cr, q) (((cr)->data++)[0] = cpu_to_be32(q))
-
-#define cf_put_4bytes(cr, b1, b2, b3, b4) \
-	(((cr)->data++)[0] = cpu_to_be32(((b1) << 24) | ((b2) << 16) | ((b3) << 8) | (b4)))
-
-#define cf_put_keyval(cr, key, val) (((cr)->data++)[0] = cpu_to_be32(((key) << 24) | (val)))
-
-static inline void cf_put_str(struct config_rom_ptr *cr, const char *str)
+static void ohci_set_hw_config_rom(struct hpsb_host *host, quadlet_t *config_rom)
 {
-	int t;
-	char fourb[4];
-
-	while (str[0]) {
-		memset(fourb, 0, 4);
-		for (t = 0; t < 4 && str[t]; t++)
-			fourb[t] = str[t];
-		cf_put_4bytes(cr, fourb[0], fourb[1], fourb[2], fourb[3]);
-		str += strlen(str) < 4 ? strlen(str) : 4;
-	}
-	return;
-}
-
-static inline void cf_put_crc16(struct config_rom_ptr *cr, int unit)
-{
-	*cr->unitdir[unit].start =
-		cpu_to_be32((cr->unitdir[unit].length << 16) |
-			    ohci_crc16(cr->unitdir[unit].start + 1,
-				       cr->unitdir[unit].length));
-}
-
-static inline void cf_unit_begin(struct config_rom_ptr *cr, int unit)
-{
-	if (cr->unitdir[unit].refer != NULL) {
-		*cr->unitdir[unit].refer |=
-			cpu_to_be32 (cr->data - cr->unitdir[unit].refer);
-		cf_put_crc16(cr, cr->unitdir[unit].refunit);
-	}
-	cr->unitnum = unit;
-	cr->unitdir[unit].start = cr->data++;
-}
-
-static inline void cf_put_refer(struct config_rom_ptr *cr, char key, int unit)
-{
-	cr->unitdir[unit].refer = cr->data;
-	cr->unitdir[unit].refunit = cr->unitnum;
-	(cr->data++)[0] = cpu_to_be32(key << 24);
-}
-
-static inline void cf_unit_end(struct config_rom_ptr *cr)
-{
-	cr->unitdir[cr->unitnum].length = cr->data -
-		(cr->unitdir[cr->unitnum].start + 1);
-	cf_put_crc16(cr, cr->unitnum);
-}
-
-/* End of NetBSD derived code.  */
-
-static void ohci_init_config_rom(struct ti_ohci *ohci)
-{
-	struct config_rom_ptr cr;
-
-	memset(&cr, 0, sizeof(cr));
-	memset(ohci->csr_config_rom_cpu, 0, OHCI_CONFIG_ROM_LEN);
-
-	cr.data = ohci->csr_config_rom_cpu;
-
-	/* Bus info block */
-	cf_unit_begin(&cr, 0);
-	cf_put_1quad(&cr, reg_read(ohci, OHCI1394_BusID));
-	cf_put_1quad(&cr, reg_read(ohci, OHCI1394_BusOptions));
-	cf_put_1quad(&cr, reg_read(ohci, OHCI1394_GUIDHi));
-	cf_put_1quad(&cr, reg_read(ohci, OHCI1394_GUIDLo));
-	cf_unit_end(&cr);
-
-	DBGMSG(ohci->id, "GUID: %08x:%08x", reg_read(ohci, OHCI1394_GUIDHi),
-		reg_read(ohci, OHCI1394_GUIDLo));
-
-	/* IEEE P1212 suggests the initial ROM header CRC should only
-	 * cover the header itself (and not the entire ROM). Since we do
-	 * this, then we can make our bus_info_len the same as the CRC
-	 * length.  */
-	ohci->csr_config_rom_cpu[0] |= cpu_to_be32(
-		(be32_to_cpu(ohci->csr_config_rom_cpu[0]) & 0x00ff0000) << 8);
-	reg_write(ohci, OHCI1394_ConfigROMhdr,
-		  be32_to_cpu(ohci->csr_config_rom_cpu[0]));
-
-	/* Root directory */
-	cf_unit_begin(&cr, 1);
-	/* Vendor ID */
-	cf_put_keyval(&cr, 0x03, reg_read(ohci,OHCI1394_VendorID) & 0xFFFFFF);
-	cf_put_refer(&cr, 0x81, 2);		/* Textual description unit */
-	cf_put_keyval(&cr, 0x0c, 0x0083c0);	/* Node capabilities */
-	/* NOTE: Add other unit referers here, and append at bottom */
-	cf_unit_end(&cr);
+	struct ti_ohci *ohci = host->hostdata;
 
-	/* Textual description - "Linux 1394" */
-	cf_unit_begin(&cr, 2);
-	cf_put_keyval(&cr, 0, 0);
-	cf_put_1quad(&cr, 0);
-	cf_put_str(&cr, "Linux OHCI-1394");
-	cf_unit_end(&cr);
+	reg_write(ohci, OHCI1394_ConfigROMhdr, be32_to_cpu(config_rom[0]));
+	reg_write(ohci, OHCI1394_BusOptions, be32_to_cpu(config_rom[2]));
 
-	ohci->csr_config_rom_length = cr.data - ohci->csr_config_rom_cpu;
+	memcpy(ohci->csr_config_rom_cpu, config_rom, OHCI_CONFIG_ROM_LEN);
 }
 
-static size_t ohci_get_rom(struct hpsb_host *host, quadlet_t **ptr)
-{
-	struct ti_ohci *ohci=host->hostdata;
-
-	DBGMSG(ohci->id, "request csr_rom address: %p",
-		ohci->csr_config_rom_cpu);
-
-	*ptr = ohci->csr_config_rom_cpu;
-
-	return ohci->csr_config_rom_length * 4;
-}
 
 static quadlet_t ohci_hw_csr_reg(struct hpsb_host *host, int reg,
                                  quadlet_t data, quadlet_t compare)
@@ -3257,7 +3115,7 @@
 static struct hpsb_host_driver ohci1394_driver = {
 	.owner =		THIS_MODULE,
 	.name =			OHCI1394_DRIVER_NAME,
-	.get_rom =		ohci_get_rom,
+	.set_hw_config_rom =	ohci_set_hw_config_rom,
 	.transmit_packet =	ohci_transmit,
 	.devctl =		ohci_devctl,
 	.isoctl =               ohci_isoctl,
@@ -3280,6 +3138,11 @@
 static int __devinit ohci1394_pci_probe(struct pci_dev *dev,
 					const struct pci_device_id *ent)
 {
+	struct csr1212_keyval *root;
+	struct csr1212_keyval *vend_id = NULL;
+	struct csr1212_keyval *text = NULL;
+	int ret;
+
 	static int version_printed = 0;
 
 	struct hpsb_host *host;
@@ -3457,6 +3320,45 @@
 
 	ohci->init_state = OHCI_INIT_HAVE_IRQ;
 	ohci_initialize(ohci);
+
+	/* Setup initial root directory entries */
+	root = host->csr.rom->root_kv;
+
+	vend_id = csr1212_new_immediate(CSR1212_KV_ID_VENDOR,
+					reg_read(ohci, OHCI1394_GUIDHi) >> 8);
+	text = csr1212_new_string_descriptor_leaf("Linux 1394 - OHCI");
+
+	if (!vend_id || !text) {
+		if (vend_id) {
+			csr1212_release_keyval(vend_id);
+		}
+		if (text) {
+			csr1212_release_keyval(text);
+		}
+		FAIL(-ENOMEM, "Failed to allocate memory for mandatory ConfigROM entries!");
+	}
+
+	ret = csr1212_associate_keyval(vend_id, text);
+	csr1212_release_keyval(text);
+	if(ret != CSR1212_SUCCESS) {
+		csr1212_release_keyval(vend_id);
+		FAIL(ret, "Failed to associate text descriptor to vendor id");
+	}
+
+	ret = csr1212_attach_keyval_to_directory(root, vend_id);
+	if(ret != CSR1212_SUCCESS) {
+		csr1212_release_keyval(vend_id);
+		FAIL(ret, "Failed to attach vendor id to root directory");
+	}
+
+	host->update_config_rom = 1;
+
+	/* Set certain csr values */
+	host->csr.guid_hi = reg_read(ohci, OHCI1394_GUIDHi);
+	host->csr.guid_lo = reg_read(ohci, OHCI1394_GUIDLo);
+	host->csr.cyc_clk_acc = 100;  /* how do we determine clk accuracy? */
+	host->csr.max_rec = (reg_read(ohci, OHCI1394_BusOptions) >> 12) & 0xf;
+	host->csr.lnk_spd = reg_read(ohci, OHCI1394_BusOptions) & 0x7;
 
 	/* Tell the highlevel this host is ready */
 	hpsb_add_host(host);
diff -Nru a/drivers/ieee1394/pcilynx.c b/drivers/ieee1394/pcilynx.c
--- a/drivers/ieee1394/pcilynx.c	Wed Feb 11 22:28:46 2004
+++ b/drivers/ieee1394/pcilynx.c	Wed Feb 11 22:28:46 2004
@@ -49,6 +49,7 @@
 #include <asm/io.h>
 #include <asm/uaccess.h>
 
+#include "csr1212.h"
 #include "ieee1394.h"
 #include "ieee1394_types.h"
 #include "hosts.h"
@@ -1515,6 +1516,11 @@
         return error; \
         } while (0)
 
+	struct csr1212_keyval *root;
+	struct csr1212_keyval *vend_id = NULL;
+	struct csr1212_keyval *text = NULL;
+	int ret;
+
 	char irq_buf[16];
 	struct hpsb_host *host;
         struct ti_lynx *lynx; /* shortcut to currently handled device */
@@ -1527,8 +1533,6 @@
         struct i2c_adapter i2c_adapter;
         struct i2c_algo_bit_data i2c_adapter_data;
 
-        int got_valid_bus_info_block = 0; /* set to 1, if we were able to get a valid bus info block from serial eeprom */
-
         error = -ENXIO;
 
         if (pci_set_dma_mask(dev, 0xffffffff))
@@ -1814,14 +1818,15 @@
 
         	if (i2c_bit_add_bus(&i2c_adapter) < 0)
         	{
-	        	PRINT(KERN_ERR, lynx->id,  "unable to register i2c");
+			error = -ENXIO;
+			FAIL("unable to register i2c");
         	}
         	else
         	{
                         /* do i2c stuff */
                         unsigned char i2c_cmd = 0x10;
                         struct i2c_msg msg[2] = { { 0x50, 0, 1, &i2c_cmd }, 
-                                                  { 0x50, I2C_M_RD, 20, (unsigned char*) lynx->config_rom }
+                                                  { 0x50, I2C_M_RD, 20, (unsigned char*) lynx->bus_info_block }
                                                 };
 
 
@@ -1858,16 +1863,16 @@
 
                                 for (i = 0; i < 5 ; i++)
                                         PRINTD(KERN_DEBUG, lynx->id, "Businfo block quadlet %i: %08x",
-					       i, be32_to_cpu(lynx->config_rom[i]));
+					       i, be32_to_cpu(lynx->bus_info_block[i]));
 
                                 /* info_length, crc_length and 1394 magic number to check, if it is really a bus info block */
-                                if (((be32_to_cpu(lynx->config_rom[0]) & 0xffff0000) == 0x04040000) &&
-                                    (lynx->config_rom[1] == __constant_cpu_to_be32(0x31333934)))
+				if (((be32_to_cpu(lynx->bus_info_block[0]) & 0xffff0000) == 0x04040000) &&
+				    (lynx->bus_info_block[1] == __constant_cpu_to_be32(0x31333934)))
                                 {
                                         PRINT(KERN_DEBUG, lynx->id, "read a valid bus info block from");
-                                        got_valid_bus_info_block = 1;
                                 } else {
-                                        PRINT(KERN_WARNING, lynx->id, "read something from serial eeprom, but it does not seem to be a valid bus info block");
+					error = -ENXIO;
+					FAIL("read something from serial eeprom, but it does not seem to be a valid bus info block");
                                 }
 
                         }
@@ -1876,29 +1881,55 @@
                 }
         }
 
-        if (got_valid_bus_info_block) {
-                memcpy(lynx->config_rom+5,lynx_csr_rom+5,sizeof(lynx_csr_rom)-20);
-        } else {
-                PRINT(KERN_INFO, lynx->id, "since we did not get a bus info block from serial eeprom, we use a generic one with a hard coded GUID");
-                memcpy(lynx->config_rom,lynx_csr_rom,sizeof(lynx_csr_rom));
-        }
-
-        hpsb_add_host(host);
-        lynx->state = is_host;
+	host->csr.guid_hi = be32_to_cpu(lynx->bus_info_block[3]);
+	host->csr.guid_lo = be32_to_cpu(lynx->bus_info_block[4]);
+	host->csr.cyc_clk_acc = (be32_to_cpu(lynx->bus_info_block[2]) >> 16) & 0xff;
+	host->csr.max_rec = (be32_to_cpu(lynx->bus_info_block[2]) >> 12) & 0xf;
+	if (!lynx->phyic.reg_1394a)
+		host->csr.lnk_spd = (get_phy_reg(lynx, 2) & 0xc0) >> 6;
+	else
+		host->csr.lnk_spd = be32_to_cpu(lynx->bus_info_block[2]) & 0x7;
+
+	/* Setup initial root directory entries */
+	root = host->csr.rom->root_kv;
+
+	vend_id = csr1212_new_immediate(CSR1212_KV_ID_VENDOR,
+					be32_to_cpu(lynx->bus_info_block[3]) >> 8);
+	text = csr1212_new_string_descriptor_leaf("Linux 1394 - PCI-Lynx");
+
+	if (!vend_id || !text) {
+		if (vend_id)
+			csr1212_release_keyval(vend_id);
+		if (text)
+			csr1212_release_keyval(text);
+		error = -ENOMEM;
+		FAIL("Failed to allocate memory for mandatory ConfigROM entries!");
+	}
 
-        return 0;
-#undef FAIL
-}
+	ret = csr1212_associate_keyval(vend_id, text);
+	csr1212_release_keyval(text);		/* no longer needed locally. */
+	if(ret != CSR1212_SUCCESS) {
+		csr1212_release_keyval(vend_id);
+		error = ret;
+		FAIL("Failed to associate text descriptor to vendor id");
+	}
 
+	ret = csr1212_attach_keyval_to_directory(root, vend_id);
+	csr1212_release_keyval(vend_id);	/* no longer needed locally. */
+	if(ret != CSR1212_SUCCESS) {
+		error = ret;
+		FAIL("Failed to attach vendor id to root directory");
+	}
 
+	host->update_config_rom = 1;
+	hpsb_add_host(host);
+	lynx->state = is_host;
 
-static size_t get_lynx_rom(struct hpsb_host *host, quadlet_t **ptr)
-{
-        struct ti_lynx *lynx = host->hostdata;
-        *ptr = lynx->config_rom;
-        return sizeof(lynx_csr_rom);
+	return ret;
+#undef FAIL
 }
 
+
 static struct pci_device_id pci_table[] = {
 	{
                 .vendor =    PCI_VENDOR_ID_TI,
@@ -1919,7 +1950,7 @@
 static struct hpsb_host_driver lynx_driver = {
 	.owner =	   THIS_MODULE,
 	.name =		   PCILYNX_DRIVER_NAME,
-        .get_rom =         get_lynx_rom,
+	.set_hw_config_rom = NULL,
         .transmit_packet = lynx_transmit,
         .devctl =          lynx_devctl,
 	.isoctl =          NULL,
diff -Nru a/drivers/ieee1394/pcilynx.h b/drivers/ieee1394/pcilynx.h
--- a/drivers/ieee1394/pcilynx.h	Wed Feb 11 22:28:46 2004
+++ b/drivers/ieee1394/pcilynx.h	Wed Feb 11 22:28:46 2004
@@ -1,3 +1,6 @@
+#ifndef __PCILYNX_H__
+#define __PCILYNX_H__
+
 #include <linux/config.h>
 
 #define PCILYNX_DRIVER_NAME      "pcilynx"
@@ -50,7 +53,7 @@
         void *local_rom;
         void *local_ram;
         void *aux_port;
-        quadlet_t config_rom[PCILYNX_CONFIG_ROM_LENGTH/4];
+	quadlet_t bus_info_block[5];
 
 #ifdef CONFIG_IEEE1394_PCILYNX_PORTS
         atomic_t aux_intr_seen;
@@ -510,76 +513,4 @@
 #define PCL_BIGENDIAN          (1<<16)
 #define PCL_ISOMODE            (1<<12)
 
-
-#define _(x) (__constant_cpu_to_be32(x))
-
-static quadlet_t lynx_csr_rom[] = {
-/* bus info block     offset (hex) */
-        _(0x04046aaf), /* info/CRC length, CRC              400  */
-        _(0x31333934), /* 1394 magic number                 404  */
-        _(0xf064a000), /* misc. settings                    408  */
-        _(0x08002850), /* vendor ID, chip ID high           40c  */
-        _(0x0000ffff), /* chip ID low                       410  */
-/* root directory */
-        _(0x00095778), /* directory length, CRC             414  */
-        _(0x03080028), /* vendor ID (Texas Instr.)          418  */
-        _(0x81000008), /* offset to textual ID              41c  */
-        _(0x0c000200), /* node capabilities                 420  */
-        _(0x8d00000e), /* offset to unique ID               424  */
-        _(0xc7000010), /* offset to module independent info 428  */
-        _(0x04000000), /* module hardware version           42c  */
-        _(0x81000014), /* offset to textual ID              430  */
-        _(0x09000000), /* node hardware version             434  */
-        _(0x81000018), /* offset to textual ID              438  */
-/* module vendor ID textual */
-        _(0x00070812), /* CRC length, CRC                   43c  */
-        _(0x00000000), /*                                   440  */
-        _(0x00000000), /*                                   444  */
-        _(0x54455841), /* "Texas Instruments"               448  */
-        _(0x5320494e), /*                                   44c  */
-        _(0x53545255), /*                                   450  */
-        _(0x4d454e54), /*                                   454  */
-        _(0x53000000), /*                                   458  */
-/* node unique ID leaf */
-        _(0x00022ead), /* CRC length, CRC                   45c  */
-        _(0x08002850), /* vendor ID, chip ID high           460  */
-        _(0x0000ffff), /* chip ID low                       464  */
-/* module dependent info */
-        _(0x0005d837), /* CRC length, CRC                   468  */
-        _(0x81000012), /* offset to module textual ID       46c  */
-        _(0x81000017), /* textual descriptor                470  */
-        _(0x39010000), /* SRAM size                         474  */
-        _(0x3a010000), /* AUXRAM size                       478  */
-        _(0x3b000000), /* AUX device                        47c  */
-/* module textual ID */
-        _(0x000594df), /* CRC length, CRC                   480  */
-        _(0x00000000), /*                                   484  */
-        _(0x00000000), /*                                   488  */
-        _(0x54534231), /* "TSB12LV21"                       48c  */
-        _(0x324c5632), /*                                   490  */
-        _(0x31000000), /*                                   494  */
-/* part number */
-        _(0x00068405), /* CRC length, CRC                   498  */
-        _(0x00000000), /*                                   49c  */
-        _(0x00000000), /*                                   4a0  */
-        _(0x39383036), /* "9806000-0001"                    4a4  */
-        _(0x3030302d), /*                                   4a8  */
-        _(0x30303031), /*                                   4ac  */
-        _(0x20000001), /*                                   4b0  */
-/* module hardware version textual */
-        _(0x00056501), /* CRC length, CRC                   4b4  */
-        _(0x00000000), /*                                   4b8  */
-        _(0x00000000), /*                                   4bc  */
-        _(0x5453424b), /* "TSBKPCITST"                      4c0  */
-        _(0x50434954), /*                                   4c4  */
-        _(0x53540000), /*                                   4c8  */
-/* node hardware version textual */
-        _(0x0005d805), /* CRC length, CRC                   4d0  */
-        _(0x00000000), /*                                   4d4  */
-        _(0x00000000), /*                                   4d8  */
-        _(0x54534232), /* "TSB21LV03"                       4dc  */
-        _(0x314c5630), /*                                   4e0  */
-        _(0x33000000)  /*                                   4e4  */
-};
-
-#undef _
+#endif
diff -Nru a/drivers/ieee1394/raw1394-private.h b/drivers/ieee1394/raw1394-private.h
--- a/drivers/ieee1394/raw1394-private.h	Wed Feb 11 22:28:46 2004
+++ b/drivers/ieee1394/raw1394-private.h	Wed Feb 11 22:28:46 2004
@@ -7,6 +7,8 @@
 #define RAW1394_DEVICE_MAJOR      171
 #define RAW1394_DEVICE_NAME       "raw1394"
 
+#define RAW1394_MAX_USER_CSR_DIRS	16
+
 struct iso_block_store {
         atomic_t refcount;
         size_t data_size;
@@ -45,6 +47,12 @@
 	/* new rawiso API */
 	enum raw1394_iso_state iso_state;
 	struct hpsb_iso *iso_handle;
+
+	/* User space's CSR1212 dynamic ConfigROM directories */
+	struct csr1212_keyval *csr1212_dirs[RAW1394_MAX_USER_CSR_DIRS];
+
+	/* Legacy ConfigROM update flag */
+	u8 cfgrom_upd;
 };
 
 struct arm_addr {
diff -Nru a/drivers/ieee1394/raw1394.c b/drivers/ieee1394/raw1394.c
--- a/drivers/ieee1394/raw1394.c	Wed Feb 11 22:28:46 2004
+++ b/drivers/ieee1394/raw1394.c	Wed Feb 11 22:28:46 2004
@@ -43,6 +43,7 @@
 #include <asm/atomic.h>
 #include <linux/devfs_fs_kernel.h>
 
+#include "csr1212.h"
 #include "ieee1394.h"
 #include "ieee1394_types.h"
 #include "ieee1394_core.h"
@@ -1822,9 +1823,9 @@
 			if (req->req.address + req->req.length <= arm_addr->end) {
 				offset = req->req.address - arm_addr->start;
 
-				DBGMSG("arm_get_buf copy_to_user( %08X, %08X, %u )",
+				DBGMSG("arm_get_buf copy_to_user( %08X, %p, %u )",
 				       (u32) req->req.recvb,
-				       (u32) (arm_addr->addr_space_buffer+offset),
+				       arm_addr->addr_space_buffer+offset,
 				       (u32) req->req.length);
 
 				if (copy_to_user(int2ptr(req->req.recvb), arm_addr->addr_space_buffer+offset, req->req.length)) {
@@ -1833,7 +1834,10 @@
 				}
 
 				spin_unlock_irqrestore(&host_info_lock, flags);
-				free_pending_request(req); /* we have to free the request, because we queue no response, and therefore nobody will free it */
+				/* We have to free the request, because we
+				 * queue no response, and therefore nobody
+				 * will free it. */
+				free_pending_request(req);
 				return sizeof(struct raw1394_request);
 			} else {
 				DBGMSG("arm_get_buf request exceeded mapping");
@@ -1873,8 +1877,8 @@
 			if (req->req.address + req->req.length <= arm_addr->end) {
 				offset = req->req.address - arm_addr->start;
 
-				DBGMSG("arm_set_buf copy_from_user( %08X, %08X, %u )",
-				       (u32) (arm_addr->addr_space_buffer+offset),
+				DBGMSG("arm_set_buf copy_from_user( %p, %08X, %u )",
+				       arm_addr->addr_space_buffer+offset,
 				       (u32) req->req.sendb,
 				       (u32) req->req.length);
 
@@ -1941,22 +1945,22 @@
 
 static int get_config_rom(struct file_info *fi, struct pending_request *req)
 {
-        size_t return_size;
-        unsigned char rom_version;
         int ret=sizeof(struct raw1394_request);
         quadlet_t *data = kmalloc(req->req.length, SLAB_KERNEL);
         int status;
+
         if (!data) return -ENOMEM;
-        status = hpsb_get_config_rom(fi->host, data, 
-                req->req.length, &return_size, &rom_version);
+
+	status = csr1212_read(fi->host->csr.rom, CSR1212_CONFIG_ROM_SPACE_OFFSET,
+			      data, req->req.length);
         if (copy_to_user(int2ptr(req->req.recvb), data, 
                 req->req.length))
                 ret = -EFAULT;
-        if (copy_to_user(int2ptr(req->req.tag), &return_size, 
-                sizeof(return_size)))
+	if (copy_to_user(int2ptr(req->req.tag), &fi->host->csr.rom->cache_head->len,
+			 sizeof(fi->host->csr.rom->cache_head->len)))
                 ret = -EFAULT;
-        if (copy_to_user(int2ptr(req->req.address), &rom_version, 
-                sizeof(rom_version)))
+	if (copy_to_user(int2ptr(req->req.address), &fi->host->csr.generation,
+			 sizeof(fi->host->csr.generation)))
                 ret = -EFAULT;
         if (copy_to_user(int2ptr(req->req.sendb), &status, 
                 sizeof(status)))
@@ -1987,10 +1991,122 @@
         kfree(data);
         if (ret >= 0) {
                 free_pending_request(req); /* we have to free the request, because we queue no response, and therefore nobody will free it */
+		fi->cfgrom_upd = 1;
         }
         return ret;
 }
 
+static int modify_config_rom(struct file_info *fi, struct pending_request *req)
+{
+	struct csr1212_keyval *kv;
+	struct csr1212_csr_rom_cache *cache;
+	struct csr1212_dentry *dentry;
+	u32 dr;
+	int ret = 0;
+
+	if (req->req.misc == ~0) {
+		if (req->req.length == 0) return -EINVAL;
+
+		/* Find an unused slot */
+		for (dr = 0; dr < RAW1394_MAX_USER_CSR_DIRS && fi->csr1212_dirs[dr]; dr++);
+
+		if (dr == RAW1394_MAX_USER_CSR_DIRS) return -ENOMEM;
+
+		fi->csr1212_dirs[dr] = csr1212_new_directory(CSR1212_KV_ID_VENDOR);
+		if (!fi->csr1212_dirs[dr]) return -ENOMEM;
+	} else {
+		dr = req->req.misc;
+		if (!fi->csr1212_dirs[dr]) return -EINVAL;
+
+		/* Delete old stuff */
+		for (dentry = fi->csr1212_dirs[dr]->value.directory.dentries_head;
+		     dentry; dentry = dentry->next) {
+			csr1212_detach_keyval_from_directory(fi->host->csr.rom->root_kv,
+							     dentry->kv);
+		}
+
+		if (req->req.length == 0) {
+			csr1212_release_keyval(fi->csr1212_dirs[dr]);
+			fi->csr1212_dirs[dr] = NULL;
+
+			hpsb_update_config_rom_image(fi->host);
+			free_pending_request(req);
+			return sizeof(struct raw1394_request);
+		}
+	}
+
+	cache = csr1212_rom_cache_malloc(0, req->req.length);
+	if (!cache) {
+		csr1212_release_keyval(fi->csr1212_dirs[dr]);
+		fi->csr1212_dirs[dr] = NULL;
+		return -ENOMEM;
+	}
+
+	cache->filled_head = kmalloc(sizeof(struct csr1212_cache_region), GFP_KERNEL);
+	if (!cache->filled_head) {
+		csr1212_release_keyval(fi->csr1212_dirs[dr]);
+		fi->csr1212_dirs[dr] = NULL;
+		CSR1212_FREE(cache);
+		return -ENOMEM;
+	}
+	cache->filled_tail = cache->filled_head;
+
+	if (copy_from_user(cache->data, int2ptr(req->req.sendb),
+			   req->req.length)) {
+		csr1212_release_keyval(fi->csr1212_dirs[dr]);
+		fi->csr1212_dirs[dr] = NULL;
+		CSR1212_FREE(cache);
+		ret= -EFAULT;
+	} else {
+		cache->len = req->req.length;
+		cache->filled_head->offset_start = 0;
+		cache->filled_head->offset_end = cache->size -1;
+
+		cache->layout_head = cache->layout_tail = fi->csr1212_dirs[dr];
+
+		ret = CSR1212_SUCCESS;
+		/* parse all the items */
+		for (kv = cache->layout_head; ret == CSR1212_SUCCESS && kv;
+		     kv = kv->next) {
+			ret = csr1212_parse_keyval(kv, cache);
+		}
+
+		/* attach top level items to the root directory */
+		for (dentry = fi->csr1212_dirs[dr]->value.directory.dentries_head;
+		     ret == CSR1212_SUCCESS && dentry; dentry = dentry->next) {
+			ret = csr1212_attach_keyval_to_directory(fi->host->csr.rom->root_kv,
+								 dentry->kv);
+		}
+
+		if (ret == CSR1212_SUCCESS) {
+			ret = hpsb_update_config_rom_image(fi->host);
+
+			if (ret >= 0 && copy_to_user(int2ptr(req->req.recvb), 
+						    &dr, sizeof(dr))) {
+				ret = -ENOMEM;
+			}
+		}
+	}
+	kfree(cache->filled_head);
+	kfree(cache);
+
+	if (ret >= 0) {
+		/* we have to free the request, because we queue no response,
+		 * and therefore nobody will free it */		
+		free_pending_request(req);
+		return sizeof(struct raw1394_request);
+	} else {
+		for (dentry = fi->csr1212_dirs[dr]->value.directory.dentries_head;
+		     dentry; dentry = dentry->next) {
+			csr1212_detach_keyval_from_directory(fi->host->csr.rom->root_kv,
+							     dentry->kv);
+		}
+		csr1212_release_keyval(fi->csr1212_dirs[dr]);
+		fi->csr1212_dirs[dr] = NULL;
+		return ret;
+	}
+}
+
 static int state_connected(struct file_info *fi, struct pending_request *req)
 {
         int node = req->req.address >> 48;
@@ -2049,6 +2165,9 @@
 
         case RAW1394_REQ_UPDATE_ROM:
                 return update_config_rom(fi, req);
+
+	case RAW1394_REQ_MODIFY_ROM:
+		return modify_config_rom(fi, req);
         }
 
         if (req->req.generation != get_hpsb_generation(fi->host)) {
@@ -2500,6 +2619,7 @@
         struct file_info *fi_hlp = NULL;
         struct arm_addr  *arm_addr = NULL;
         int another_host;
+	int csr_mod = 0;
 
 	if (fi->iso_state != RAW1394_ISO_INACTIVE)
 		raw1394_iso_shutdown(fi);
@@ -2586,6 +2706,22 @@
 
                 if (!done) down_interruptible(&fi->complete_sem);
         }
+
+	/* Remove any sub-trees left by user space programs */
+	for (i = 0; i < RAW1394_MAX_USER_CSR_DIRS; i++) {
+		struct csr1212_dentry *dentry;
+		if (!fi->csr1212_dirs[i]) continue;
+		for (dentry = fi->csr1212_dirs[i]->value.directory.dentries_head;
+		     dentry; dentry = dentry->next) {
+			csr1212_detach_keyval_from_directory(fi->host->csr.rom->root_kv, dentry->kv);
+		}
+		csr1212_release_keyval(fi->csr1212_dirs[i]);
+		fi->csr1212_dirs[i] = NULL;
+		csr_mod = 1;
+	}
+
+	if ((csr_mod || fi->cfgrom_upd) && hpsb_update_config_rom_image(fi->host) < 0)
+		HPSB_ERR("Failed to generate Configuration ROM image for host %d", fi->host->id);
 
         if (fi->state == connected) {
                 spin_lock_irq(&host_info_lock);
diff -Nru a/drivers/ieee1394/raw1394.h b/drivers/ieee1394/raw1394.h
--- a/drivers/ieee1394/raw1394.h	Wed Feb 11 22:28:46 2004
+++ b/drivers/ieee1394/raw1394.h	Wed Feb 11 22:28:46 2004
@@ -27,6 +27,7 @@
 #define RAW1394_REQ_GET_ROM         203
 #define RAW1394_REQ_UPDATE_ROM      204
 #define RAW1394_REQ_ECHO            205
+#define RAW1394_REQ_MODIFY_ROM      206
 
 #define RAW1394_REQ_ARM_REGISTER    300
 #define RAW1394_REQ_ARM_UNREGISTER  301
diff -Nru a/drivers/ieee1394/sbp2.c b/drivers/ieee1394/sbp2.c
--- a/drivers/ieee1394/sbp2.c	Wed Feb 11 22:28:46 2004
+++ b/drivers/ieee1394/sbp2.c	Wed Feb 11 22:28:46 2004
@@ -67,6 +67,7 @@
 #include "../scsi/scsi.h"
 #include "../scsi/hosts.h"
 
+#include "csr1212.h"
 #include "ieee1394.h"
 #include "ieee1394_types.h"
 #include "ieee1394_core.h"
@@ -77,7 +78,7 @@
 #include "sbp2.h"
 
 static char version[] __devinitdata =
-	"$Rev: 1096 $ Ben Collins <bcollins@debian.org>";
+	"$Rev: 1118 $ Ben Collins <bcollins@debian.org>";
 
 /*
  * Module load parameter definitions
@@ -1538,6 +1539,8 @@
 static void sbp2_parse_unit_directory(struct scsi_id_group *scsi_group,
 				      struct unit_directory *ud)
 {
+	struct csr1212_keyval *kv;
+	struct csr1212_dentry *dentry;
 	struct scsi_id_instance_data *scsi_id;
 	struct list_head *lh;
 	u64 management_agent_addr;
@@ -1554,29 +1557,46 @@
 	firmware_revision = 0x0;
 
 	/* Handle different fields in the unit directory, based on keys */
-	for (i = 0; i < ud->length; i++) {
-		switch (CONFIG_ROM_KEY(ud->quadlets[i])) {
-		case SBP2_CSR_OFFSET_KEY:
-			/* Save off the management agent address */
-			management_agent_addr =
-				CSR_REGISTER_BASE + 
-				(CONFIG_ROM_VALUE(ud->quadlets[i]) << 2);
-
-			SBP2_DEBUG("sbp2_management_agent_addr = %x",
-				   (unsigned int) management_agent_addr);
+	csr1212_for_each_dir_entry(ud->ne->csr, kv, ud->ud_kv, dentry) {
+		switch (kv->key.id) {
+		case CSR1212_KV_ID_DEPENDENT_INFO:
+			if (kv->key.type == CSR1212_KV_TYPE_CSR_OFFSET) {
+				/* Save off the management agent address */
+				management_agent_addr =
+					CSR1212_REGISTER_SPACE_BASE +
+					(kv->value.csr_offset << 2);
+
+				SBP2_DEBUG("sbp2_management_agent_addr = %x",
+					   (unsigned int) management_agent_addr);
+			} else {
+				/*
+				 * Device type and lun (used for
+				 * detemining type of sbp2 device)
+				 */
+				scsi_id = kmalloc(sizeof(*scsi_id), GFP_KERNEL);
+				if (!scsi_id) {
+					SBP2_ERR("Out of memory adding scsi_id, not all LUN's will be added");
+					break;
+				}
+				memset(scsi_id, 0, sizeof(*scsi_id));
+
+				scsi_id->sbp2_device_type_and_lun = kv->value.immediate;
+				SBP2_DEBUG("sbp2_device_type_and_lun = %x",
+					   (unsigned int) scsi_id->sbp2_device_type_and_lun);
+				list_add_tail(&scsi_id->list, &scsi_group->scsi_id_list);
+			}
 			break;
 
 		case SBP2_COMMAND_SET_SPEC_ID_KEY:
 			/* Command spec organization */
-			command_set_spec_id
-				= CONFIG_ROM_VALUE(ud->quadlets[i]);
+			command_set_spec_id = kv->value.immediate;
 			SBP2_DEBUG("sbp2_command_set_spec_id = %x",
 				   (unsigned int) command_set_spec_id);
 			break;
 
 		case SBP2_COMMAND_SET_KEY:
 			/* Command set used by sbp2 device */
-			command_set = CONFIG_ROM_VALUE(ud->quadlets[i]);
+			command_set = kv->value.immediate;
 			SBP2_DEBUG("sbp2_command_set = %x",
 				   (unsigned int) command_set);
 			break;
@@ -1586,35 +1606,14 @@
 			 * Unit characterisitcs (orb related stuff
 			 * that I'm not yet paying attention to)
 			 */
-			unit_characteristics
-				= CONFIG_ROM_VALUE(ud->quadlets[i]);
+			unit_characteristics = kv->value.immediate;
 			SBP2_DEBUG("sbp2_unit_characteristics = %x",
 				   (unsigned int) unit_characteristics);
 			break;
 
-		case SBP2_DEVICE_TYPE_AND_LUN_KEY:
-			/*
-			 * Device type and lun (used for
-			 * detemining type of sbp2 device)
-			 */
-			scsi_id = kmalloc(sizeof(*scsi_id), GFP_KERNEL);
-			if (!scsi_id) {
-				SBP2_ERR("Out of memory adding scsi_id, not all LUN's will be added");
-				break;
-			}
-			memset(scsi_id, 0, sizeof(*scsi_id));
-
-			scsi_id->sbp2_device_type_and_lun
-				= CONFIG_ROM_VALUE(ud->quadlets[i]);
-			SBP2_DEBUG("sbp2_device_type_and_lun = %x",
-				   (unsigned int) scsi_id->sbp2_device_type_and_lun);
-			list_add_tail(&scsi_id->list, &scsi_group->scsi_id_list);
-			break;
-
 		case SBP2_FIRMWARE_REVISION_KEY:
 			/* Firmware revision */
-			firmware_revision
-				= CONFIG_ROM_VALUE(ud->quadlets[i]);
+			firmware_revision = kv->value.immediate;
 			if (force_inquiry_hack)
 				SBP2_INFO("sbp2_firmware_revision = %x",
 				   (unsigned int) firmware_revision);
@@ -1727,7 +1726,7 @@
 	/* Payload size is the lesser of what our speed supports and what
 	 * our host supports.  */
 	scsi_id->max_payload_size = min(sbp2_speedto_max_payload[scsi_id->speed_code],
-					(u8)(((be32_to_cpu(hi->host->csr.rom[2]) >> 12) & 0xf) - 1));
+					(u8)(hi->host->csr.max_rec - 1));
 
 	SBP2_ERR("Node " NODE_BUS_FMT ": Max speed [%s] - Max payload [%u]",
 		 NODE_BUS_ARGS(hi->host, scsi_id->ne->nodeid),