summaryrefslogtreecommitdiff
path: root/nuttx/fs
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-06-10 18:16:01 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-06-10 18:16:01 +0000
commitbd4defc1489e67d10a8ebbadc0ef91d48ff584fa (patch)
tree78d0ed9c5aa18d8d9bdd1934003a3945b6da5f08 /nuttx/fs
parent16efc815bddec5f830a35316aeb4080f112dc554 (diff)
downloadpx4-nuttx-bd4defc1489e67d10a8ebbadc0ef91d48ff584fa.tar.gz
px4-nuttx-bd4defc1489e67d10a8ebbadc0ef91d48ff584fa.tar.bz2
px4-nuttx-bd4defc1489e67d10a8ebbadc0ef91d48ff584fa.zip
NFS update
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4824 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/fs')
-rw-r--r--nuttx/fs/nfs/nfs.h4
-rw-r--r--nuttx/fs/nfs/nfs_mount.h4
-rw-r--r--nuttx/fs/nfs/nfs_node.h21
-rw-r--r--nuttx/fs/nfs/nfs_proto.h38
-rw-r--r--nuttx/fs/nfs/nfs_util.c84
-rw-r--r--nuttx/fs/nfs/nfs_vfsops.c290
-rw-r--r--nuttx/fs/nfs/rpc.h2
-rw-r--r--nuttx/fs/nfs/rpc_clnt.c40
-rw-r--r--nuttx/fs/nfs/xdr_subs.h4
9 files changed, 251 insertions, 236 deletions
diff --git a/nuttx/fs/nfs/nfs.h b/nuttx/fs/nfs/nfs.h
index 63efbdaa4..fb36dafa5 100644
--- a/nuttx/fs/nfs/nfs.h
+++ b/nuttx/fs/nfs/nfs.h
@@ -225,9 +225,9 @@ struct nfsd_srvargs
uid_t nsd_uid; /* Effective uid mapped to cred */
uint32_t nsd_haddr; /* IP address of client */
int nsd_authlen; /* Length of auth string (ret) */
- unsigned char *nsd_authstr; /* Auth string (ret) */
+ uint8_t *nsd_authstr; /* Auth string (ret) */
int nsd_verflen; /* and the verifier */
- unsigned char *nsd_verfstr;
+ uint8_t *nsd_verfstr;
struct timeval nsd_timestamp; /* timestamp from verifier */
uint32_t nsd_ttl; /* credential ttl (sec) */
};
diff --git a/nuttx/fs/nfs/nfs_mount.h b/nuttx/fs/nfs/nfs_mount.h
index 3e58057c0..60ffdd3a4 100644
--- a/nuttx/fs/nfs/nfs_mount.h
+++ b/nuttx/fs/nfs/nfs_mount.h
@@ -77,7 +77,7 @@ struct nfsmount
uint32_t nm_numgrps; /* Max. size of groupslist */
nfsfh_t nm_fh; /* File handle of root dir */
char nm_path[90]; /* server's path of the directory being mount */
- uint32_t nm_fhsize; /* Size of root file handle */
+ uint32_t nm_fhsize; /* Size of root file handle (host order) */
struct nfs_fattr nm_fattr; /* nfs file attribute cache */
struct rpcclnt *nm_rpcclnt; /* rpc state */
struct socket *nm_so; /* Rpc socket */
@@ -101,7 +101,7 @@ struct nfsmount
uint32_t nm_acdirmax; /* Directory attr cache max lifetime */
uint32_t nm_acregmin; /* Reg file attr cache min lifetime */
uint32_t nm_acregmax; /* Reg file attr cache max lifetime */
- unsigned char nm_verf[NFSX_V3WRITEVERF]; /* V3 write verifier */
+ uint8_t nm_verf[NFSX_V3WRITEVERF]; /* V3 write verifier */
};
#endif
diff --git a/nuttx/fs/nfs/nfs_node.h b/nuttx/fs/nfs/nfs_node.h
index 09f9f2b08..ff0380c85 100644
--- a/nuttx/fs/nfs/nfs_node.h
+++ b/nuttx/fs/nfs/nfs_node.h
@@ -61,7 +61,6 @@
#define n_atim n_un1.nf_atim
#define n_mtim n_un2.nf_mtim
#define n_cookieverf n_un1.nd_cookieverf
-#define n_direofoffset n_un2.nd_direof
/* Flags for n_flag */
@@ -85,7 +84,6 @@
#define n_sillyrename n_un3.nf_silly
#define n_cookieverf n_un1.nd_cookieverf
#define n4_cookieverf n_un1.nd4_cookieverf
-#define n_direofoffset n_un2.nd_direof
#define n_cookies n_un3.nd_cook
/****************************************************************************
@@ -125,7 +123,6 @@ struct nfsnode
union
{
struct timespec nf_mtim;
- off_t nd_direof; /* Directory EOF offset cache */
} n_un2;
uint32_t n_fhsize; /* size in bytes, of fh */
short n_flag; /* Flag for locking.. */
@@ -143,22 +140,4 @@ struct nfsnode
//int n_commitflags;
};
-/* This structure is used internally for describing the result of
- * walking a path
- */
-
-struct nfs_dirinfo_s
-{
- /* These values describe the directory containing the terminal
- * path component (of the terminal component itself if it is
- * a directory.
- */
-
- struct nfsdir_s n_dir; /* Describes directory. */
-
- /* Values from the NFS file entry */
-
- struct nfsnode attribute;
-};
-
#endif /* __FS_NFS_NFS_NODE_H */
diff --git a/nuttx/fs/nfs/nfs_proto.h b/nuttx/fs/nfs/nfs_proto.h
index 1aeba0a6a..b9d4655c3 100644
--- a/nuttx/fs/nfs/nfs_proto.h
+++ b/nuttx/fs/nfs/nfs_proto.h
@@ -348,14 +348,17 @@ struct fhandle
typedef struct fhandle fhandle_t;
-/* File Handle (32 bytes for version 2), variable up to 64 for version 3. */
+/* File Handle (32 bytes for version 2), variable up to 64 for version 3.
+ * This structures a variable sized and are provided only for setting aside
+ * maximum memory allocatins for a file handle.
+ */
-union nfsfh
+struct nfsfh
{
-//fhandle_t fh_generic;
- uint8_t fh_bytes[NFSX_V2FH];
+ uint8_t fh_bytes[NFSX_V2FH];
};
-typedef union nfsfh nfsfh_t;
+typedef struct nfsfh nfsfh_t;
+#define SIZEOF_nfsfh_t(n) (n)
struct nfsv2_time
{
@@ -562,6 +565,7 @@ struct file_handle
uint32_t length;
nfsfh_t handle;
};
+#define SIZEOF_file_handle(n) (sizeof(uint32_t) + SIZEOF_nfsfh_t(n))
struct diropargs3
{
@@ -584,16 +588,26 @@ struct CREATE3resok
struct wcc_data dir_wcc;
};
+/* The actual size of the lookup argument is variable. These structures are, therefore,
+ * only useful in setting aside maximum memory usage for the LOOKUP arguments.
+ */
+
+struct LOOKUP3filename
+{
+ uint32_t namelen; /* Size name */
+ uint32_t name[(NAME_MAX+3) >> 2]; /* Variable length */
+};
+
struct LOOKUP3args
{
- struct file_handle dirhandle;
- uint32_t namelen;
- uint32_t name[(NAME_MAX+3) >> 2]; /* Actual size determined by namelen */
+ struct file_handle dirhandle; /* Variable length */
+ struct LOOKUP3filename name; /* Variable length */
};
/* Actual size of LOOKUP3args */
-#define SIZEOF_LOOKUP3args(n) (sizeof(struct file_handle) + sizeof(namelen) + (((n)+3) & ~3))
+#define SIZEOF_LOOKUP3filename(b) (sizeof(uint32_t) + (((b)+3) & ~3))
+#define SIZEOF_LOOKUP3args(a,b) (SIZEOF_file_handle(a) + SIZEOF_LOOKUP3filename(b))
struct LOOKUP3resok
{
@@ -683,9 +697,13 @@ struct RMDIR3resok
struct wcc_data dir_wcc;
};
+/* The actual size of the lookup argument is variable. This structures is, therefore,
+ * only useful in setting aside maximum memory usage for the LOOKUP arguments.
+ */
+
struct READDIR3args
{
- struct file_handle dir;
+ struct file_handle dir; /* Variable length */
nfsuint64 cookie;
uint8_t cookieverf[NFSX_V3COOKIEVERF];
uint32_t count;
diff --git a/nuttx/fs/nfs/nfs_util.c b/nuttx/fs/nfs/nfs_util.c
index e9d7ac863..5d8ac7bb6 100644
--- a/nuttx/fs/nfs/nfs_util.c
+++ b/nuttx/fs/nfs/nfs_util.c
@@ -312,19 +312,18 @@ int nfs_lookup(struct nfsmount *nmp, FAR const char *filename,
{
struct LOOKUP3args request;
struct rpc_reply_lookup response;
- uint32_t *ptr;
+ FAR uint32_t *ptr;
uint32_t value;
+ int reqlen;
int namelen;
int error = 0;
- DEBUGASSERT(nmp && filename && fhandle && obj_attributes && dir_attributes);
+ DEBUGASSERT(nmp && filename && fhandle);
/* Set all of the buffers to a known state */
memset(&request, 0, sizeof(struct LOOKUP3args));
memset(&response, 0, sizeof(struct rpc_reply_lookup));
- memset(obj_attributes, 0, sizeof(struct nfs_fattr));
- memset(dir_attributes, 0, sizeof(struct nfs_fattr));
/* Get the length of the string to be sent */
@@ -337,20 +336,35 @@ int nfs_lookup(struct nfsmount *nmp, FAR const char *filename,
/* Initialize the request */
- nfsstats.rpccnt[NFSPROC_LOOKUP]++;
+ ptr = (FAR uint32_t*)&request;
+ reqlen = 0;
+
+ /* Copy the variable length, directory file handle */
+
+ *ptr++ = txdr_unsigned(fhandle->length);
+ reqlen += sizeof(uint32_t);
+
+ memcpy(ptr, &fhandle->handle, fhandle->length);
+ reqlen += fhandle->length;
+ ptr += uint32_increment(fhandle->length);
- memcpy(&request.dirhandle, fhandle, sizeof(struct file_handle));
- request.namelen = txdr_unsigned(namelen);
- memcpy(request.name, filename, namelen);
+ /* Copy the variable-length file name */
+
+ *ptr++ = txdr_unsigned(namelen);
+ reqlen += sizeof(uint32_t);
+
+ memcpy(ptr, filename, namelen);
+ reqlen += uint32_alignup(namelen);
/* Request LOOKUP from the server */
+ nfsstats.rpccnt[NFSPROC_LOOKUP]++;
error = nfs_request(nmp, NFSPROC_LOOKUP,
- (FAR const void *)&request, SIZEOF_LOOKUP3args(namelen),
+ (FAR const void *)&request, reqlen,
(FAR void *)&response, sizeof(struct rpc_reply_lookup));
if (error)
{
- fdbg("nfs_request failed: %d\n", error);
+ fdbg("ERROR: nfs_request failed: %d\n", error);
return error;
}
@@ -359,27 +373,44 @@ int nfs_lookup(struct nfsmount *nmp, FAR const char *filename,
* may differ in size whereas struct rpc_reply_lookup uses a fixed size.
*/
- ptr = (uint32_t*)&response.lookup;
+ ptr = (FAR uint32_t*)&response.lookup;
- /* Get the length of the file handle and return the file handle */
+ /* Get the length of the file handle */
- value = txdr_unsigned(*ptr) + sizeof(uint32_t);
- memcpy(fhandle, ptr, value);
+ value = *ptr++;
+ value = fxdr_unsigned(uint32_t, value);
+ if (value > NFSX_V2FH)
+ {
+ fdbg("ERROR: Bad file handle length: %d\n", value);
+ return EIO;
+ }
+
+ /* Return the file handle */
+
+ fhandle->length = value;
+ memcpy(&fhandle->handle, ptr, value);
ptr += uint32_increment(value);
- /* Check if there are object attributes and, if so, copy them to the user buffer */
+ /* Check if there are object attributes and, if so, copy them to the user
+ * buffer
+ */
value = *ptr++;
if (value)
{
- memcpy(obj_attributes, ptr, sizeof(struct nfs_fattr));
+ if (obj_attributes)
+ {
+ memcpy(obj_attributes, ptr, sizeof(struct nfs_fattr));
+ }
ptr += uint32_increment(sizeof(struct nfs_fattr));
}
- /* Check if there are directory attributes and, if so, copy them to the user buffer */
+ /* Check if there are directory attributes and, if so, copy them to the
+ * user buffer
+ */
value = *ptr++;
- if (value)
+ if (value && dir_attributes)
{
memcpy(dir_attributes, ptr, sizeof(struct nfs_fattr));
}
@@ -408,12 +439,10 @@ int nfs_findnode(struct nfsmount *nmp, FAR const char *relpath,
char terminator;
int error;
- /* Start with the file handle and attributes of the root directory */
+ /* Start with the file handle of the root directory. */
fhandle->length = nmp->nm_fhsize;
memcpy(&fhandle->handle, &nmp->nm_fh, sizeof(nfsfh_t));
- memset(obj_attributes, 0, sizeof(struct nfs_fattr));
- memset(dir_attributes, 0, sizeof(struct nfs_fattr));
/* If no path was provided, then the root directory must be exactly what
* the caller is looking for.
@@ -421,7 +450,18 @@ int nfs_findnode(struct nfsmount *nmp, FAR const char *relpath,
if (*path == '\0' || strlen(path) == 0)
{
-#warning "Where do we get the attributes of the root file system?"
+ /* Return the root directory attributes */
+
+ if (obj_attributes)
+ {
+ memcpy(obj_attributes, &nmp->nm_fattr, sizeof(struct nfs_fattr));
+ }
+
+ if (dir_attributes)
+ {
+ memcpy(dir_attributes, &nmp->nm_fattr, sizeof(struct nfs_fattr));
+ }
+
return OK;
}
diff --git a/nuttx/fs/nfs/nfs_vfsops.c b/nuttx/fs/nfs/nfs_vfsops.c
index ad4100539..40f482abe 100644
--- a/nuttx/fs/nfs/nfs_vfsops.c
+++ b/nuttx/fs/nfs/nfs_vfsops.c
@@ -85,6 +85,18 @@
#define NFS_DIRHDSIZ (sizeof (struct nfs_dirent) - (MAXNAMLEN + 1))
#define NFS_DIRENT_OVERHEAD offsetof(struct nfs_dirent, dirent)
+/* include/nuttx/fs/dirent.h has its own version of these lengths. They must
+ * match the NFS versions.
+ */
+
+#if NFSX_V2FH != DIRENT_NFS_MAXHANDLE
+# error "Length of file handle in fs_dirent_s is incorrect"
+#endif
+
+#if NFSX_V3COOKIEVERF != DIRENT_NFS_VERFLEN
+# error "Length of cookie verify in fs_dirent_s is incorrect"
+#endif
+
/****************************************************************************
* Private Type Definitions
****************************************************************************/
@@ -714,105 +726,126 @@ errout_with_semaphore:
****************************************************************************/
static int nfs_opendir(struct inode *mountpt, const char *relpath,
- struct fs_dirent_s *dir)
+ struct fs_dirent_s *dir)
{
struct nfsmount *nmp;
- struct nfsnode *np;
-//struct nfs_dirinfo_s dirinfo;
- int ret;
+ struct file_handle fhandle;
+ struct nfs_fattr obj_attributes;
+ uint32_t objtype;
+ int error;
fvdbg("relpath: \"%s\"\n", relpath ? relpath : "NULL");
/* Sanity checks */
- DEBUGASSERT(mountpt != NULL && mountpt->i_private != NULL);
+ DEBUGASSERT(mountpt != NULL && mountpt->i_private != NULL && dir);
/* Recover our private data from the inode instance */
nmp = mountpt->i_private;
- np = nmp->nm_head;
+
+ /* Initialize the NFS-specific portions of dirent structure to zero */
+
+ memset(&dir->u.nfs, 0, sizeof(struct nfsdir_s));
/* Make sure that the mount is still healthy */
nfs_semtake(nmp);
- ret = nfs_checkmount(nmp);
- if (ret != OK)
+ error = nfs_checkmount(nmp);
+ if (error != OK)
{
- fdbg("nfs_checkmount failed: %d\n", ret);
+ fdbg("ERROR: nfs_checkmount failed: %d\n", error);
goto errout_with_semaphore;
}
- /* The entry is a directory */
+ /* Find the NFS node associate with the path */
- if (np->nfsv3_type != NFDIR)
+ error = nfs_findnode(nmp, relpath, &fhandle, &obj_attributes, NULL);
+ if (error != 0)
{
- fdbg("open eacces type=%d\n", np->nfsv3_type);
- ret = EACCES;
+ fdbg("ERROR: nfs_findnode failed: %d\n", error);
goto errout_with_semaphore;
}
- /* The requested directory must be the volume-relative "root" directory */
+ /* The entry is a directory */
- if (relpath && relpath[0] != '\0')
+ objtype = fxdr_unsigned(uint32_t, obj_attributes.fa_type);
+ if (objtype != NFDIR)
{
- ret = ENOENT;
+ fdbg("ERROR: Not a directory, type=%d\n", objtype);
+ error = ENOTDIR;
goto errout_with_semaphore;
}
- if (np->n_flag & NMODIFIED)
- {
- if (np->nfsv3_type == NFDIR)
- {
- np->n_direofoffset = 0;
- dir->u.nfs.nd_direoffset = 0;
- dir->u.nfs.cookie[0] = 0;
- dir->u.nfs.cookie[1] = 0;
- }
- }
+ /* Save the directory information in struct fs_dirent_s so that it can be
+ * used later when readdir() is called.
+ */
- ret = OK;
+ dir->u.nfs.nfs_fhsize = (uint8_t)fhandle.length;
+ DEBUGASSERT(fhandle.length <= DIRENT_NFS_MAXHANDLE);
+
+ memcpy(dir->u.nfs.nfs_fhandle, &fhandle.handle, DIRENT_NFS_MAXHANDLE);
+ error = OK;
errout_with_semaphore:
nfs_semgive(nmp);
- return -ret;
+ return -error;
}
/****************************************************************************
- * Name: nfs_readdirrpc
+ * Name: nfs_readdir
*
- * Description:
- * Perform the READIR RPC call.
+ * Description: Read from directory
*
* Returned Value:
- * 0 on success; a positive errno value on failure.
+ * 0 on success; a negated errno value on failure.
*
****************************************************************************/
-int nfs_readdirrpc(struct nfsmount *nmp, struct nfsnode *np,
- struct fs_dirent_s *dir)
+static int nfs_readdir(struct inode *mountpt, struct fs_dirent_s *dir)
{
-/* This buffer needs to go into struct fs_dirent_s nuttx/dirent.h */
- uint32_t buffer[64];
+ struct nfsmount *nmp;
+ uint32_t buffer[64]; /* Needs to go into struct fs_dirent_s nuttx/dirent.h */
struct READDIR3args rddir;
struct rpc_reply_readdir *resok;
struct file_handle fhandle;
struct nfs_fattr obj_attributes;
- struct nfs_fattr dir_attributes;
uint32_t tmp;
- uint32_t *ptr; /* This goes in fs_dirent_s */
+ uint32_t *ptr;
uint8_t *name;
unsigned int length;
bool more;
bool eod;
+ int reqlen;
int error = 0;
-/* Check in 'dir' if we are have directories entries?
- * 1) have data, and
- * 2) Index of the last returned entry has nextentry != 0
- *
- * If we have returned entries then read more entries if:
- * 3) EOF = 0
- */
+ fvdbg("Entry\n");
+
+ /* Sanity checks */
+
+ DEBUGASSERT(mountpt != NULL && mountpt->i_private != NULL);
+
+ /* Recover our private data from the inode instance */
+
+ nmp = mountpt->i_private;
+
+ /* Make sure that the mount is still healthy */
+
+ nfs_semtake(nmp);
+ error = nfs_checkmount(nmp);
+ if (error != 0)
+ {
+ fdbg("ERROR: nfs_checkmount failed: %d\n", error);
+ goto errout_with_semaphore;
+ }
+
+ /* Check in 'dir' if we are have directories entries?
+ * 1) have data, and
+ * 2) Index of the last returned entry has nextentry != 0
+ *
+ * If we have returned entries then read more entries if:
+ * 3) EOF = 0
+ */
more = false; /* Set 'more' to true if we have buffered entries to be processed */
eod = false; /* Set 'eod' if we are at the end of the directory */
@@ -823,33 +856,52 @@ int nfs_readdirrpc(struct nfsmount *nmp, struct nfsnode *np,
while (!more && !eod)
{
- /* Request a block directory entries */
+ /* Request a block directory entries, copying directory information from
+ * the dirent structure.
+ */
- nfsstats.rpccnt[NFSPROC_READDIR]++;
memset(&rddir, 0, sizeof(struct READDIR3args));
- rddir.dir.length = txdr_unsigned(np->n_fhsize);
- memcpy(&rddir.dir.handle, &np->n_fhp, sizeof(nfsfh_t));
- rddir.count = txdr_unsigned(nmp->nm_readdirsize);
- if (nfsstats.rpccnt[NFSPROC_READDIR] == 1)
- {
- rddir.cookie.nfsuquad[0] = 0;
- rddir.cookie.nfsuquad[1] = 0;
- memset(&rddir.cookieverf, 0, NFSX_V3COOKIEVERF);
- }
- else
- {
- rddir.cookie.nfsuquad[0] = dir->u.nfs.cookie[0];
- rddir.cookie.nfsuquad[1] = dir->u.nfs.cookie[1];
- memcpy(&rddir.cookieverf, &np->n_cookieverf, NFSX_V3COOKIEVERF);
- }
+ /* Initialize the request */
+
+ ptr = (FAR uint32_t*)&rddir;
+ reqlen = 0;
+
+ /* Copy the variable length, directory file handle */
+
+ *ptr++ = txdr_unsigned((uint32_t)dir->u.nfs.nfs_fhsize);
+ reqlen += sizeof(uint32_t);
+
+ memcpy(ptr, dir->u.nfs.nfs_fhandle, dir->u.nfs.nfs_fhsize);
+ reqlen += (int)dir->u.nfs.nfs_fhsize;
+ ptr += uint32_increment((int)dir->u.nfs.nfs_fhsize);
+
+ /* Cookie and cookie verifier */
+
+ ptr[0] = dir->u.nfs.nfs_cookie[0];
+ ptr[1] = dir->u.nfs.nfs_cookie[1];
+ ptr += 2;
+ reqlen += 2*sizeof(uint32_t);
+ memcpy(ptr, dir->u.nfs.nfs_verifier, DIRENT_NFS_VERFLEN);
+ ptr += uint32_increment(DIRENT_NFS_VERFLEN);
+ reqlen += DIRENT_NFS_VERFLEN;
+
+ /* Number of directory entries (We currently only process one entry at a time) */
+
+ *ptr = txdr_unsigned(nmp->nm_readdirsize);
+ reqlen += sizeof(uint32_t);
+
+ /* And read the directory */
+
+ nfsstats.rpccnt[NFSPROC_READDIR]++;
error = nfs_request(nmp, NFSPROC_READDIR,
- (FAR const void *)&rddir, sizeof(struct READDIR3args),
+ (FAR const void *)&rddir, reqlen,
(FAR void *)buffer, sizeof(buffer));
- if (error)
+ if (error != 0)
{
- goto nfsmout;
+ fdbg("ERROR: nfs_request failed: %d\n", error);
+ goto errout_with_semaphore;
}
/* A new group of entries was successfully read. Process the
@@ -872,18 +924,15 @@ int nfs_readdirrpc(struct nfsmount *nmp, struct nfsnode *np,
if (resok->readdir.attributes_follow == 1)
{
- /* Get attibutes */
-
- memcpy(&np->n_fattr, &resok->readdir.dir_attributes,
- sizeof(struct nfs_fattr));
+ /* Attributes are not currently used */
}
#warning "Won't the structure format be wrong if there are no attributes -- this will need to be parsed too"
/* Save the verification cookie */
- memcpy(&np->n_cookieverf, &resok->readdir.cookieverf, NFSX_V3WRITEVERF);
+ memcpy(dir->u.nfs.nfs_verifier, &resok->readdir.cookieverf, DIRENT_NFS_VERFLEN);
- /* Get a point to the entries (if any) */
+ /* Get a pointer to the diretory entries (if any) */
ptr = (uint32_t*)&resok->readdir.reply;
@@ -940,8 +989,8 @@ int nfs_readdirrpc(struct nfsmount *nmp, struct nfsnode *np,
/* Save the cookie and increment the pointer to the next entry */
- dir->u.nfs.cookie[0] = *ptr++;
- dir->u.nfs.cookie[1] = *ptr++;
+ dir->u.nfs.nfs_cookie[0] = *ptr++;
+ dir->u.nfs.nfs_cookie[1] = *ptr++;
ptr++; /* Just skip over the nextentry for now */
@@ -959,20 +1008,20 @@ int nfs_readdirrpc(struct nfsmount *nmp, struct nfsnode *np,
* the file type.
*/
- fhandle.length = txdr_unsigned(np->n_fhsize);
- memcpy(&fhandle.handle, &np->n_fhp, sizeof(nfsfh_t));
+ fhandle.length = (uint32_t)dir->u.nfs.nfs_fhsize;
+ memcpy(&fhandle.handle, dir->u.nfs.nfs_fhandle, DIRENT_NFS_MAXHANDLE);
- error = nfs_lookup(nmp, dir->fd_dir.d_name, &fhandle,
- &obj_attributes, &dir_attributes);
+ error = nfs_lookup(nmp, dir->fd_dir.d_name, &fhandle, &obj_attributes, NULL);
if (error != 0)
{
fdbg("nfs_lookup failed: %d\n", error);
- return error;
+ goto errout_with_semaphore;
}
/* Set the dirent file type */
- switch (fxdr_unsigned(uint32_t, obj_attributes.fa_type))
+ tmp = fxdr_unsigned(uint32_t, obj_attributes.fa_type);
+ switch (tmp)
{
default:
case NFNON: /* Unknown type */
@@ -997,8 +1046,7 @@ int nfs_readdirrpc(struct nfsmount *nmp, struct nfsnode *np,
dir->fd_dir.d_type = DTYPE_CHR;
break;
}
-
- error = 0;
+ fvdbg("type: %d->%d\n", (int)tmp, dir->fd_dir.d_type);
}
/* We are at the end of the directory. If 'eod' is true then we all of the
@@ -1014,85 +1062,9 @@ int nfs_readdirrpc(struct nfsmount *nmp, struct nfsnode *np,
fvdbg("End of directory\n");
error = ENOENT;
- }
-
-nfsmout:
- return error;
-}
-
-/****************************************************************************
- * Name: nfs_readdir
- *
- * Description: Read from directory
- *
- * Returned Value:
- * 0 on success; a negated errno value on failure.
- *
- ****************************************************************************/
-
-static int nfs_readdir(struct inode *mountpt, struct fs_dirent_s *dir)
-{
- int error = 0;
- struct nfsmount *nmp;
- struct nfsnode *np;
-//struct nfs_dirent *ndp;
-
- fvdbg("Entry\n");
-
- /* Sanity checks */
-
- DEBUGASSERT(mountpt != NULL && mountpt->i_private != NULL);
-
- /* Recover our private data from the inode instance */
-
- nmp = mountpt->i_private;
- np = nmp->nm_head;
- dir->fd_root = mountpt;
-
- /* Make sure that the mount is still healthy */
-
- nfs_semtake(nmp);
- error = nfs_checkmount(nmp);
- if (error != 0)
- {
- fdbg("ERROR: nfs_checkmount failed: %d\n", error);
- goto errout_with_semaphore;
- }
-
- dir->fd_dir.d_name[0] = '\0';
-
- if (np->nfsv3_type != NFDIR)
- {
- error = EPERM;
- goto errout_with_semaphore;
- }
-
- dir->u.nfs.nd_direoffset = np->n_direofoffset;
- dir->fd_dir.d_type = np->nfsv3_type;
-
- /* First, check for hit on the EOF offset */
-
- if (dir->u.nfs.nd_direoffset != 0)
- {
- nfsstats.direofcache_hits++;
- //np->n_open = true;
- goto success_with_semaphore;
- }
-
- if ((nmp->nm_flag & (NFSMNT_NFSV3 | NFSMNT_GOTFSINFO)) == NFSMNT_NFSV3)
- {
- (void)nfs_fsinfo(nmp);
- }
-
- /* Read and return one directory entry. */
-
- error = nfs_readdirrpc(nmp, np, dir);
- if (error != 0)
- {
goto errout_with_semaphore;
}
-success_with_semaphore:
error = 0;
errout_with_semaphore:
@@ -2007,7 +1979,6 @@ static int nfs_getstat(struct nfsmount *nmp, const char *relpath,
{
struct file_handle fhandle;
struct nfs_fattr obj_attributes;
- struct nfs_fattr dir_attributes;
uint32_t tmp;
uint32_t mode;
int error = 0;
@@ -2016,8 +1987,7 @@ static int nfs_getstat(struct nfsmount *nmp, const char *relpath,
/* Get the attributes of the requested node */
- error = nfs_findnode(nmp, relpath, &fhandle, &obj_attributes,
- &dir_attributes);
+ error = nfs_findnode(nmp, relpath, &fhandle, &obj_attributes, NULL);
if (error != 0)
{
fdbg("ERROR: nfs_findnode failed: %d\n", error);
diff --git a/nuttx/fs/nfs/rpc.h b/nuttx/fs/nfs/rpc.h
index b03d73546..921dc2ce7 100644
--- a/nuttx/fs/nfs/rpc.h
+++ b/nuttx/fs/nfs/rpc.h
@@ -287,7 +287,7 @@ struct rpc_auth_info
struct auth_unix
{
int32_t stamp;
- unsigned char hostname; /* null */
+ uint8_t hostname; /* null */
int32_t uid;
int32_t gid;
int32_t gidlist; /* null */
diff --git a/nuttx/fs/nfs/rpc_clnt.c b/nuttx/fs/nfs/rpc_clnt.c
index cdf16f56c..8fc3fb5d7 100644
--- a/nuttx/fs/nfs/rpc_clnt.c
+++ b/nuttx/fs/nfs/rpc_clnt.c
@@ -601,7 +601,6 @@ static int rpcclnt_receive(struct rpctask *rep, struct sockaddr *aname,
}
}
- fvdbg("Returning %d\n", error);
return error;
}
@@ -1116,18 +1115,18 @@ static int rpcclnt_buildheader(struct rpcclnt *rpc, int procid, int prog, int ve
case NFSPROC_LOOKUP:
{
- struct rpc_call_lookup *callmsg = (struct rpc_call_lookup *)msgbuf;
- uint32_t namelen;
-
- /* Copy the variable, caller-provided data into the call message structure */
+ /* Copy the variable length, caller-provided data into the call
+ * message structure.
+ */
+ struct rpc_call_lookup *callmsg = (struct rpc_call_lookup *)msgbuf;
memcpy(&callmsg->lookup, request, *reqlen);
- /* Return the full size of the message (including messages headers) */
+ /* Return the full size of the message (the size of variable data
+ * plus the size of the messages header).
+ */
- namelen = fxdr_unsigned(uint32_t, ((FAR struct LOOKUP3args*)request)->namelen);
- DEBUGASSERT(*reqlen <= SIZEOF_LOOKUP3args(namelen));
- *reqlen = SIZEOF_rpc_call_lookup(namelen);
+ *reqlen += sizeof(struct rpc_call_header);
/* Format the message header */
@@ -1176,15 +1175,18 @@ static int rpcclnt_buildheader(struct rpcclnt *rpc, int procid, int prog, int ve
case NFSPROC_READDIR:
{
- /* Copy the variable, caller-provided data into the call message structure */
+ /* Copy the variable length, caller-provided data into the call
+ * message structure.
+ */
struct rpc_call_readdir *callmsg = (struct rpc_call_readdir *)msgbuf;
memcpy(&callmsg->readdir, request, *reqlen);
- /* Return the full size of the message (including messages headers) */
+ /* Return the full size of the message (the size of variable data
+ * plus the size of the messages header).
+ */
- DEBUGASSERT(*reqlen == sizeof(struct READDIR3args));
- *reqlen = sizeof(struct rpc_call_readdir);
+ *reqlen += sizeof(struct rpc_call_header);
/* Format the message header */
@@ -1561,7 +1563,7 @@ int rpcclnt_connect(struct rpcclnt *rpc)
error = fxdr_unsigned(uint32_t, mdata.mount.status);
if (error != 0)
{
- fdbg("ERROR: fxdr_unsigned failed: %d\n", error);
+ fdbg("ERROR: Bad mount status: %d\n", error);
goto bad;
}
@@ -1607,8 +1609,7 @@ int rpcclnt_connect(struct rpcclnt *rpc)
}
}
- fvdbg("Succeeded\n");
- return 0;
+ return OK;
bad:
rpcclnt_disconnect(rpc);
@@ -1746,7 +1747,7 @@ int rpcclnt_umount(struct rpcclnt *rpc)
goto bad;
}
- return 0;
+ return OK;
bad:
rpcclnt_disconnect(rpc);
@@ -1904,7 +1905,10 @@ int rpcclnt_request(FAR struct rpcclnt *rpc, int procnum, int prog,
if (error == 0 || error == EPIPE)
{
error = rpcclnt_reply(task, procnum, prog, response, resplen);
- fvdbg("rpcclnt_reply returned: %d\n", error);
+ if (error != 0)
+ {
+ fvdbg("rpcclnt_reply returned: %d\n", error);
+ }
}
/* RPC done, unlink the request. */
diff --git a/nuttx/fs/nfs/xdr_subs.h b/nuttx/fs/nfs/xdr_subs.h
index a95249118..028132e0a 100644
--- a/nuttx/fs/nfs/xdr_subs.h
+++ b/nuttx/fs/nfs/xdr_subs.h
@@ -118,6 +118,10 @@
((uint32_t *)(t))[1] = htonl((uint32_t)((f) & 0xffffffff)); \
}
+/* Macros for dealing with byte data saved in uint32_t aligned memory */
+
+#define uint32_aligndown(b) ((b) & ~3)
+#define uint32_alignup(b) (((b) + 3) & ~3)
#define uint32_increment(b) (((b) + 3) >> 2)
#endif /* __FS_NFS_XDR_SUBS_H */