summaryrefslogtreecommitdiff
path: root/nuttx/fs/nfs/nfs_vfsops.c
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-04-18 23:31:47 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-04-18 23:31:47 +0000
commit38fa2b80515c47c54d69af5adf5746174706f14e (patch)
treed774ecc6a25dc9c89bb318f4e22580d6ccddfdc0 /nuttx/fs/nfs/nfs_vfsops.c
parent607ce6753b14ac62010faab2e174b9a34e26d00f (diff)
downloadpx4-nuttx-38fa2b80515c47c54d69af5adf5746174706f14e.tar.gz
px4-nuttx-38fa2b80515c47c54d69af5adf5746174706f14e.tar.bz2
px4-nuttx-38fa2b80515c47c54d69af5adf5746174706f14e.zip
NFS update
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4634 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/fs/nfs/nfs_vfsops.c')
-rw-r--r--nuttx/fs/nfs/nfs_vfsops.c1038
1 files changed, 499 insertions, 539 deletions
diff --git a/nuttx/fs/nfs/nfs_vfsops.c b/nuttx/fs/nfs/nfs_vfsops.c
index 805b48967..856ed6819 100644
--- a/nuttx/fs/nfs/nfs_vfsops.c
+++ b/nuttx/fs/nfs/nfs_vfsops.c
@@ -60,6 +60,8 @@
#include <assert.h>
#include <errno.h>
#include <debug.h>
+#include <time.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/fs/dirent.h>
#include <nuttx/fs/fs.h>
@@ -67,11 +69,14 @@
#include <netinet/in.h>
#include "rpc_v2.h"
+#include "rpc.h"
#include "nfs_proto.h"
#include "nfs_node.h"
#include "nfs.h"
#include "nfs_mount.h"
#include "xdr_subs.h"
+#include "nfs_socket.h"
+#include "nfs_args.h"
/****************************************************************************
* Pre-processor Definitions
@@ -169,20 +174,19 @@ const struct mountpt_operations nfs_ops =
* Description: if oflags == O_CREAT it creates a file, if not it
* check to see if the type is ok and that deletion is not in progress.
****************************************************************************/
-
static int
nfs_open(FAR struct file *filep, FAR const char *relpath,
int oflags, mode_t mode)
{
struct inode *in;
- struct nfs_fattr *vap;
- struct nfsv3_sattr *sp;
+ struct nfs_fattr vap;
+ struct nfsv3_sattr sp;
struct nfsmount *nmp;
struct nfsnode *np;
- struct CREATE3args *create;
- struct CREATE3resok *resok;
- void *replydata;
+ struct CREATE3args *create = NULL;
+ struct CREATE3resok *resok = NULL;
+ void *datareply = NULL;
int error = 0;
/* Sanity checks */
@@ -216,29 +220,28 @@ nfs_open(FAR struct file *filep, FAR const char *relpath,
again:
nfsstats.rpccnt[NFSPROC_CREATE]++;
vap = nmp->nm_head->n_fattr;
- sp->sa_modetrue = nfs_true;
- sp->sa_mode = txdr_unsigned(vap->fa_mode);
- sp->sa_uid = nfs_xdrneg1;
- sp->sa_gid = nfs_xdrneg1;
- sp->sa_size = nfs_xdrneg1;
- sp->sa_atimetype = txdr_unsigned(NFSV3SATTRTIME_TOCLIENT);
- sp->sa_mtimetype = txdr_unsigned(NFSV3SATTRTIME_TOCLIENT);
-
- txdr_nfsv3time(&vap->fa_atime, &sp->sa_atime);
- txdr_nfsv3time(&vap->fa_mtime, &sp->sa_mtime);
+ sp.sa_modetrue = nfs_true;
+ sp.sa_mode = txdr_unsigned(vap.fa_mode);
+ sp.sa_uidfalse = nfs_xdrneg1;
+ sp.sa_gidfalse = nfs_xdrneg1;
+ sp.sa_sizefalse = nfs_xdrneg1;
+ sp.sa_atimetype = txdr_unsigned(NFSV3SATTRTIME_TOCLIENT);
+ sp.sa_mtimetype = txdr_unsigned(NFSV3SATTRTIME_TOCLIENT);
+ sp.sa_atime = vap.fa3_atime;
+ sp.sa_mtime = vap.fa3_mtime;
create->how = sp;
- create->where->dir= nmp->nm_fh;
- create->where->name = relpath;
+ create->where.dir = nmp->nm_fh;
+ create->where.name = relpath;
- error = nfs_request(in, NFSPROC_CREATE, create, replydata);
+ error = nfs_request(nmp, NFSPROC_CREATE, create, datareply);
if (!error)
{
/* Create an instance of the file private data to describe the opened
* file.
*/
- np = (struct nfsnode *)zalloc(sizeof(struct nfsnode));
+ np = (struct nfsnode *)kzalloc(sizeof(struct nfsnode));
if (!np)
{
fdbg("Failed to allocate private data\n", error);
@@ -250,14 +253,14 @@ again:
* non-zero elements)
*/
- resok = (struct CREATE3resok *) replydata;
+ resok = (struct CREATE3resok *) datareply;
np->n_open = true;
np->nfsv3_type = NFREG;
np->n_fhp = resok->handle;
- np->n_size = (struct uint64_t *)resok->attributes->nfsv3fa_size;
+ np->n_size = fxdr_hyper(&resok->attributes.fa3_size);
np->n_fattr = resok->attributes;
- np->n_mtime = (struct timespec*) resok->attributes->nfsv3fa_mtime
- np->n_ctime = (struct time_t*) resok->attributes->nfsv3fa_ctime
+ fxdr_nfsv3time(&resok->attributes.fa3_mtime, &np->n_mtime)
+ np->n_ctime = fxdr_hyper(&resok->attributes.fa3_ctime);
/* Attach the private date to the struct file instance */
@@ -275,7 +278,7 @@ again:
}
else
{
- if (info_v3 && error == NFSERR_NOTSUPP)
+ if (error == NFSERR_NOTSUPP)
{
goto again;
}
@@ -309,7 +312,8 @@ errout_with_semaphore:
return error;
}
-#ifdef 0
+#undef COMP
+#ifdef COMP
/****************************************************************************
* Name: nfs_close
****************************************************************************/
@@ -355,11 +359,10 @@ static ssize_t nfs_read(FAR struct file *filep, char *buffer, size_t buflen)
unsigned int readsize;
int bytesleft;
uint64_t offset;
- void *datareply;
- struct READ3args *read;
- struct READ3resok *resok;
+ void *datareply = NULL;
+ struct READ3args *read = NULL;
+ struct READ3resok *resok = NULL;
uint8_t *userbuffer = (uint8_t*)buffer;
- int info_v3;
int error = 0;
int len;
bool eof;
@@ -381,7 +384,7 @@ static ssize_t nfs_read(FAR struct file *filep, char *buffer, size_t buflen)
/* Make sure that the mount is still healthy */
- nfafs_semtake(nmp);
+ nfs_semtake(nmp);
error = nfs_checkmount(nmp);
if (error != 0)
{
@@ -417,7 +420,7 @@ static ssize_t nfs_read(FAR struct file *filep, char *buffer, size_t buflen)
len = nmp->nm_rsize;
if (len < buflen)
{
- error = EFBIG
+ error = EFBIG;
goto errout_with_semaphore;
}
@@ -439,7 +442,7 @@ again:
{
readsize = resok->count;
np->n_fattr = resok->file_attributes;
- memcpy(userbuffer, resok->data, (struct size_t)readsize);
+ memcpy(userbuffer, resok->data, readsize);
}
else
{
@@ -465,14 +468,14 @@ nfs_write(FAR struct file *filep, const char *buffer, size_t buflen)
struct nfsmount *nmp;
struct nfsnode *np;
unsigned int writesize;
- void *datareply;
- struct WRITE3args *write;
- struct WRITE3resok *resok;
+ void *datareply = NULL;
+ struct WRITE3args *write = NULL;
+ struct WRITE3resok *resok =NULL;
uint8_t *userbuffer = (uint8_t*)buffer;
int error = 0;
uint64_t offset;
int len;
- struct stable_how commit;
+ enum stable_how commit;
int committed = NFSV3WRITE_FILESYNC;
/* Sanity checks */
@@ -490,7 +493,7 @@ nfs_write(FAR struct file *filep, const char *buffer, size_t buflen)
/* Make sure that the mount is still healthy */
- nfs_semtake();
+ nfs_semtake(nmp);
error = nfs_checkmount(nmp);
if (error != 0)
{
@@ -501,14 +504,14 @@ nfs_write(FAR struct file *filep, const char *buffer, size_t buflen)
if (np->n_size + buflen < np->n_size)
{
- ret = -EFBIG;
+ error = -EFBIG;
goto errout_with_semaphore;
}
len = nmp->nm_wsize;
if (len < buflen)
{
- error = -EFBIG
+ error = -EFBIG;
goto errout_with_semaphore;
}
writesize = 0;
@@ -518,7 +521,7 @@ nfs_write(FAR struct file *filep, const char *buffer, size_t buflen)
write->offset = offset;
write->count = buflen;
write->stable = committed;
- memcpy(write->data, userbuffer, buflen);
+ memcpy((void *)write->data, userbuffer, buflen);
error = nfs_request(nmp, NFSPROC_WRITE, write, datareply);
if (error)
@@ -530,12 +533,12 @@ nfs_write(FAR struct file *filep, const char *buffer, size_t buflen)
writesize = resok->count;
if (writesize == 0)
{
- error = -NFSERR_IO;
+ error = NFSERR_IO;
goto errout_with_semaphore;
}
commit = resok->committed;
- np->n_fattr = resok->file_wcc->after;
+ np->n_fattr = resok->file_wcc.after;
/* Return the lowest committment level obtained by any of the RPCs. */
@@ -551,15 +554,15 @@ nfs_write(FAR struct file *filep, const char *buffer, size_t buflen)
if ((nmp->nm_flag & NFSMNT_HASWRITEVERF) == 0)
{
- bcopy((void) resok->verf, (void) nmp->nm_verf, NFSX_V3WRITEVERF);
+ bcopy((void*) resok->verf, (void*) nmp->nm_verf, NFSX_V3WRITEVERF);
nmp->nm_flag |= NFSMNT_HASWRITEVERF;
}
- else if (strncmp((char) resok->verf, (char) nmp->nm_verf, NFSX_V3WRITEVERF))
+ else if (strncmp((char*) resok->verf, (char*) nmp->nm_verf, NFSX_V3WRITEVERF))
{
- bcopy((void) resok->verf, (void) nmp->nm_verf, NFSX_V3WRITEVERF);
+ bcopy((void*) resok->verf, (void*) nmp->nm_verf, NFSX_V3WRITEVERF);
}
- np->n_mtime = np->n_fattr.nfsv3fa_mtime;
+ fxdr_nfsv3time(&np->n_fattr.fa3_mtime, &np->n_mtime)
nfs_semgive(nmp);
return writesize;
@@ -570,6 +573,110 @@ errout_with_semaphore:
}
/****************************************************************************
+ * Name: nfs_readdirrpc
+ *
+ * Description: The function below stuff the cookies in after the name.
+ ****************************************************************************/
+
+int nfs_readdirrpc(struct nfsmount *nmp, struct nfsnode *np, bool end_of_directory, struct fs_dirent_s *dir)
+{
+ int error = 0;
+ void *datareply = NULL;
+ struct READDIR3args *readir = NULL;
+ struct READDIR3resok *resok = NULL;
+
+ /* Loop around doing readdir rpc's of size nm_readdirsize
+ * truncated to a multiple of NFS_READDIRBLKSIZ.
+ * The stopping criteria is EOF.
+ */
+
+ while (end_of_directory == false)
+ {
+ nfsstats.rpccnt[NFSPROC_READDIR]++;
+ readir->dir = np->n_fhp;
+ readir->count = nmp->nm_readdirsize;
+ if (nfsstats.rpccnt[NFSPROC_READDIR] == 1)
+ {
+ readir->cookie.nfsuquad[0] = 0;
+ readir->cookie.nfsuquad[1] = 0;
+ readir->cookieverf.nfsuquad[0] = 0;
+ readir->cookieverf.nfsuquad[1] = 0;
+ }
+ else
+ {
+ readir->cookie.nfsuquad[0] = dir->u.nfs.cookie[0];
+ readir->cookie.nfsuquad[1] = dir->u.nfs.cookie[1];
+ readir->cookieverf.nfsuquad[0] = np->n_cookieverf.nfsuquad[0];
+ readir->cookieverf.nfsuquad[1] = np->n_cookieverf.nfsuquad[1];
+ }
+
+ error = nfs_request(nmp, NFSPROC_READDIR, readir, datareply);
+
+ if (error)
+ {
+ goto nfsmout;
+ }
+
+ resok = (struct READDIR3resok*) datareply;
+ np->n_fattr = resok->dir_attributes;
+ np->n_cookieverf.nfsuquad[0] = resok->cookieverf.nfsuquad[0];
+ np->n_cookieverf.nfsuquad[1] = resok->cookieverf.nfsuquad[1];
+ dir->fd_dir.d_type = resok->reply.entries->fileid;
+ memcpy(&dir->fd_dir.d_name[NAME_MAX], &resok->reply.entries->name, NAME_MAX);
+ //dir->fd_dir.d_name = resok->reply.entries->name;//
+ dir->u.nfs.cookie[0] = resok->reply.entries->cookie.nfsuquad[0];
+ dir->u.nfs.cookie[1] = resok->reply.entries->cookie.nfsuquad[1];
+
+ if(resok->reply.eof == true)
+ {
+ end_of_directory = true;
+ }
+
+ //more_dirs = fxdr_unsigned(int, *dp);
+
+ /* loop thru the dir entries*/
+/*
+ while (more_dirs && bigenough)
+ {
+ if (bigenough)
+ {
+ if (info_v3)
+ {
+ dir->u.nfs.cookie[0] = cookie.nfsuquad[0];
+ }
+ else
+ {
+ dir->u.nfs.cookie[0] = ndp->cookie[0] = 0;
+ }
+
+ dir->u.nfs.cookie[1] = ndp->cookie[1] = cookie.nfsuquad[1];
+ }
+
+ more_dirs = fxdr_unsigned(int, *ndp);
+ }
+ */
+ }
+
+ /* We are now either at the end of the directory */
+
+ if (resok->reply.entries == NULL)
+ {
+ np->n_direofoffset = fxdr_hyper(&dir->u.nfs.cookie[0]);
+
+ /* We signal the end of the directory by returning the
+ * special error -ENOENT
+ */
+
+ fdbg("End of directory\n");
+ error = -ENOENT;
+ }
+
+nfsmout:
+ return error;
+}
+
+
+/****************************************************************************
* Name: nfs_readdir
*
* Description: Read the next directory entry
@@ -579,8 +686,6 @@ errout_with_semaphore:
static int nfs_readdir(struct inode *mountpt, struct fs_dirent_s *dir)
{
int error = 0;
- unsigned long *cookies = NULL;
- int cnt;
struct nfsmount *nmp;
struct nfsnode *np;
bool eof = false;
@@ -595,7 +700,7 @@ static int nfs_readdir(struct inode *mountpt, struct fs_dirent_s *dir)
/* Recover our private data from the inode instance */
nmp = mountpt->i_private;
- np = np->nm_head;
+ np = nmp->nm_head;
dir->fd_root = mountpt;
/* Make sure that the mount is still healthy */
@@ -614,7 +719,7 @@ static int nfs_readdir(struct inode *mountpt, struct fs_dirent_s *dir)
goto errout_with_semaphore;
}
- dir->u.nfs.nd_direoffset = np->nd_direoffset;
+ dir->u.nfs.nd_direoffset = np->n_direofoffset;
/* First, check for hit on the EOF offset */
@@ -630,7 +735,7 @@ static int nfs_readdir(struct inode *mountpt, struct fs_dirent_s *dir)
(void)nfs_fsinfo(mountpt, NULL, NULL);
}
- error = nfs_readdirrpc(nmp, np, &eof, dir);
+ error = nfs_readdirrpc(nmp, np, eof, dir);
if (error == NFSERR_BAD_COOKIE)
{
@@ -650,173 +755,222 @@ errout_with_semaphore:
}
/****************************************************************************
- * Name: nfs_readdirrpc
- *
- * Description: The function below stuff the cookies in after the name.
+ * Name: nfs_decode_args
****************************************************************************/
-static int nfs_readdirrpc(struct nfsmount *nmp, struct nfsnode *np, bool *end_of_directory, fs_dirent_s *dir)
+void nfs_decode_args(struct nfsmount *nmp, struct nfs_args *argp)
{
- int error = 0;
- void *datareply;
- struct READDIR3args *readdir;
- struct READDIR3resok *resok;
+ int adjsock = 0;
+ int maxio;
- /* Loop around doing readdir rpc's of size nm_readdirsize
- * truncated to a multiple of NFS_READDIRBLKSIZ.
- * The stopping criteria is EOF.
- */
+#ifdef CONFIG_NFS_TCPIP
+ /* Re-bind if rsrvd port requested and wasn't on one */
- while (end_of_directory == false)
+ adjsock = !(nmp->nm_flag & NFSMNT_RESVPORT)
+ && (argp->flags & NFSMNT_RESVPORT);
+#endif
+
+ /* Also re-bind if we're switching to/from a connected UDP socket */
+
+ adjsock |= ((nmp->nm_flag & NFSMNT_NOCONN) != (argp->flags & NFSMNT_NOCONN));
+
+ /* Update flags atomically. Don't change the lock bits. */
+
+ nmp->nm_flag =
+ (argp->flags & ~NFSMNT_INTERNAL) | (nmp->nm_flag & NFSMNT_INTERNAL);
+
+ if ((argp->flags & NFSMNT_TIMEO) && argp->timeo > 0)
{
- nfsstats.rpccnt[NFSPROC_READDIR]++;
- readdir->dir = np->n_fhp;
- readdir->count = nmp->nm_readdirsiz;
- if (nfsstats.rpccnt[NFSPROC_READDIR] == 1)
+ nmp->nm_timeo = (argp->timeo * NFS_HZ + 5) / 10;
+ if (nmp->nm_timeo < NFS_MINTIMEO)
{
- readdir->cookie.nfsuquad[0] = 0;
- readdir->cookie.nfsuquad[1] = 0;
- readdir->cookieverf.nfsuquad[0] = 0;
- readdir->cookieverf.nfsuquad[1] = 0;
+ nmp->nm_timeo = NFS_MINTIMEO;
}
- else
+ else if (nmp->nm_timeo > NFS_MAXTIMEO)
{
- readdir->cookie.nfsuquad[0] = dir->u.nfs.cookie[0];
- readdir->cookie.nfsuquad[1] = dir->u.nfs.cookie[1];
- readdir->cookieverf.nfsuquad[0] = np->n_cookieverf.nfsuquad[0];
- readdir->cookieverf.nfsuquad[1] = np->n_cookieverf.nfsuquad[1];
+ nmp->nm_timeo = NFS_MAXTIMEO;
}
+ }
- error = nfs_request(nmp, NFSPROC_READDIR, readdir, datareply);
+ if ((argp->flags & NFSMNT_RETRANS) && argp->retrans > 1)
+ {
+ nmp->nm_retry = (argp->retrans < NFS_MAXREXMIT)? argp->retrans : NFS_MAXREXMIT;
+ }
- if (error)
+ if (!(nmp->nm_flag & NFSMNT_SOFT))
+ {
+ nmp->nm_retry = NFS_MAXREXMIT + 1; /* past clip limit */
+ }
+
+ if (argp->flags & NFSMNT_NFSV3)
+ {
+ if (argp->sotype == SOCK_DGRAM)
{
- goto nfsmout;
+ maxio = NFS_MAXDGRAMDATA;
}
+ else
+ {
+ maxio = NFS_MAXDATA;
+ }
+ }
+ else
+ {
+ maxio = NFS_V2MAXDATA;
+ }
- resok = (void READDIR3resok*) datareply;
- np->n_fattr = resok->dir_attributes;
- np->nd_cookieverf.nfsuquad[0] = resok->cookieverf.nfsuquad[0];
- np->nd_cookieverf.nfsuquad[1] = resok->cookieverf.nfsuquad[1];
- dir->fd_dir->d_type = resok->reply->entries->fileid;
- dir->fd_dir->d_name = resok->reply->entries->name;
- dir->u.nfs.cookie[0] = resok->reply->entries->cookie.nfsuquad[0];
- dir->u.nfs.cookie[1] = resok->reply->entries->cookie.nfsuquad[1];
-
- if(resok->reply->eof == true)
- {
- end_of_directory = true;
- }
+ if ((argp->flags & NFSMNT_WSIZE) && argp->wsize > 0)
+ {
+ int osize = nmp->nm_wsize;
+ nmp->nm_wsize = argp->wsize;
- //more_dirs = fxdr_unsigned(int, *dp);
+ /* Round down to multiple of blocksize */
- /* loop thru the dir entries*/
-/*
- while (more_dirs && bigenough)
+ nmp->nm_wsize &= ~(NFS_FABLKSIZE - 1);
+ if (nmp->nm_wsize <= 0)
{
- if (bigenough)
- {
- if (info_v3)
- {
- dir->u.nfs.cookie[0] = cookie.nfsuquad[0];
- }
- else
- {
- dir->u.nfs.cookie[0] = ndp->cookie[0] = 0;
- }
+ nmp->nm_wsize = NFS_FABLKSIZE;
+ }
- dir->u.nfs.cookie[1] = ndp->cookie[1] = cookie.nfsuquad[1];
- }
+ adjsock |= (nmp->nm_wsize != osize);
+ }
- more_dirs = fxdr_unsigned(int, *ndp);
- }
- */
+ if (nmp->nm_wsize > maxio)
+ {
+ nmp->nm_wsize = maxio;
}
- /* We are now either at the end of the directory */
+ if (nmp->nm_wsize > MAXBSIZE)
+ {
+ nmp->nm_wsize = MAXBSIZE;
+ }
- if (resok->reply->entries == NULL)
+ if ((argp->flags & NFSMNT_RSIZE) && argp->rsize > 0)
{
- np->n_direofoffset = fxdr_hyper(&dir->u.nfs.cookie[0]);
+ int osize = nmp->nm_rsize;
+ nmp->nm_rsize = argp->rsize;
- /* We signal the end of the directory by returning the
- * special error -ENOENT
- */
+ /* Round down to multiple of blocksize */
- fdbg("End of directory\n");
- error = -ENOENT;
+ nmp->nm_rsize &= ~(NFS_FABLKSIZE - 1);
+ if (nmp->nm_rsize <= 0)
+ {
+ nmp->nm_rsize = NFS_FABLKSIZE;
+ }
+
+ adjsock |= (nmp->nm_rsize != osize);
}
-nfsmout:
- return error;
-}
+ if (nmp->nm_rsize > maxio)
+ {
+ nmp->nm_rsize = maxio;
+ }
-/****************************************************************************
- * Name: nfs_mount
- *
- * Description: This implements a portion of the mount operation. This
- * function allocates and initializes the mountpoint private data and
- * binds the blockdriver inode to the filesystem private data. The final
- * binding of the private data (containing the blockdriver) to the
- * mountpoint is performed by mount().
- *
- ****************************************************************************/
+ if (nmp->nm_rsize > MAXBSIZE)
+ {
+ nmp->nm_rsize = MAXBSIZE;
+ }
-static int nfs_mount(struct inode *blkdriver, void *data, void **handle)
-{
- int error;
- struct nfs_args args;
- struct sockaddr *nam;
- nfsfh_t nfh[NFSX_V3FHMAX];
+ if ((argp->flags & NFSMNT_READDIRSIZE) && argp->readdirsize > 0)
+ {
+ nmp->nm_readdirsize = argp->readdirsize;
- bcopy(data, &args, sizeof(args.version));
- if (args.version == 3)
+ /* Round down to multiple of blocksize */
+
+ nmp->nm_readdirsize &= ~(NFS_DIRBLKSIZ - 1);
+ if (nmp->nm_readdirsize < NFS_DIRBLKSIZ)
+ {
+ nmp->nm_readdirsize = NFS_DIRBLKSIZ;
+ }
+ }
+ else if (argp->flags & NFSMNT_RSIZE)
{
- bcopy(data, &args, sizeof(struct nfs_args3));
- args.flags &= ~(NFSMNT_INTERNAL | NFSMNT_NOAC);
+ nmp->nm_readdirsize = nmp->nm_rsize;
}
- else if (args.version == NFS_ARGSVERSION)
+
+ if (nmp->nm_readdirsize > maxio)
{
- error = copyin(data, &args, sizeof(struct nfs_args));
- args.flags &= ~NFSMNT_NOAC;
+ nmp->nm_readdirsize = maxio;
}
- else
+
+ if ((argp->flags & NFSMNT_MAXGRPS) && argp->maxgrouplist >= 0 &&
+ argp->maxgrouplist <= NFS_MAXGRPS)
{
- return EPROGMISMATCH;
+ nmp->nm_numgrps = argp->maxgrouplist;
}
- if ((args.flags & (NFSMNT_NFSV3 | NFSMNT_RDIRPLUS)) == NFSMNT_RDIRPLUS)
+ if ((argp->flags & NFSMNT_READAHEAD) && argp->readahead >= 0 &&
+ argp->readahead <= NFS_MAXRAHEAD)
{
- return EINVAL;
+ nmp->nm_readahead = argp->readahead;
}
- if (blkdriver->mnt_flag & MNT_UPDATE)
+ if (argp->flags & NFSMNT_ACREGMIN && argp->acregmin >= 0)
{
- struct nfsmount *nmp = (struct nfsmount*)blkdriver->i_private;
+ if (argp->acregmin > 0xffff)
+ {
+ nmp->nm_acregmin = 0xffff;
+ }
+ else
+ {
+ nmp->nm_acregmin = argp->acregmin;
+ }
+ }
- if (nmp == NULL)
+ if (argp->flags & NFSMNT_ACREGMAX && argp->acregmax >= 0)
+ {
+ if (argp->acregmax > 0xffff)
{
- return EIO;
+ nmp->nm_acregmax = 0xffff;
}
+ else
+ {
+ nmp->nm_acregmax = argp->acregmax;
+ }
+ }
- /* When doing an update, we can't change from or to v3. */
+ if (nmp->nm_acregmin > nmp->nm_acregmax)
+ {
+ nmp->nm_acregmin = nmp->nm_acregmax;
+ }
- args.flags = (args.flags & ~(NFSMNT_NFSV3)) |
- (nmp->nm_flag & (NFSMNT_NFSV3));
- nfs_decode_args(nmp, &args);
- return 0;
+ if (argp->flags & NFSMNT_ACDIRMIN && argp->acdirmin >= 0)
+ {
+ if (argp->acdirmin > 0xffff)
+ {
+ nmp->nm_acdirmin = 0xffff;
+ }
+ else
+ {
+ nmp->nm_acdirmin = argp->acdirmin;
+ }
}
- if (args.fhsize < 0 || args.fhsize > NFSX_V3FHMAX)
+ if (argp->flags & NFSMNT_ACDIRMAX && argp->acdirmax >= 0)
{
- return EINVAL;
+ if (argp->acdirmax > 0xffff)
+ {
+ nmp->nm_acdirmax = 0xffff;
+ }
+ else
+ {
+ nmp->nm_acdirmax = argp->acdirmax;
+ }
}
- bcopy(args.fh, nfh, args.fhsize);
- bcopy(args.addr, nam, sizeof(args.addr));
- args.fh = nfh;
- error = mountnfs(&args, blkdriver, nam);
- return error;
+ if (nmp->nm_acdirmin > nmp->nm_acdirmax)
+ {
+ nmp->nm_acdirmin = nmp->nm_acdirmax;
+ }
+
+ if (nmp->nm_so && adjsock)
+ {
+ nfs_disconnect(nmp);
+ if (nmp->nm_sotype == SOCK_DGRAM)
+ while (nfs_connect(nmp))
+ {
+ nvdbg("nfs_args: retrying connect\n");
+ }
+ }
}
/****************************************************************************
@@ -826,98 +980,87 @@ static int nfs_mount(struct inode *blkdriver, void *data, void **handle)
*
****************************************************************************/
-static int mountnfs(struct nfs_args *argp, struct inode *blkdriver,
+int mountnfs(struct nfs_args *argp, struct inode *blkdriver,
struct sockaddr *nam, void **handle)
{
struct nfsmount *nmp;
int error;
- if (blkdriver->mnt_flag & MNT_UPDATE)
- {
- nmp = (struct nfsmount*)blkdriver->i_private;
-
- /* update paths, file handles, etc, here XXX */
+ /* Open the block driver */
- return 0;
- }
- else
+ if (!blkdriver || !blkdriver->u.i_bops)
{
- /* Open the block driver */
-
- if (!blkdriver || !blkdriver->u.i_bops)
- {
- fdbg("No block driver/ops\n");
- return -ENODEV;
- }
+ fdbg("No block driver/ops\n");
+ return -ENODEV;
+ }
- if (blkdriver->u.i_bops->open &&
- blkdriver->u.i_bops->open(blkdriver) != OK)
- {
- fdbg("No open method\n");
- return -ENODEV;
- }
+ if (blkdriver->u.i_bops->open &&
+ blkdriver->u.i_bops->open(blkdriver) != OK)
+ {
+ fdbg("No open method\n");
+ return -ENODEV;
+ }
- /* Create an instance of the mountpt state structure */
+ /* Create an instance of the mountpt state structure */
- nmp = (struct nfsmount*)zalloc(sizeof(struct nfmount));
- if (!nmp)
- {
- fdbg("Failed to allocate mountpoint structure\n");
- return -ENOMEM;
- }
+ nmp = (struct nfsmount *)kzalloc(sizeof(struct nfsmount));
+ if (!nmp)
+ {
+ fdbg("Failed to allocate mountpoint structure\n");
+ return -ENOMEM;
+ }
- /* Initialize the allocated mountpt state structure. The filesystem is
- * responsible for one reference ont the blkdriver inode and does not
- * have to addref() here (but does have to release in ubind().
- */
+ /* Initialize the allocated mountpt state structure. The filesystem is
+ * responsible for one reference ont the blkdriver inode and does not
+ * have to addref() here (but does have to release in ubind().
+ */
- sem_init(&rm->rm_sem, 0, 0); /* Initialize the semaphore that controls access */
-
- //vfs_getnewfsid(mp);
- nmp->nm_blkdriver = blkdriver; /* Save the block driver reference */
- nmp->nm_timeo = NFS_TIMEO;
- nmp->nm_retry = NFS_RETRANS;
- nmp->nm_wsize = NFS_WSIZE;
- nmp->nm_rsize = NFS_RSIZE;
- nmp->nm_readdirsize = NFS_READDIRSIZE;
- nmp->nm_numgrps = NFS_MAXGRPS;
- nmp->nm_readahead = NFS_DEFRAHEAD;
- nmp->nm_fhsize = argp->fhsize;
- nmp->nm_acregmin = NFS_MINATTRTIMO;
- nmp->nm_acregmax = NFS_MAXATTRTIMO;
- nmp->nm_acdirmin = NFS_MINATTRTIMO;
- nmp->nm_acdirmax = NFS_MAXATTRTIMO;
- memmove(nmp->nm_fh, argp->fh, argp->fhsize);
- //strncpy(&mp->mnt_stat.f_fstypename[0], mp->mnt_vfc->vfc_name, MFSNAMELEN);
- //memmove(hst, mp->mnt_stat.f_mntfromname, MNAMELEN);
- // bcopy(pth, nmp->nm_mntonname, 90);
- //memmove(argp, &mp->mnt_stat.mount_info.nfs_args, sizeof(*argp));
- nmp->nm_nam = nam;
- nfs_decode_args(nmp, argp);
-
- /* Set up the sockets and per-host congestion */
-
- nmp->nm_sotype = argp->sotype;
- nmp->nm_soproto = argp->proto;
-
- /* For Connection based sockets (TCP,...) defer the connect until
- * the first request, in case the server is not responding.
- */
+ sem_init(&nmp->nm_sem, 0, 0); /* Initialize the semaphore that controls access */
+
+//vfs_getnewfsid(mp);
+ nmp->nm_blkdriver = blkdriver; /* Save the block driver reference */
+ nmp->nm_timeo = NFS_TIMEO;
+ nmp->nm_retry = NFS_RETRANS;
+ nmp->nm_wsize = NFS_WSIZE;
+ nmp->nm_rsize = NFS_RSIZE;
+ nmp->nm_readdirsize = NFS_READDIRSIZE;
+ nmp->nm_numgrps = NFS_MAXGRPS;
+ nmp->nm_readahead = NFS_DEFRAHEAD;
+ nmp->nm_fhsize = argp->fhsize;
+ nmp->nm_acregmin = NFS_MINATTRTIMO;
+ nmp->nm_acregmax = NFS_MAXATTRTIMO;
+ nmp->nm_acdirmin = NFS_MINATTRTIMO;
+ nmp->nm_acdirmax = NFS_MAXATTRTIMO;
+ nmp->nm_fh = argp->fh;
+//strncpy(&mp->mnt_stat.f_fstypename[0], mp->mnt_vfc->vfc_name, MFSNAMELEN);
+//memmove(hst, mp->mnt_stat.f_mntfromname, MNAMELEN);
+//bcopy(pth, nmp->nm_mntonname, 90);
+//memmove(argp, &mp->mnt_stat.mount_info.nfs_args, sizeof(*argp));
+ nmp->nm_nam = nam;
+ nfs_decode_args(nmp, argp);
+
+ /* Set up the sockets and per-host congestion */
+
+ nmp->nm_sotype = argp->sotype;
+ nmp->nm_soproto = argp->proto;
+
+ /* For Connection based sockets (TCP,...) defer the connect until
+ * the first request, in case the server is not responding.
+ */
- if (nmp->nm_sotype == SOCK_DGRAM && (error = nfs_connect(nmp)))
- {
- goto bad;
- }
+ if (nmp->nm_sotype == SOCK_DGRAM && (error = nfs_connect(nmp)))
+ {
+ goto bad;
+ }
- /* Mounted! */
+ /* Mounted! */
- nmp->nfs_mounted = true;
- nfs_init();
- *handle = blkdriver->i_private = &nmp;
- nfs_semgive(nmp);
+ nmp->nm_mounted = true;
+ nfs_init();
+ *handle = blkdriver->i_private = &nmp;
+ nfs_semgive(nmp);
- return 0;
- }
+ return 0;
bad:
nfs_disconnect(nmp);
@@ -927,6 +1070,48 @@ bad:
}
/****************************************************************************
+ * Name: nfs_mount
+ *
+ * Description: This implements a portion of the mount operation. This
+ * function allocates and initializes the mountpoint private data and
+ * binds the blockdriver inode to the filesystem private data. The final
+ * binding of the private data (containing the blockdriver) to the
+ * mountpoint is performed by mount().
+ *
+ ****************************************************************************/
+
+static int nfs_mount(struct inode *blkdriver, const void *data, void **handle)
+{
+ int error;
+ struct nfs_args args;
+ struct sockaddr *nam;
+
+ bcopy(data, &args, sizeof(struct nfs_args));
+ if (args.version == NFS_ARGSVERSION)
+ {
+ args.flags &= ~(NFSMNT_INTERNAL | NFSMNT_NOAC);
+ }
+ else
+ {
+ return -EINVAL;
+ }
+
+ if ((args.flags & (NFSMNT_NFSV3 | NFSMNT_RDIRPLUS)) == NFSMNT_RDIRPLUS)
+ {
+ return -EINVAL;
+ }
+
+ if (args.fhsize < 0 || args.fhsize > NFSX_V3FHMAX)
+ {
+ return -EINVAL;
+ }
+
+ nam = args.addr;
+ error = mountnfs(&args, blkdriver, nam, handle);
+ return error;
+}
+
+/****************************************************************************
* Name: nfs_unmount
*
* Description: This implements the filesystem portion of the umount
@@ -934,9 +1119,9 @@ bad:
*
****************************************************************************/
-int nfs_unmount(struct inode *blkdriver, void *handle)
+int nfs_unmount(void *handle, struct inode **blkdriver)
{
- struct nfsmount *nmp = (struct nfsmount*) handle ;
+ struct nfsmount *nmp = (struct nfsmount *) handle ;
int error;
fvdbg("Entry\n");
@@ -946,7 +1131,7 @@ int nfs_unmount(struct inode *blkdriver, void *handle)
return -EINVAL;
}
- nfs_semtake(nmp)
+ nfs_semtake(nmp);
if (nmp->nm_head)
{
/* We cannot unmount now.. there are open files */
@@ -955,7 +1140,7 @@ int nfs_unmount(struct inode *blkdriver, void *handle)
}
else
{
- /* Unmount ... close the block driver */
+ /* Unmount ... close the block driver */
if (nmp->nm_blkdriver)
{
@@ -981,12 +1166,7 @@ int nfs_unmount(struct inode *blkdriver, void *handle)
}
/* Release the mountpoint private data */
-
- if (blkdriver->i_private)
- {
- kfree(blkdriver->nm_buffer);
- }
-
+
nfs_disconnect(nmp);
sem_destroy(&nmp->nm_sem);
kfree(nmp);
@@ -994,8 +1174,8 @@ int nfs_unmount(struct inode *blkdriver, void *handle)
return 0;
}
- nfs_semgive(nmp)
- return 0;
+ nfs_semgive(nmp);
+ return error;
}
/****************************************************************************
@@ -1011,8 +1191,8 @@ static int nfs_statfs(struct inode *mountpt, struct statfs *sbp)
struct nfsmount *nmp;
int error = 0;
uint64_t tquad;
- void *datareply;
- struct FSSTAT3args *fsstat
+ void *datareply = NULL;
+ struct FSSTAT3args *fsstat = NULL;
int info_v3;
/* Sanity checks */
@@ -1053,7 +1233,7 @@ static int nfs_statfs(struct inode *mountpt, struct statfs *sbp)
}
sfp = (struct nfs_statfs *)datareply;
- nmp->nm_head->n_fattr = sfp->obj_attributes
+ nmp->nm_head->n_fattr = sfp->obj_attributes;
if (info_v3)
{
sbp->f_bsize = NFS_FABLKSIZE;
@@ -1062,13 +1242,13 @@ static int nfs_statfs(struct inode *mountpt, struct statfs *sbp)
tquad = fxdr_hyper(&sfp->sf_fbytes);
sbp->f_bfree = tquad / (uint64_t) NFS_FABLKSIZE;
tquad = fxdr_hyper(&sfp->sf_abytes);
- sbp->f_bavail = (quad_t) tquad / (quad_t) NFS_FABLKSIZE;
+ sbp->f_bavail = tquad / (uint64_t) NFS_FABLKSIZE;
tquad = fxdr_hyper(&sfp->sf_tfiles);
sbp->f_files = tquad;
tquad = fxdr_hyper(&sfp->sf_ffiles);
sbp->f_ffree = tquad;
- sbp->f_namelen = MAXNAMLEN;
+ sbp->f_namelen = NAME_MAX;
}
else
{
@@ -1094,11 +1274,11 @@ errout_with_semaphore:
static int nfs_remove(struct inode *mountpt, const char *relpath)
{
- struct nsfmount *nmp;
+ struct nfsmount *nmp;
struct nfsnode *np;
- void *datreply;
- struct REMOVE3args *remove;
- struct REMOVE3resok *resok;
+ void *datareply = NULL;
+ struct REMOVE3args *remove = NULL;
+ struct REMOVE3resok *resok = NULL;
int error = 0;
/* Sanity checks */
@@ -1107,13 +1287,13 @@ static int nfs_remove(struct inode *mountpt, const char *relpath)
/* Get the mountpoint private data from the inode structure */
- nmp = (struct nfsmount *)mountpt->i_private;
+ nmp = (struct nfsmount*)mountpt->i_private;
np = nmp->nm_head;
/* Check if the mount is still healthy */
nfs_semtake(nmp);
- error = fat_checkmount(nmp);
+ error = nfs_checkmount(nmp);
if (error == 0)
{
/* If the file is open, the correct behavior is to remove the file
@@ -1123,7 +1303,7 @@ static int nfs_remove(struct inode *mountpt, const char *relpath)
/* Remove the file */
- if (np->n_type != NFREG)
+ if (np->nfsv3_type != NFREG)
{
error = EPERM;
goto errout_with_semaphore;
@@ -1132,8 +1312,8 @@ static int nfs_remove(struct inode *mountpt, const char *relpath)
/* Do the rpc */
nfsstats.rpccnt[NFSPROC_REMOVE]++;
- remove->object->dir = np->n_fhp;
- remove->object->name = relpath;
+ remove->object.dir = np->n_fhp;
+ remove->object.name = relpath;
error = nfs_request(nmp, NFSPROC_REMOVE, remove, datareply);
@@ -1154,7 +1334,7 @@ static int nfs_remove(struct inode *mountpt, const char *relpath)
}
resok = (struct REMOVE3resok *)datareply;
- np->n_fattr = resok->dir_wcc->after;
+ np->n_fattr = resok->dir_wcc.after;
np->n_flag |= NMODIFIED;
}
NFS_INVALIDATE_ATTRCACHE(np);
@@ -1173,14 +1353,13 @@ errout_with_semaphore:
static int nfs_mkdir(struct inode *mountpt, const char *relpath, mode_t mode)
{
- struct nfsv3_sattr *vap;
- struct nfsv3_sattr *sp;
+ struct nfs_fattr vap;
+ struct nfsv3_sattr sp;
struct nfsmount *nmp;
struct nfsnode *np;
- struct MKDIR3args *mkdir;
- struct MKDIR3resok *resok;
- void *datareply;
- int len;
+ struct MKDIR3args *mkir = NULL;
+ struct MKDIR3resok *resok = NULL;
+ void *datareply = NULL;
int error = 0;
/* Sanity checks */
@@ -1203,21 +1382,21 @@ static int nfs_mkdir(struct inode *mountpt, const char *relpath, mode_t mode)
}
nfsstats.rpccnt[NFSPROC_MKDIR]++;
- mkdir->where->dir = nmp->nm_fh;
- mkdir->where->name = relpath;
+ mkir->where.dir = nmp->nm_fh;
+ mkir->where.name = relpath;
- sp->sa_modetrue = nfs_true;
- sp->sa_mode = txdr_unsigned(vap->sa_mode);
- sp->sa_uid = nfs_xdrneg1;
- sp->sa_gid = nfs_xdrneg1;
- sp->sa_size = nfs_xdrneg1;
- sp->sa_atimetype = txdr_unsigned(NFSV3SATTRTIME_TOCLIENT);
- sp->sa_mtimetype = txdr_unsigned(NFSV3SATTRTIME_TOCLIENT);
+ sp.sa_modetrue = nfs_true;
+ sp.sa_mode = txdr_unsigned(vap.fa_mode);
+ sp.sa_uidfalse = nfs_xdrneg1;
+ sp.sa_gidfalse = nfs_xdrneg1;
+ sp.sa_sizefalse = nfs_xdrneg1;
+ sp.sa_atimetype = txdr_unsigned(NFSV3SATTRTIME_TOCLIENT);
+ sp.sa_mtimetype = txdr_unsigned(NFSV3SATTRTIME_TOCLIENT);
- txdr_nfsv3time(&vap->sa_atime, &sp->sa_atime);
- txdr_nfsv3time(&vap->sa_mtime, &sp->sa_mtime);
+ fxdr_nfsv3time2(&vap.fa3_atime, &sp.sa_atime);
+ fxdr_nfsv3time2(&vap.fa3_mtime, &sp.sa_mtime);
- mkdir->attributes = sp;
+ mkir->attributes = sp;
error = nfs_request(nmp, NFSPROC_MKDIR, mkdir, datareply);
if (error)
@@ -1226,10 +1405,10 @@ static int nfs_mkdir(struct inode *mountpt, const char *relpath, mode_t mode)
}
resok = (struct MKDIR3resok *) datareply;
- np->nfsv3_type = NDIR;
+ np->nfsv3_type = NFDIR;
np->n_fhp = resok->handle;
np->n_fattr = resok->obj_attributes;
- nmp->n_flag |= NMODIFIED;
+ np->n_flag |= NMODIFIED;
NFS_INVALIDATE_ATTRCACHE(np);
errout_with_semaphore:
@@ -1248,9 +1427,9 @@ 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 RMDIR3args *rmdir = NULL;
+ struct RMDIR3resok *resok = NULL;
+ void *datareply = NULL;
int error = 0;
/* Sanity checks */
@@ -1265,12 +1444,12 @@ static int nfs_rmdir(struct inode *mountpt, const char *relpath)
/* Check if the mount is still healthy */
nfs_semtake(nmp);
- error = fat_checkmount(nmp);
+ error = nfs_checkmount(nmp);
if (error == 0)
{
/* Remove the directory */
- if (np->n_type != NDIR)
+ if (np->nfsv3_type != NFDIR)
{
error = EPERM;
goto errout_with_semaphore;
@@ -1279,9 +1458,9 @@ static int nfs_rmdir(struct inode *mountpt, const char *relpath)
/* Do the rpc */
nfsstats.rpccnt[NFSPROC_RMDIR]++;
- rmdir->object->dir = np->n_fhp;
- rmdir->object->name = relpath;
- error = nfs_request(dvp, NFSPROC_RMDIR, rmdir, datareply);
+ rmdir->object.dir = np->n_fhp;
+ rmdir->object.name = relpath;
+ error = nfs_request(nmp, NFSPROC_RMDIR, rmdir, datareply);
if (error == ENOENT)
{
@@ -1293,8 +1472,8 @@ static int nfs_rmdir(struct inode *mountpt, const char *relpath)
goto errout_with_semaphore;
}
- resok = (struct REMOVE3resok *)datareply;
- np->n_fattr = resok->dir_wcc->after;
+ resok = (struct RMDIR3resok *)datareply;
+ np->n_fattr = resok->dir_wcc.after;
np->n_flag |= NMODIFIED;
}
NFS_INVALIDATE_ATTRCACHE(np);
@@ -1314,11 +1493,11 @@ errout_with_semaphore:
static int nfs_rename(struct inode *mountpt, const char *oldrelpath,
const char *newrelpath)
{
- struct nsfmount *nmp;
+ struct nfsmount *nmp;
struct nfsnode *np;
- void *datreply;
- struct RENAME3args *rename;
- struct RENAME3resok *resok;
+ void *datareply = NULL;
+ struct RENAME3args *rename = NULL;
+ struct RENAME3resok *resok = NULL;
int error = 0;
/* Sanity checks */
@@ -1347,12 +1526,12 @@ static int nfs_rename(struct inode *mountpt, const char *oldrelpath,
}
nfsstats.rpccnt[NFSPROC_RENAME]++;
- rename->from->dir = np->n_fhp;
- rename->from->name = oldrelpath;
- rename->to->dir = np->n_fhp;
- rename->to->name = newrelpath;
+ rename->from.dir = np->n_fhp;
+ rename->from.name = oldrelpath;
+ rename->to.dir = np->n_fhp;
+ rename->to.name = newrelpath;
- error = nfs_request(fdvp, NFSPROC_RENAME, rename, datareply);
+ error = nfs_request(nmp, NFSPROC_RENAME, rename, datareply);
/* Kludge: Map ENOENT => 0 assuming that it is a reply to a retry. */
@@ -1367,7 +1546,7 @@ static int nfs_rename(struct inode *mountpt, const char *oldrelpath,
}
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);
@@ -1386,11 +1565,11 @@ errout_with_semaphore:
static int nfs_fsinfo(struct inode *mountpt, const char *relpath, struct stat *buf)
{
struct nfsv3_fsinfo *fsp;
- struct FSINFOargs *fsinfo;
+ struct FSINFOargs *fsinfo = NULL;
struct nfsmount *nmp;
uint32_t pref, max;
int error = 0;
- void *datareply;
+ void *datareply = NULL;
/* Sanity checks */
@@ -1403,7 +1582,7 @@ static int nfs_fsinfo(struct inode *mountpt, const char *relpath, struct stat *b
/* Check if the mount is still healthy */
nfs_semtake(nmp);
- error = nfd_checkmount(nmp);
+ error = nfs_checkmount(nmp);
if (error != 0)
{
goto errout_with_semaphore;
@@ -1415,7 +1594,7 @@ static int nfs_fsinfo(struct inode *mountpt, const char *relpath, struct stat *b
error = nfs_request(nmp, NFSPROC_FSINFO, fsinfo, datareply);
if (error)
{
- goto errout_with_semaphoret;
+ goto errout_with_semaphore;
}
fsp = (struct nfsv3_fsinfo *)datareply;
@@ -1465,13 +1644,13 @@ static int nfs_fsinfo(struct inode *mountpt, const char *relpath, struct stat *b
}
}
- buf->st_mode = fxdr_hyper(&fsp->obj_attributes->fa_mode);
- buf->st_size = fxdr_hyper(&fsp->obj_attributes->fa3_size);
+ buf->st_mode = fxdr_hyper(&fsp->obj_attributes.fa_mode);
+ buf->st_size = fxdr_hyper(&fsp->obj_attributes.fa3_size);
buf->st_blksize = 0;
buf->st_blocks = 0;
- buf->st_mtime = fxdr_hyper(&fsp->obj_attributes->fa3_mtime);
- buf->st_atime = fxdr_hyper(&fsp->obj_attributes->fa3_atime);
- buf->st_ctime = fxdr_hyper(&fsp->obj_attributes->fa3_ctime);
+ buf->st_mtime = fxdr_hyper(&fsp->obj_attributes.fa3_mtime);
+ buf->st_atime = fxdr_hyper(&fsp->obj_attributes.fa3_atime);
+ buf->st_ctime = fxdr_hyper(&fsp->obj_attributes.fa3_ctime);
nmp->nm_flag |= NFSMNT_GOTFSINFO;
errout_with_semaphore:
@@ -1479,226 +1658,7 @@ errout_with_semaphore:
return error;
}
-/****************************************************************************
- * Name: nfs_decode_args
- ****************************************************************************/
-
-void nfs_decode_args(struct nfsmount *nmp, struct nfs_args *argp)
-{
- int adjsock = 0;
- int maxio;
-
-#ifdef CONFIG_NFS_TCPIP
- /* Re-bind if rsrvd port requested and wasn't on one */
-
- adjsock = !(nmp->nm_flag & NFSMNT_RESVPORT)
- && (argp->flags & NFSMNT_RESVPORT);
-#endif
-
- /* Also re-bind if we're switching to/from a connected UDP socket */
-
- adjsock |= ((nmp->nm_flag & NFSMNT_NOCONN) != (argp->flags & NFSMNT_NOCONN));
-
- /* Update flags atomically. Don't change the lock bits. */
-
- nmp->nm_flag =
- (argp->flags & ~NFSMNT_INTERNAL) | (nmp->nm_flag & NFSMNT_INTERNAL);
-
- if ((argp->flags & NFSMNT_TIMEO) && argp->timeo > 0)
- {
- nmp->nm_timeo = (argp->timeo * NFS_HZ + 5) / 10;
- if (nmp->nm_timeo < NFS_MINTIMEO)
- {
- nmp->nm_timeo = NFS_MINTIMEO;
- }
- else if (nmp->nm_timeo > NFS_MAXTIMEO)
- {
- nmp->nm_timeo = NFS_MAXTIMEO;
- }
- }
-
- if ((argp->flags & NFSMNT_RETRANS) && argp->retrans > 1)
- {
- nmp->nm_retry = MIN(argp->retrans, NFS_MAXREXMIT);
- }
-
- if (!(nmp->nm_flag & NFSMNT_SOFT))
- {
- nmp->nm_retry = NFS_MAXREXMIT + 1; /* past clip limit */
- }
-
- if (argp->flags & NFSMNT_NFSV3)
- {
- if (argp->sotype == SOCK_DGRAM)
- {
- maxio = NFS_MAXDGRAMDATA;
- }
- else
- {
- maxio = NFS_MAXDATA;
- }
- }
- else
- {
- maxio = NFS_V2MAXDATA;
- }
-
- if ((argp->flags & NFSMNT_WSIZE) && argp->wsize > 0)
- {
- int osize = nmp->nm_wsize;
- nmp->nm_wsize = argp->wsize;
-
- /* Round down to multiple of blocksize */
-
- nmp->nm_wsize &= ~(NFS_FABLKSIZE - 1);
- if (nmp->nm_wsize <= 0)
- {
- nmp->nm_wsize = NFS_FABLKSIZE;
- }
-
- adjsock |= (nmp->nm_wsize != osize);
- }
-
- if (nmp->nm_wsize > maxio)
- {
- nmp->nm_wsize = maxio;
- }
-
- if (nmp->nm_wsize > MAXBSIZE)
- {
- nmp->nm_wsize = MAXBSIZE;
- }
-
- if ((argp->flags & NFSMNT_RSIZE) && argp->rsize > 0)
- {
- int osize = nmp->nm_rsize;
- nmp->nm_rsize = argp->rsize;
-
- /* Round down to multiple of blocksize */
-
- nmp->nm_rsize &= ~(NFS_FABLKSIZE - 1);
- if (nmp->nm_rsize <= 0)
- {
- nmp->nm_rsize = NFS_FABLKSIZE;
- }
-
- adjsock |= (nmp->nm_rsize != osize);
- }
-
- if (nmp->nm_rsize > maxio)
- {
- nmp->nm_rsize = maxio;
- }
-
- if (nmp->nm_rsize > MAXBSIZE)
- {
- nmp->nm_rsize = MAXBSIZE;
- }
-
- if ((argp->flags & NFSMNT_READDIRSIZE) && argp->readdirsize > 0)
- {
- nmp->nm_readdirsize = argp->readdirsize;
-
- /* Round down to multiple of blocksize */
-
- nmp->nm_readdirsize &= ~(NFS_DIRBLKSIZ - 1);
- if (nmp->nm_readdirsize < NFS_DIRBLKSIZ)
- {
- nmp->nm_readdirsize = NFS_DIRBLKSIZ;
- }
- }
- else if (argp->flags & NFSMNT_RSIZE)
- {
- nmp->nm_readdirsize = nmp->nm_rsize;
- }
-
- if (nmp->nm_readdirsize > maxio)
- {
- nmp->nm_readdirsize = maxio;
- }
-
- if ((argp->flags & NFSMNT_MAXGRPS) && argp->maxgrouplist >= 0 &&
- argp->maxgrouplist <= NFS_MAXGRPS)
- {
- nmp->nm_numgrps = argp->maxgrouplist;
- }
-
- if ((argp->flags & NFSMNT_READAHEAD) && argp->readahead >= 0 &&
- argp->readahead <= NFS_MAXRAHEAD)
- {
- nmp->nm_readahead = argp->readahead;
- }
-
- if (argp->flags & NFSMNT_ACREGMIN && argp->acregmin >= 0)
- {
- if (argp->acregmin > 0xffff)
- {
- nmp->nm_acregmin = 0xffff;
- }
- else
- {
- nmp->nm_acregmin = argp->acregmin;
- }
- }
-
- if (argp->flags & NFSMNT_ACREGMAX && argp->acregmax >= 0)
- {
- if (argp->acregmax > 0xffff)
- {
- nmp->nm_acregmax = 0xffff;
- }
- else
- {
- nmp->nm_acregmax = argp->acregmax;
- }
- }
-
- if (nmp->nm_acregmin > nmp->nm_acregmax)
- {
- nmp->nm_acregmin = nmp->nm_acregmax;
- }
-
- if (argp->flags & NFSMNT_ACDIRMIN && argp->acdirmin >= 0)
- {
- if (argp->acdirmin > 0xffff)
- {
- nmp->nm_acdirmin = 0xffff;
- }
- else
- {
- nmp->nm_acdirmin = argp->acdirmin;
- }
- }
-
- if (argp->flags & NFSMNT_ACDIRMAX && argp->acdirmax >= 0)
- {
- if (argp->acdirmax > 0xffff)
- {
- nmp->nm_acdirmax = 0xffff;
- }
- else
- {
- nmp->nm_acdirmax = argp->acdirmax;
- }
- }
-
- if (nmp->nm_acdirmin > nmp->nm_acdirmax)
- {
- nmp->nm_acdirmin = nmp->nm_acdirmax;
- }
-
- if (nmp->nm_so && adjsock)
- {
- nfs_disconnect(nmp);
- if (nmp->nm_sotype == SOCK_DGRAM)
- while (nfs_connect(nmp))
- {
- nvdbg("nfs_args: retrying connect\n");
- }
- }
-}
-
-#ifdef 0
+#ifdef COMP
/****************************************************************************
* Name: nfs_sync
*