From a6eddbb85537ebee6860b0c38ab48be615b297f6 Mon Sep 17 00:00:00 2001 From: patacongo Date: Mon, 28 May 2012 23:40:20 +0000 Subject: NFS update git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4781 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/fs/nfs/nfs_mount.h | 3 +- nuttx/fs/nfs/nfs_node.h | 10 +-- nuttx/fs/nfs/nfs_proto.h | 143 +++++++++++++++++++++------------- nuttx/fs/nfs/nfs_socket.c | 5 +- nuttx/fs/nfs/nfs_vfsops.c | 159 ++++++++++++++++++++++++------------- nuttx/fs/nfs/rpc.h | 168 ++++++++++++++++++++++++++++++++++------ nuttx/fs/nfs/rpc_clnt.c | 16 +--- nuttx/fs/nfs/rpc_clnt_private.h | 148 ----------------------------------- nuttx/fs/nfs/rpc_v2.h | 117 ---------------------------- nuttx/include/nuttx/fs/nfs.h | 57 +------------- 10 files changed, 358 insertions(+), 468 deletions(-) delete mode 100644 nuttx/fs/nfs/rpc_clnt_private.h delete mode 100644 nuttx/fs/nfs/rpc_v2.h diff --git a/nuttx/fs/nfs/nfs_mount.h b/nuttx/fs/nfs/nfs_mount.h index 82bb26fe5..d7012991d 100644 --- a/nuttx/fs/nfs/nfs_mount.h +++ b/nuttx/fs/nfs/nfs_mount.h @@ -47,7 +47,8 @@ * Included Files ****************************************************************************/ - #include +#include "nfs_proto.h" +#include /**************************************************************************** * Pre-processor Definitions diff --git a/nuttx/fs/nfs/nfs_node.h b/nuttx/fs/nfs/nfs_node.h index e32c49d78..c2d2ca5e0 100644 --- a/nuttx/fs/nfs/nfs_node.h +++ b/nuttx/fs/nfs/nfs_node.h @@ -47,9 +47,7 @@ * Included Files ****************************************************************************/ -#include - -#include "nfs.h" +#include "nfs_proto.h" /**************************************************************************** * Pre-processor Definitions @@ -57,8 +55,8 @@ /* Values for n_commitflags */ -#define NFS_COMMIT_PUSH_VALID 0x0001/* push range valid */ -#define NFS_COMMIT_PUSHED_VALID 0x0002/* pushed range valid */ +#define NFS_COMMIT_PUSH_VALID 0x0001 /* Push range valid */ +#define NFS_COMMIT_PUSHED_VALID 0x0002 /* Pushed range valid */ #define n_atim n_un1.nf_atim #define n_mtim n_un2.nf_mtim @@ -142,7 +140,7 @@ struct nfsnode struct timespec nf_mtim; off_t nd_direof; /* Directory EOF offset cache */ } n_un2; -//short n_fhsize; /* size in bytes, of fh */ + int n_fhsize; /* size in bytes, of fh */ short n_flag; /* Flag for locking.. */ //nfsfh_t n_fh; /* Small File Handle */ time_t n_accstamp; /* Access cache timestamp */ diff --git a/nuttx/fs/nfs/nfs_proto.h b/nuttx/fs/nfs/nfs_proto.h index 36407ba03..dbbf5caee 100644 --- a/nuttx/fs/nfs/nfs_proto.h +++ b/nuttx/fs/nfs/nfs_proto.h @@ -47,10 +47,6 @@ * Included Files ****************************************************************************/ -#include - -#include "nfs.h" - /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ @@ -214,29 +210,66 @@ /* Constants used by the Version 3 protocol for various RPCs */ -#define NFSV3SATTRTIME_DONTCHANGE 0 -#define NFSV3SATTRTIME_TOSERVER 1 -#define NFSV3SATTRTIME_TOCLIENT 2 - -#define NFSV3ACCESS_READ 0x01 -#define NFSV3ACCESS_LOOKUP 0x02 -#define NFSV3ACCESS_MODIFY 0x04 -#define NFSV3ACCESS_EXTEND 0x08 -#define NFSV3ACCESS_DELETE 0x10 -#define NFSV3ACCESS_EXECUTE 0x20 - -#define NFSV3WRITE_UNSTABLE 0 -#define NFSV3WRITE_DATASYNC 1 -#define NFSV3WRITE_FILESYNC 2 - -#define NFSV3CREATE_UNCHECKED 0 -#define NFSV3CREATE_GUARDED 1 -#define NFSV3CREATE_EXCLUSIVE 2 - -#define NFSV3FSINFO_LINK 0x01 -#define NFSV3FSINFO_SYMLINK 0x02 -#define NFSV3FSINFO_HOMOGENEOUS 0x08 -#define NFSV3FSINFO_CANSETTIME 0x10 +#define NFSV3SATTRTIME_DONTCHANGE 0 +#define NFSV3SATTRTIME_TOSERVER 1 +#define NFSV3SATTRTIME_TOCLIENT 2 + +#define NFSV3ACCESS_READ 0x01 +#define NFSV3ACCESS_LOOKUP 0x02 +#define NFSV3ACCESS_MODIFY 0x04 +#define NFSV3ACCESS_EXTEND 0x08 +#define NFSV3ACCESS_DELETE 0x10 +#define NFSV3ACCESS_EXECUTE 0x20 + +#define NFSV3WRITE_UNSTABLE 0 +#define NFSV3WRITE_DATASYNC 1 +#define NFSV3WRITE_FILESYNC 2 + +#define NFSV3CREATE_UNCHECKED 0 +#define NFSV3CREATE_GUARDED 1 +#define NFSV3CREATE_EXCLUSIVE 2 + +#define NFSV3FSINFO_LINK 0x01 +#define NFSV3FSINFO_SYMLINK 0x02 +#define NFSV3FSINFO_HOMOGENEOUS 0x08 +#define NFSV3FSINFO_CANSETTIME 0x10 + +/* NFS mount option flags */ + +#define NFSMNT_SOFT 0x00000001 /* soft mount (hard is default) */ +#define NFSMNT_WSIZE 0x00000002 /* set write size */ +#define NFSMNT_RSIZE 0x00000004 /* set read size */ +#define NFSMNT_TIMEO 0x00000008 /* set initial timeout */ +#define NFSMNT_RETRANS 0x00000010 /* set number of request retries */ +#define NFSMNT_MAXGRPS 0x00000020 /* set maximum grouplist size */ +#define NFSMNT_INT 0x00000040 /* allow interrupts on hard mount */ +#define NFSMNT_NOCONN 0x00000080 /* Don't Connect the socket */ + +/* 0x100 free, was NFSMNT_NQNFS */ + +#define NFSMNT_NFSV3 0x00000200 /* Use NFS Version 3 protocol */ + +/* 0x400 free, was NFSMNT_KERB */ + +#define NFSMNT_DUMBTIMR 0x00000800 /* Don't estimate rtt dynamically */ + +/* 0x1000 free, was NFSMNT_LEASETERM */ + +#define NFSMNT_READAHEAD 0x00002000 /* set read ahead */ +#define NFSMNT_DEADTHRESH 0x00004000 /* set dead server retry thresh */ +#define NFSMNT_RESVPORT 0x00008000 /* Allocate a reserved port */ +#define NFSMNT_RDIRPLUS 0x00010000 /* Use Readdirplus for V3 */ +#define NFSMNT_READDIRSIZE 0x00020000 /* Set readdir size */ +#define NFSMNT_ACREGMIN 0x00040000 +#define NFSMNT_ACREGMAX 0x00080000 +#define NFSMNT_ACDIRMIN 0x00100000 +#define NFSMNT_ACDIRMAX 0x00200000 +#define NFSMNT_NOLOCKD 0x00400000 /* Locks are local */ +#define NFSMNT_NFSV4 0x00800000 /* Use NFS Version 4 protocol */ +#define NFSMNT_HASWRITEVERF 0x01000000 /* NFSv4 Write verifier */ +#define NFSMNT_GOTFSINFO 0x00000004 /* Got the V3 fsinfo */ +#define NFSMNT_INTERNAL 0xfffc0000 /* Bits set internally */ +#define NFSMNT_NOAC 0x00080000 /* Turn off attribute cache */ /* Conversion macros */ @@ -250,11 +283,11 @@ #define nfsv2tov_type(a) nv2tov_type[fxdr_unsigned(uint32_t,(a))&0x7] #define nfsv3tov_type(a) nv3tov_type[fxdr_unsigned(uint32_t,(a))&0x7] -#define NFS_MAXFHSIZE 64 +#define NFS_MAXFHSIZE 64 /* File identifier */ -#define MAXFIDSZ 16 +#define MAXFIDSZ 16 /**************************************************************************** * Public Types @@ -301,14 +334,14 @@ struct fhandle typedef struct fhandle fhandle_t; /* File Handle (32 bytes for version 2), variable up to 64 for version 3. */ -/* + union nfsfh { - fhandle_t fh_generic; - unsigned char fh_bytes[NFS_MAXFHSIZE]; +//fhandle_t fh_generic; + unsigned char fh_bytes[NFSX_V2FH]; }; typedef union nfsfh nfsfh_t; -*/ + struct nfsv2_time { uint32_t nfsv2_sec; @@ -360,7 +393,7 @@ struct nfs_fattr uint32_t fa_gid; union { - struct + /*struct { uint32_t nfsv2fa_size; uint32_t nfsv2fa_blocksize; @@ -371,7 +404,7 @@ struct nfs_fattr nfstime2 nfsv2fa_atime; nfstime2 nfsv2fa_mtime; nfstime2 nfsv2fa_ctime; - } fa_nfsv2; + } fa_nfsv2;*/ struct { nfsuint64 nfsv3fa_size; @@ -388,7 +421,7 @@ struct nfs_fattr /* And some ugly defines for accessing union components */ -#define fa2_size fa_un.fa_nfsv2.nfsv2fa_size +/*#define fa2_size fa_un.fa_nfsv2.nfsv2fa_size #define fa2_blocksize fa_un.fa_nfsv2.nfsv2fa_blocksize #define fa2_rdev fa_un.fa_nfsv2.nfsv2fa_rdev #define fa2_blocks fa_un.fa_nfsv2.nfsv2fa_blocks @@ -396,7 +429,7 @@ struct nfs_fattr #define fa2_fileid fa_un.fa_nfsv2.nfsv2fa_fileid #define fa2_atime fa_un.fa_nfsv2.nfsv2fa_atime #define fa2_mtime fa_un.fa_nfsv2.nfsv2fa_mtime -#define fa2_ctime fa_un.fa_nfsv2.nfsv2fa_ctime +#define fa2_ctime fa_un.fa_nfsv2.nfsv2fa_ctime*/ #define fa3_size fa_un.fa_nfsv3.nfsv3fa_size #define fa3_used fa_un.fa_nfsv3.nfsv3fa_used #define fa3_rdev fa_un.fa_nfsv3.nfsv3fa_rdev @@ -436,14 +469,14 @@ struct nfs_statfs struct nfs_fattr obj_attributes; union { - struct + /*struct { uint32_t nfsv2sf_tsize; uint32_t nfsv2sf_bsize; uint32_t nfsv2sf_blocks; uint32_t nfsv2sf_bfree; uint32_t nfsv2sf_bavail; - } sf_nfsv2; + } sf_nfsv2;*/ struct { nfsuint64 nfsv3sf_tbytes; @@ -457,11 +490,11 @@ struct nfs_statfs } sf_un; }; -#define sf_tsize sf_un.sf_nfsv2.nfsv2sf_tsize +/*#define sf_tsize sf_un.sf_nfsv2.nfsv2sf_tsize #define sf_bsize sf_un.sf_nfsv2.nfsv2sf_bsize #define sf_blocks sf_un.sf_nfsv2.nfsv2sf_blocks #define sf_bfree sf_un.sf_nfsv2.nfsv2sf_bfree -#define sf_bavail sf_un.sf_nfsv2.nfsv2sf_bavail +#define sf_bavail sf_un.sf_nfsv2.nfsv2sf_bavail*/ #define sf_tbytes sf_un.sf_nfsv3.nfsv3sf_tbytes #define sf_fbytes sf_un.sf_nfsv3.nfsv3sf_fbytes #define sf_abytes sf_un.sf_nfsv3.nfsv3sf_abytes @@ -489,21 +522,27 @@ struct nfsv3_fsinfo struct wcc_attr { - nfsuint64 size; - nfstime3 mtime; - nfstime3 ctime; + nfsuint64 size; + nfstime3 mtime; + nfstime3 ctime; }; struct wcc_data { - struct wcc_attr before; - struct nfs_fattr after; + struct wcc_attr before; + struct nfs_fattr after; +}; + +struct file_handle +{ + uint32_t length; + nfsfh_t handle; }; struct diropargs3 { - nfsfh_t dir; - const char *name; + struct file_handle dir; + char *name; }; struct CREATE3args @@ -514,7 +553,7 @@ struct CREATE3args struct CREATE3resok { - nfsfh_t handle; + struct file_handle fshandle; struct nfs_fattr attributes; struct wcc_data dir_wcc; }; @@ -588,7 +627,7 @@ struct MKDIR3args struct MKDIR3resok { - nfsfh_t handle; + struct file_handle fshandle; struct nfs_fattr obj_attributes; struct wcc_data dir_wcc; }; @@ -605,7 +644,7 @@ struct RMDIR3resok struct READDIR3args { - nfsfh_t dir; + struct file_handle dir; nfsuint64 cookie; nfsuint64 cookieverf; uint32_t count; @@ -634,6 +673,6 @@ struct READDIR3resok struct FS3args { - nfsfh_t fsroot; + struct file_handle fsroot; }; #endif diff --git a/nuttx/fs/nfs/nfs_socket.c b/nuttx/fs/nfs/nfs_socket.c index b2635c291..b023c9212 100644 --- a/nuttx/fs/nfs/nfs_socket.c +++ b/nuttx/fs/nfs/nfs_socket.c @@ -47,12 +47,11 @@ #include #include +#include "nfs_proto.h" +#include "nfs_mount.h" #include "nfs.h" #include "rpc.h" -#include "rpc_v2.h" -#include "nfs_proto.h" #include "xdr_subs.h" -#include "nfs_mount.h" #include "nfs_socket.h" /**************************************************************************** diff --git a/nuttx/fs/nfs/nfs_vfsops.c b/nuttx/fs/nfs/nfs_vfsops.c index d78d70dde..860c657d8 100644 --- a/nuttx/fs/nfs/nfs_vfsops.c +++ b/nuttx/fs/nfs/nfs_vfsops.c @@ -71,7 +71,6 @@ #include #include "nfs.h" -#include "rpc_v2.h" #include "rpc.h" #include "nfs_proto.h" #include "nfs_node.h" @@ -105,9 +104,11 @@ static int nfs_open(FAR struct file *filep, const char *relpath, static ssize_t nfs_read(FAR struct file *filep, char *buffer, size_t buflen); static ssize_t nfs_write(FAR struct file *filep, const char *buffer, size_t buflen); +static int nfs_opendir(struct inode *mountpt, const char *relpath, + struct fs_dirent_s *dir); static int nfs_readdir(struct inode *mountpt, struct fs_dirent_s *dir); static int nfs_bind(FAR struct inode *blkdriver, const void *data, - void **handle); + void **handle); static int nfs_unbind(void *handle, FAR struct inode **blkdriver); static int nfs_statfs(struct inode *mountpt, struct statfs *buf); static int nfs_remove(struct inode *mountpt, const char *relpath); @@ -144,7 +145,7 @@ const struct mountpt_operations nfs_operations = NULL, /* ioctl */ NULL, /* sync */ - NULL, /* opendir */ + nfs_opendir, /* opendir */ NULL, /* closedir */ nfs_readdir, /* readdir */ NULL, /* rewinddir */ @@ -235,8 +236,9 @@ again: memset(&create, 0, sizeof(struct CREATE3args)); create.how = sp; - create.where.dir = np->n_fhp; - create.where.name = relpath; + create.where.dir.length = txdr_unsigned(np->n_fhsize); + create.where.dir.handle = np->n_fhp; + //create.where.name = relpath; error = nfs_request(nmp, NFSPROC_CREATE, (FAR const void *)&create, (void *)&resok); if (!error) @@ -259,7 +261,7 @@ again: np->n_open = true; np->nfsv3_type = NFREG; - np->n_fhp = resok.handle; + np->n_fhp = resok.fshandle.handle; np->n_size = fxdr_hyper(&resok.attributes.fa3_size); np->n_fattr = resok.attributes; fxdr_nfsv3time(&resok.attributes.fa3_mtime, &np->n_mtime) @@ -579,6 +581,54 @@ errout_with_semaphore: return error; } +/**************************************************************************** + * Name: nfs_opendir + * + * Description: + * Open a directory for read access + * + ****************************************************************************/ + +static int nfs_opendir(struct inode *mountpt, const char *relpath, + struct fs_dirent_s *dir) +{ + struct nfsmount *nmp; + //struct romfs_dirinfo_s dirinfo; + int ret; + + fvdbg("relpath: '%s'\n", relpath); + + /* 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); + ret = nfs_checkmount(nmp); + if (ret != OK) + { + fdbg("nfs_checkmount failed: %d\n", ret); + goto errout_with_semaphore; + } + + /* The entry is a directory */ + + dir->u.nfs.nd_direoffset = false; + dir->u.nfs.cookie[0] = 0; + dir->u.nfs.cookie[1] = 0; + nfs_semgive(nmp); + return OK; + +errout_with_semaphore: + nfs_semgive(nmp); + return ERROR; +} + /**************************************************************************** * Name: nfs_readdirrpc * @@ -602,7 +652,8 @@ int nfs_readdirrpc(struct nfsmount *nmp, struct nfsnode *np, { nfsstats.rpccnt[NFSPROC_READDIR]++; memset(&readir, 0, sizeof(struct READDIR3args)); - readir.dir = np->n_fhp; + readir.dir.length = txdr_unsigned(np->n_fhsize); + readir.dir.handle = np->n_fhp; readir.count = nmp->nm_readdirsize; if (nfsstats.rpccnt[NFSPROC_READDIR] == 1) @@ -719,7 +770,7 @@ static int nfs_readdir(struct inode *mountpt, struct fs_dirent_s *dir) error = nfs_checkmount(nmp); if (error != 0) { - ndbg("romfs_checkmount failed: %d\n", error); + ndbg("nfs_checkmount failed: %d\n", error); goto errout_with_semaphore; } @@ -1030,8 +1081,7 @@ int mountnfs(struct nfs_args *argp, void **handle) nmp->nm_acregmax = NFS_MAXATTRTIMO; nmp->nm_acdirmin = NFS_MINATTRTIMO; nmp->nm_acdirmax = NFS_MAXATTRTIMO; - nmp->nm_fh = argp->fh; - strncpy(nmp->nm_path, argp->path,90); + strncpy(nmp->nm_path, argp->path, 90); nmp->nm_nam = argp->addr; nfs_decode_args(nmp, argp); @@ -1046,6 +1096,8 @@ int mountnfs(struct nfs_args *argp, void **handle) return -ENOMEM; } + np->nfsv3_type = NFDIR; + np->n_open = true; nmp->nm_head = np; /* Set up the sockets and per-host congestion */ @@ -1066,6 +1118,9 @@ int mountnfs(struct nfs_args *argp, void **handle) nmp->nm_mounted = true; nmp->nm_fh = nmp->nm_rpcclnt->rc_fh; + nmp->nm_fhsize = NFSX_V2FH; + nmp->nm_head->n_fhp = nmp->nm_fh; + nmp->nm_head->n_fhsize = nmp->nm_fhsize; nmp->nm_so = nmp->nm_rpcclnt->rc_so; *handle = (void*)nmp; nfs_semgive(nmp); @@ -1113,11 +1168,6 @@ static int nfs_bind(struct inode *blkdriver, const void *data, void **handle) return -EINVAL; } - if (args.fhsize < 0 || args.fhsize > NFSX_V3FHMAX) - { - return -EINVAL; - } - error = mountnfs(&args, handle); return error; } @@ -1194,7 +1244,7 @@ static int nfs_statfs(struct inode *mountpt, struct statfs *sbp) error = nfs_checkmount(nmp); if (error < 0) { - ndbg("romfs_checkmount failed: %d\n", error); + ndbg("nfs_checkmount failed: %d\n", error); goto errout_with_semaphore; } @@ -1210,7 +1260,9 @@ static int nfs_statfs(struct inode *mountpt, struct statfs *sbp) nfsstats.rpccnt[NFSPROC_FSSTAT]++; memset(&fsstat, 0, sizeof(struct FS3args)); - fsstat.fsroot = nmp->nm_fh; + fsstat.fsroot.length = txdr_unsigned(nmp->nm_fhsize); + fsstat.fsroot.handle = nmp->nm_fh; +//fsstat.fsroot = nmp->nm_fh; error = nfs_request(nmp, NFSPROC_FSSTAT, (FAR const void *)&fsstat, (FAR void *) &sfp); if (error) @@ -1248,9 +1300,8 @@ static int nfs_remove(struct inode *mountpt, const char *relpath) { struct nfsmount *nmp; struct nfsnode *np; - void *datareply; struct REMOVE3args remove; - struct REMOVE3resok *resok; + struct REMOVE3resok resok; int error = 0; /* Sanity checks */ @@ -1285,10 +1336,12 @@ static int nfs_remove(struct inode *mountpt, const char *relpath) nfsstats.rpccnt[NFSPROC_REMOVE]++; memset(&remove, 0, sizeof(struct REMOVE3args)); - remove.object.dir = np->n_fhp; - remove.object.name = relpath; + remove.object.dir.length = txdr_unsigned(np->n_fhsize); + remove.object.dir.handle = np->n_fhp; + //remove.object.name = relpath; - error = nfs_request(nmp, NFSPROC_REMOVE, &remove, &datareply); + error = nfs_request(nmp, NFSPROC_REMOVE, (FAR const void *)&remove, + (FAR void*)&resok); /* Kludge City: If the first reply to the remove rpc is lost.. * the reply to the retransmitted request will be ENOENT @@ -1306,8 +1359,7 @@ static int nfs_remove(struct inode *mountpt, const char *relpath) goto errout_with_semaphore; } - resok = (struct REMOVE3resok *) datareply; - np->n_fattr = resok->dir_wcc.after; + np->n_fattr = resok.dir_wcc.after; np->n_flag |= NMODIFIED; } @@ -1331,8 +1383,7 @@ static int nfs_mkdir(struct inode *mountpt, const char *relpath, mode_t mode) struct nfsmount *nmp; struct nfsnode *np; struct MKDIR3args mkir; - struct MKDIR3resok *resok; - void *datareply; + struct MKDIR3resok resok; int error = 0; /* Sanity checks */ @@ -1355,8 +1406,9 @@ static int nfs_mkdir(struct inode *mountpt, const char *relpath, mode_t mode) nfsstats.rpccnt[NFSPROC_MKDIR]++; memset(&mkir, 0, sizeof(struct MKDIR3args)); - mkir.where.dir = np->n_fhp; - mkir.where.name = relpath; + mkir.where.dir.length = txdr_unsigned(np->n_fhsize); + mkir.where.dir.handle = np->n_fhp; +//mkir.where.name = relpath; sp.sa_modetrue = nfs_true; sp.sa_mode = txdr_unsigned(mode); @@ -1371,16 +1423,16 @@ static int nfs_mkdir(struct inode *mountpt, const char *relpath, mode_t mode) mkir.attributes = sp; - error = nfs_request(nmp, NFSPROC_MKDIR, &mkir, &datareply); + error = nfs_request(nmp, NFSPROC_MKDIR, (FAR const void *)&mkir, + (FAR void *)&resok); if (error) { goto errout_with_semaphore; } - resok = (struct MKDIR3resok *) datareply; np->nfsv3_type = NFDIR; - np->n_fhp = resok->handle; - np->n_fattr = resok->obj_attributes; + np->n_fhp = resok.fshandle.handle; + np->n_fattr = resok.obj_attributes; np->n_flag |= NMODIFIED; NFS_INVALIDATE_ATTRCACHE(np); @@ -1402,8 +1454,7 @@ static int nfs_rmdir(struct inode *mountpt, const char *relpath) struct nfsmount *nmp; struct nfsnode *np; struct RMDIR3args rmdir; - struct RMDIR3resok *resok; - void *datareply; + struct RMDIR3resok resok; int error = 0; /* Sanity checks */ @@ -1433,10 +1484,12 @@ static int nfs_rmdir(struct inode *mountpt, const char *relpath) nfsstats.rpccnt[NFSPROC_RMDIR]++; memset(&rmdir, 0, sizeof(struct RMDIR3args)); - rmdir.object.dir = np->n_fhp; - rmdir.object.name = relpath; + rmdir.object.dir.length = txdr_unsigned(np->n_fhsize); + rmdir.object.dir.handle = np->n_fhp; + //rmdir.object.name = relpath; - error = nfs_request(nmp, NFSPROC_RMDIR, &rmdir, &datareply); + error = nfs_request(nmp, NFSPROC_RMDIR, (FAR const void *)&rmdir, + (FAR void *)&resok); if (error == ENOENT) { error = 0; @@ -1447,8 +1500,7 @@ static int nfs_rmdir(struct inode *mountpt, const char *relpath) goto errout_with_semaphore; } - resok = (struct RMDIR3resok *) datareply; - np->n_fattr = resok->dir_wcc.after; + np->n_fattr = resok.dir_wcc.after; np->n_flag |= NMODIFIED; } @@ -1467,13 +1519,12 @@ errout_with_semaphore: ****************************************************************************/ static int nfs_rename(struct inode *mountpt, const char *oldrelpath, - const char *newrelpath) + const char *newrelpath) { struct nfsmount *nmp; struct nfsnode *np; - void *datareply; struct RENAME3args rename; - struct RENAME3resok *resok; + struct RENAME3resok resok; int error = 0; /* Sanity checks */ @@ -1503,12 +1554,15 @@ static int nfs_rename(struct inode *mountpt, const char *oldrelpath, nfsstats.rpccnt[NFSPROC_RENAME]++; memset(&rename, 0, sizeof(struct RENAME3args)); - rename.from.dir = np->n_fhp; - rename.from.name = oldrelpath; - rename.to.dir = np->n_fhp; - rename.to.name = newrelpath; + rename.from.dir.length = txdr_unsigned(np->n_fhsize); + rename.from.dir.handle = np->n_fhp; +//rename.from.name = oldrelpath; + rename.to.dir.length = txdr_unsigned(np->n_fhsize); + rename.to.dir.handle = np->n_fhp; +//rename.to.name = newrelpath; - error = nfs_request(nmp, NFSPROC_RENAME, &rename, &datareply); + error = nfs_request(nmp, NFSPROC_RENAME, (FAR const void *)&rename, + (FAR void *)&resok); /* ENOENT => 0 assuming that it is a reply to a retry. */ @@ -1522,8 +1576,7 @@ static int nfs_rename(struct inode *mountpt, const char *oldrelpath, goto errout_with_semaphore; } - resok = (struct RENAME3resok *) datareply; - np->n_fattr = resok->todir_wcc.after; + np->n_fattr = resok.todir_wcc.after; np->n_flag |= NMODIFIED; NFS_INVALIDATE_ATTRCACHE(np); @@ -1566,11 +1619,11 @@ static int nfs_fsinfo(struct inode *mountpt, const char *relpath, struct stat *b memset(buf, 0, sizeof(struct stat)); nfsstats.rpccnt[NFSPROC_FSINFO]++; - fsinfo.fsroot = nmp->nm_fh; - nvdbg("fhinfo %d\n", nmp->nm_fh); - nvdbg("fhinfo2 %d\n", fsinfo.fsroot); + fsinfo.fsroot.length = txdr_unsigned(nmp->nm_fhsize); + fsinfo.fsroot.handle = nmp->nm_fh; - error = nfs_request(nmp, NFSPROC_FSINFO, (FAR const void *)&fsinfo, (FAR void *)&fsp); + error = nfs_request(nmp, NFSPROC_FSINFO, (FAR const void *)&fsinfo, + (FAR void *)&fsp); if (error) { goto errout_with_semaphore; diff --git a/nuttx/fs/nfs/rpc.h b/nuttx/fs/nfs/rpc.h index 8fa3da917..9c85777fa 100644 --- a/nuttx/fs/nfs/rpc.h +++ b/nuttx/fs/nfs/rpc.h @@ -80,31 +80,144 @@ * Pre-processor Definitions ****************************************************************************/ +/* Version # */ + +#define RPC_VER2 2 + +/* Authentication */ + +#define RPCAUTH_NULL 0 +#define RPCAUTH_UNIX 1 +#define RPCAUTH_SHORT 2 +#define RPCAUTH_KERB4 4 +#define RPCAUTH_MAXSIZ 400 +#define RPCVERF_MAXSIZ 12 + /* For Kerb, can actually be 400 */ +#define RPCAUTH_UNIXGIDS 16 + +/* Constants associated with authentication flavours. */ + +#define RPCAKN_FULLNAME 0 +#define RPCAKN_NICKNAME 1 + +/* Rpc Constants */ + +#define RPC_CALL 0 +#define RPC_REPLY 1 +#define RPC_MSGACCEPTED 0 +#define RPC_MSGDENIED 1 +#define RPC_PROGUNAVAIL 1 +#define RPC_PROGMISMATCH 2 +#define RPC_PROCUNAVAIL 3 +#define RPC_GARBAGE 4 + +#define RPC_MISMATCH 0 +#define RPC_AUTHERR 1 + +/* Authentication failures */ + +#define AUTH_BADCRED 1 +#define AUTH_REJECTCRED 2 +#define AUTH_BADVERF 3 +#define AUTH_REJECTVERF 4 +#define AUTH_TOOWEAK 5 + +/* Sizes of rpc header parts */ + +#define RPC_SIZ 24 +#define RPC_REPLYSIZ 28 + +/* RPC Prog definitions */ + +#define RPCPROG_MNT 100005 +#define RPCMNT_VER1 1 +#define RPCMNT_VER3 3 +#define RPCMNT_MOUNT 1 +#define RPCMNT_DUMP 2 +#define RPCMNT_UMOUNT 3 +#define RPCMNT_UMNTALL 4 +#define RPCMNT_EXPORT 5 +#define RPCMNT_NAMELEN 255 +#define RPCMNT_PATHLEN 1024 +#define RPCPROG_NFS 100003 + /* for rpcclnt's rc_flags */ -#define RPCCLNT_SOFT 0x001 /* soft mount (hard is details) */ -#define RPCCLNT_INT 0x002 /* allow interrupts on hard mounts */ -#define RPCCLNT_NOCONN 0x004 /* dont connect the socket (udp) */ -#define RPCCLNT_DUMBTIMR 0x010 +#define RPCCLNT_SOFT 0x001 /* soft mount (hard is details) */ +#define RPCCLNT_INT 0x002 /* allow interrupts on hard mounts */ +#define RPCCLNT_NOCONN 0x004 /* dont connect the socket (udp) */ +#define RPCCLNT_DUMBTIMR 0x010 /* XXX should be replaced with real locks */ -#define RPCCLNT_SNDLOCK 0x100 -#define RPCCLNT_WANTSND 0x200 -#define RPCCLNT_RCVLOCK 0x400 -#define RPCCLNT_WANTRCV 0x800 +#define RPCCLNT_SNDLOCK 0x100 +#define RPCCLNT_WANTSND 0x200 +#define RPCCLNT_RCVLOCK 0x400 +#define RPCCLNT_WANTRCV 0x800 /* RPC definitions for the portmapper. */ -#define PMAPPORT 111 -#define PMAPPROG 100000 -#define PMAPVERS 2 -#define PMAPPROC_NULL 0 -#define PMAPPROC_SET 1 -#define PMAPPROC_UNSET 2 -#define PMAPPROC_GETPORT 3 -#define PMAPPROC_DUMP 4 -#define PMAPPROC_CALLIT 5 +#define PMAPPORT 111 +#define PMAPPROG 100000 +#define PMAPVERS 2 +#define PMAPPROC_NULL 0 +#define PMAPPROC_SET 1 +#define PMAPPROC_UNSET 2 +#define PMAPPROC_GETPORT 3 +#define PMAPPROC_DUMP 4 +#define PMAPPROC_CALLIT 5 + +#define RPCCLNT_DEBUG 1 + +#define RPC_TICKINTVL 5 + +/* from nfs/nfsproto.h */ + +#define RPC_MAXDATA 32768 +#define RPC_MAXPKTHDR 404 +#define RPC_MAXPACKET (RPC_MAXPKTHDR + RPC_MAXDATA) + +#define RPCX_UNSIGNED 4 + +#define RPC_SUCCESS 0 + +/* Flag values for r_flags */ + +#define TASK_TIMING 0x01 /* timing request (in mntp) */ +#define TASK_SENT 0x02 /* request has been sent */ +#define TASK_SOFTTERM 0x04 /* soft mnt, too many retries */ + + +#define TASK_INTR 0x08 /* intr mnt, signal pending */ +#define TASK_SOCKERR 0x10 /* Fatal error on socket */ + + +#define TASK_TPRINTFMSG 0x20 /* Did a tprintf msg. */ + +#define TASK_MUSTRESEND 0x40 /* Must resend request */ +#define TASK_GETONEREP 0x80 /* Probe for one reply only */ + + +#define RPC_HZ (CLOCKS_PER_SEC / rpcclnt_ticks) /* Ticks/sec */ +#define RPC_TIMEO (1 * RPC_HZ) /* Default timeout = 1 second */ + +#define RPC_MAXREXMIT 100 /* Stop counting after this many */ + + +#define RPCIGNORE_SOERROR(s, e) \ + ((e) != EINTR && (e) != ERESTART && (e) != EWOULDBLOCK) + +#define RPCINT_SIGMASK (sigmask(SIGINT)|sigmask(SIGTERM)|sigmask(SIGKILL)| \ + sigmask(SIGHUP)|sigmask(SIGQUIT)) + +#define RPCMADV(m, s) (m)->m_data += (s) + +#define RPCAUTH_ROOTCREDS NULL + +#define RPCCLNTINT_SIGMASK(set) \ + (SIGISMEMBER(set, SIGINT) || SIGISMEMBER(set, SIGTERM) || \ + SIGISMEMBER(set, SIGHUP) || SIGISMEMBER(set, SIGKILL) || \ + SIGISMEMBER(set, SIGQUIT)) /**************************************************************************** * Public Types @@ -115,6 +228,17 @@ struct xidr uint32_t xid; }; +/* global rpcstats */ + +struct rpcstats +{ + int rpcretries; + int rpcrequests; + int rpctimeouts; + int rpcunexpected; + int rpcinvalid; +}; + /* PMAP headers */ struct call_args_pmap { @@ -134,7 +258,7 @@ struct call_result_pmap struct call_args_mount { uint32_t len; - char rpath[92]; + char rpath[90]; }; struct call_result_mount @@ -147,9 +271,9 @@ struct call_result_mount enum auth_flavor { - AUTH_NONE = 0, - AUTH_SYS = 1, - AUTH_SHORT = 2 + AUTH_NONE = 0, + AUTH_SYS = 1, + AUTH_SHORT = 2 /* and more to be defined */ }; @@ -258,7 +382,7 @@ struct rpc_reply_header uint32_t type; struct rpc_auth_info rpc_verfi; uint32_t status; -//enum msg_type rp_direction; /* call direction (1) */ +//enum msg_type rp_direction; /* call direction (1) */ //enum reply_stat type; //enum accept_stat status; /* diff --git a/nuttx/fs/nfs/rpc_clnt.c b/nuttx/fs/nfs/rpc_clnt.c index dfb25823a..e39d1c161 100644 --- a/nuttx/fs/nfs/rpc_clnt.c +++ b/nuttx/fs/nfs/rpc_clnt.c @@ -95,8 +95,6 @@ #include "xdr_subs.h" #include "nfs_proto.h" #include "rpc.h" -#include "rpc_clnt_private.h" -#include "rpc_v2.h" /**************************************************************************** * Pre-processor Definitions @@ -1158,7 +1156,7 @@ void rpcclnt_init(void) //rpcclnt_timer(NULL, callmgs); - nvdbg("rpc initialized"); + nvdbg("rpc initialized\n"); return; } @@ -1305,7 +1303,7 @@ int rpcclnt_connect(struct rpcclnt *rpc) memset(&mountd, 0, sizeof(mountd)); memset(&mdata, 0, sizeof(mdata)); - strncpy(mountd.rpath, rpc->rc_path, 92); + strncpy(mountd.rpath, rpc->rc_path, 90); mountd.len = txdr_unsigned(sizeof(mountd.rpath)); error = rpcclnt_request(rpc, RPCMNT_MOUNT, RPCPROG_MNT, RPCMNT_VER1, @@ -1321,13 +1319,7 @@ int rpcclnt_connect(struct rpcclnt *rpc) goto bad; } - nvdbg("fh %d\n", mdata.mount.fhandle); - nvdbg("fh rpc antes %d\n", rpc->rc_fh); - //bcopy(&mdata.mount.fhandle, rpc->rc_fh, NFS_MAXFHSIZE); - //bcopy(mdata.mount.fhandle, rpc->rc_fh, NFS_MAXFHSIZE); rpc->rc_fh = mdata.mount.fhandle; - //ndvbg("fh_mounted %d\n", mdata.mount.fhandle); - ndbg("fh rpc despues %d\n", rpc->rc_fh); /* NFS port in the socket*/ @@ -1423,8 +1415,6 @@ int rpcclnt_umount(struct rpcclnt *rpc) * Get port number for MOUNTD. */ - nvdbg("Entry: fh %d\n", rpc->rc_fh); - memset(&sdata, 0, sizeof(sdata)); memset(&rdata, 0, sizeof(rdata)); sa->sin_port = htons(PMAPPORT); @@ -1474,7 +1464,7 @@ int rpcclnt_umount(struct rpcclnt *rpc) if ((fxdr_unsigned(uint32_t, mdata.mount.status)) != 0) { - ndbg("error mounting with the server %d\n", error); + ndbg("error unmounting with the server %d\n", error); goto bad; } diff --git a/nuttx/fs/nfs/rpc_clnt_private.h b/nuttx/fs/nfs/rpc_clnt_private.h deleted file mode 100644 index 204bb2b83..000000000 --- a/nuttx/fs/nfs/rpc_clnt_private.h +++ /dev/null @@ -1,148 +0,0 @@ -/**************************************************************************** - * fs/nfs/rpc_clnt_private.h - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Copyright (C) 2012 Jose Pablo Rojas Vargas. All rights reserved. - * Author: Jose Pablo Rojas Vargas - * - * Leveraged from OpenBSD: - * - * copyright (c) 2003 - * the regents of the university of michigan - * all rights reserved - * - * permission is granted to use, copy, create derivative works and redistribute - * this software and such derivative works for any purpose, so long as the name - * of the university of michigan is not used in any advertising or publicity - * pertaining to the use or distribution of this software without specific, - * written prior authorization. if the above copyright notice or any other - * identification of the university of michigan is included in any copy of any - * portion of this software, then the disclaimer below must also be included. - * - * this software is provided as is, without representation from the university - * of michigan as to its fitness for any purpose, and without warranty by the - * university of michigan of any kind, either express or implied, including - * without limitation the implied warranties of merchantability and fitness for - * a particular purpose. the regents of the university of michigan shall not be - * liable for any damages, including special, indirect, incidental, or - * consequential damages, with respect to any claim arising out of or in - * connection with the use of the software, even if it has been or is hereafter - * advised of the possibility of such damages. - * - * Copyright (c) 1989, 1993 - * The Regents of the University of California. All rights reserved. - * - * This code is derived from software contributed to Berkeley by - * Rick Macklem at The University of Guelph. - * - * 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. All advertising materials mentioning features or use of this software - * must display the following acknowledgement: - * This product includes software developed by the University of - * California, Berkeley and its contributors. - * 4. Neither the name of the University nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE REGENTS AND CONTRIBUTORS ``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 REGENTS OR CONTRIBUTORS 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 __FS_NFS_RPC_CLIENT_PRIVATE_H -#define __FS_NFS_RPC_CLIENT_PRIVATE_H - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -#define RPCCLNT_DEBUG 1 - -#define RPC_TICKINTVL 5 - -/* from nfs/nfsproto.h */ - -#define RPC_MAXDATA 32768 -#define RPC_MAXPKTHDR 404 -#define RPC_MAXPACKET (RPC_MAXPKTHDR + RPC_MAXDATA) - -#define RPCX_UNSIGNED 4 - -#define RPC_SUCCESS 0 - -/* Flag values for r_flags */ - -#define TASK_TIMING 0x01 /* timing request (in mntp) */ -#define TASK_SENT 0x02 /* request has been sent */ -#define TASK_SOFTTERM 0x04 /* soft mnt, too many retries */ - - -#define TASK_INTR 0x08 /* intr mnt, signal pending */ -#define TASK_SOCKERR 0x10 /* Fatal error on socket */ - - -#define TASK_TPRINTFMSG 0x20 /* Did a tprintf msg. */ - -#define TASK_MUSTRESEND 0x40 /* Must resend request */ -#define TASK_GETONEREP 0x80 /* Probe for one reply only */ - - -#define RPC_HZ (CLOCKS_PER_SEC / rpcclnt_ticks) /* Ticks/sec */ -#define RPC_TIMEO (1 * RPC_HZ) /* Default timeout = 1 second */ - -#define RPC_MAXREXMIT 100 /* Stop counting after this many */ - - -#define RPCIGNORE_SOERROR(s, e) \ - ((e) != EINTR && (e) != ERESTART && (e) != EWOULDBLOCK) - -#define RPCINT_SIGMASK (sigmask(SIGINT)|sigmask(SIGTERM)|sigmask(SIGKILL)| \ - sigmask(SIGHUP)|sigmask(SIGQUIT)) - -#define RPCMADV(m, s) (m)->m_data += (s) - -#define RPCAUTH_ROOTCREDS NULL - -#define RPCCLNTINT_SIGMASK(set) \ - (SIGISMEMBER(set, SIGINT) || SIGISMEMBER(set, SIGTERM) || \ - SIGISMEMBER(set, SIGHUP) || SIGISMEMBER(set, SIGKILL) || \ - SIGISMEMBER(set, SIGQUIT)) - -/**************************************************************************** - * Public Types - ****************************************************************************/ - -/* global rpcstats - * XXX should be per rpcclnt */ - -struct rpcstats -{ - int rpcretries; - int rpcrequests; - int rpctimeouts; - int rpcunexpected; - int rpcinvalid; -}; - -#endif /* __FS_NFS_RPC_CLIENT_PRIVATE_H */ diff --git a/nuttx/fs/nfs/rpc_v2.h b/nuttx/fs/nfs/rpc_v2.h deleted file mode 100644 index 3e4f215ff..000000000 --- a/nuttx/fs/nfs/rpc_v2.h +++ /dev/null @@ -1,117 +0,0 @@ -/**************************************************************************** - * fs/nfs/rpc_types.h - * Definitions for Sun RPC Version 2, from - * "RPC: Remote Procedure Call Protocol Specification" RFC1057 - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Copyright (C) 2012 Jose Pablo Rojas Vargas. All rights reserved. - * Author: Jose Pablo Rojas Vargas - * - * Leveraged from OpenBSD: - * - * Copyright (c) 1989, 1993 - * The Regents of the University of California. All rights reserved. - * - * This code is derived from software contributed to Berkeley by - * Rick Macklem at The University of Guelph. - * - * 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. Neither the name of the University nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE REGENTS AND CONTRIBUTORS ``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 REGENTS OR CONTRIBUTORS 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 __FS_NFS_RPC_V2_H -#define __FS_NFS_RPC_V2_H - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/* Version # */ - -#define RPC_VER2 2 - -/* Authentication */ - -#define RPCAUTH_NULL 0 -#define RPCAUTH_UNIX 1 -#define RPCAUTH_SHORT 2 -#define RPCAUTH_KERB4 4 -#define RPCAUTH_MAXSIZ 400 -#define RPCVERF_MAXSIZ 12 - /* For Kerb, can actually be 400 */ -#define RPCAUTH_UNIXGIDS 16 - -/* Constants associated with authentication flavours. */ - -#define RPCAKN_FULLNAME 0 -#define RPCAKN_NICKNAME 1 - -/* Rpc Constants */ - -#define RPC_CALL 0 -#define RPC_REPLY 1 -#define RPC_MSGACCEPTED 0 -#define RPC_MSGDENIED 1 -#define RPC_PROGUNAVAIL 1 -#define RPC_PROGMISMATCH 2 -#define RPC_PROCUNAVAIL 3 -#define RPC_GARBAGE 4 - -#define RPC_MISMATCH 0 -#define RPC_AUTHERR 1 - -/* Authentication failures */ - -#define AUTH_BADCRED 1 -#define AUTH_REJECTCRED 2 -#define AUTH_BADVERF 3 -#define AUTH_REJECTVERF 4 -#define AUTH_TOOWEAK 5 - -/* Sizes of rpc header parts */ - -#define RPC_SIZ 24 -#define RPC_REPLYSIZ 28 - -/* RPC Prog definitions */ - -#define RPCPROG_MNT 100005 -#define RPCMNT_VER1 1 -#define RPCMNT_VER3 3 -#define RPCMNT_MOUNT 1 -#define RPCMNT_DUMP 2 -#define RPCMNT_UMOUNT 3 -#define RPCMNT_UMNTALL 4 -#define RPCMNT_EXPORT 5 -#define RPCMNT_NAMELEN 255 -#define RPCMNT_PATHLEN 1024 -#define RPCPROG_NFS 100003 - -#endif /* __FS_NFS_RPC_V2_H */ diff --git a/nuttx/include/nuttx/fs/nfs.h b/nuttx/include/nuttx/fs/nfs.h index 4e009fb77..fb78151ab 100644 --- a/nuttx/include/nuttx/fs/nfs.h +++ b/nuttx/include/nuttx/fs/nfs.h @@ -53,62 +53,14 @@ * Pre-processor Definitions ****************************************************************************/ - /* NFS mount option flags */ - -#define NFSMNT_SOFT 0x00000001 /* soft mount (hard is default) */ -#define NFSMNT_WSIZE 0x00000002 /* set write size */ -#define NFSMNT_RSIZE 0x00000004 /* set read size */ -#define NFSMNT_TIMEO 0x00000008 /* set initial timeout */ -#define NFSMNT_RETRANS 0x00000010 /* set number of request retries */ -#define NFSMNT_MAXGRPS 0x00000020 /* set maximum grouplist size */ -#define NFSMNT_INT 0x00000040 /* allow interrupts on hard mount */ -#define NFSMNT_NOCONN 0x00000080 /* Don't Connect the socket */ - -/* 0x100 free, was NFSMNT_NQNFS */ - -#define NFSMNT_NFSV3 0x00000200 /* Use NFS Version 3 protocol */ - -/* 0x400 free, was NFSMNT_KERB */ - -#define NFSMNT_DUMBTIMR 0x00000800 /* Don't estimate rtt dynamically */ - -/* 0x1000 free, was NFSMNT_LEASETERM */ - -#define NFSMNT_READAHEAD 0x00002000 /* set read ahead */ -#define NFSMNT_DEADTHRESH 0x00004000 /* set dead server retry thresh */ -#define NFSMNT_RESVPORT 0x00008000 /* Allocate a reserved port */ -#define NFSMNT_RDIRPLUS 0x00010000 /* Use Readdirplus for V3 */ -#define NFSMNT_READDIRSIZE 0x00020000 /* Set readdir size */ -#define NFSMNT_ACREGMIN 0x00040000 -#define NFSMNT_ACREGMAX 0x00080000 -#define NFSMNT_ACDIRMIN 0x00100000 -#define NFSMNT_ACDIRMAX 0x00200000 -#define NFSMNT_NOLOCKD 0x00400000 /* Locks are local */ -#define NFSMNT_NFSV4 0x00800000 /* Use NFS Version 4 protocol */ -#define NFSMNT_HASWRITEVERF 0x01000000 /* NFSv4 Write verifier */ -#define NFSMNT_GOTFSINFO 0x00000004 /* Got the V3 fsinfo */ -#define NFSMNT_INTERNAL 0xfffc0000 /* Bits set internally */ -#define NFSMNT_NOAC 0x00080000 /* Turn off attribute cache */ - -#define NFS_ARGSVERSION 3 /* change when nfs_args changes */ -#define NFS_MAXFHSIZE 64 -#define NFS_PORT 2049 -#define NFS_PMAPPORT 111 +#define NFSMNT_NFSV3 0x00000200 /* Use NFS Version 3 protocol */ +#define NFS_ARGSVERSION 3 /* change when nfs_args changes */ +#define NFS_PMAPPORT 111 /**************************************************************************** * Public Types ****************************************************************************/ - /* File Handle (32 bytes for version 2), variable up to 64 for version 3. */ - -union nfsfh -{ - unsigned char fh_bytes[NFS_MAXFHSIZE]; -}; -typedef union nfsfh nfsfh_t; - -/* Arguments to mount NFS */ - struct nfs_args { uint8_t version; /* args structure version number */ @@ -116,8 +68,6 @@ struct nfs_args uint8_t addrlen; /* length of address */ uint8_t sotype; /* Socket type */ uint8_t proto; /* and Protocol */ - nfsfh_t fh; /* File handle to be mounted */ - int fhsize; /* Size, in bytes, of fh */ int flags; /* flags */ int wsize; /* write size in bytes */ int rsize; /* read size in bytes */ @@ -142,6 +92,7 @@ struct nfs_args /**************************************************************************** * Public Function Prototypes ****************************************************************************/ + #undef EXTERN #if defined(__cplusplus) #define EXTERN extern "C" -- cgit v1.2.3