summaryrefslogtreecommitdiff
path: root/nuttx/fs/nfs
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-03-22 00:51:01 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-03-22 00:51:01 +0000
commit0c7804b74dcec7d746e95425157bd6afc1435de6 (patch)
treef1012156c3adfa9214f97d33ca5c8e0fea1402fd /nuttx/fs/nfs
parent68d6dcf76ee0aa13cd6dd0d6f9b07f2d8fdf64d4 (diff)
downloadpx4-nuttx-0c7804b74dcec7d746e95425157bd6afc1435de6.tar.gz
px4-nuttx-0c7804b74dcec7d746e95425157bd6afc1435de6.tar.bz2
px4-nuttx-0c7804b74dcec7d746e95425157bd6afc1435de6.zip
NFS update + make some examples configurable as NSH built-ins
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4501 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/fs/nfs')
-rw-r--r--nuttx/fs/nfs/Make.defs2
-rw-r--r--nuttx/fs/nfs/nfs.h273
-rw-r--r--nuttx/fs/nfs/nfs_args.h145
-rw-r--r--nuttx/fs/nfs/nfs_mount.h (renamed from nuttx/fs/nfs/nfsmount.h)95
-rw-r--r--nuttx/fs/nfs/nfs_node.h157
-rw-r--r--nuttx/fs/nfs/nfs_proto.h75
-rw-r--r--nuttx/fs/nfs/nfs_socket.c166
-rw-r--r--nuttx/fs/nfs/nfs_socket.h72
-rw-r--r--nuttx/fs/nfs/nfs_vfsops.c927
-rw-r--r--nuttx/fs/nfs/nfs_vnops.c3035
-rw-r--r--nuttx/fs/nfs/rpc.h53
-rw-r--r--nuttx/fs/nfs/rpc_clnt.c931
-rw-r--r--nuttx/fs/nfs/rpc_clnt_private.h45
-rw-r--r--nuttx/fs/nfs/rpc_types.h28
14 files changed, 5180 insertions, 824 deletions
diff --git a/nuttx/fs/nfs/Make.defs b/nuttx/fs/nfs/Make.defs
index be633c1fa..915d6bb9c 100644
--- a/nuttx/fs/nfs/Make.defs
+++ b/nuttx/fs/nfs/Make.defs
@@ -42,7 +42,7 @@ CSRCS +=
# Files required for NFS RPC
ASRCS +=
-CSRCS += rpc_clnt.c
+CSRCS += rpc_clnt.c nfs_socket.c
# Argument for dependency checking
diff --git a/nuttx/fs/nfs/nfs.h b/nuttx/fs/nfs/nfs.h
index a5092e07a..f3d6bb403 100644
--- a/nuttx/fs/nfs/nfs.h
+++ b/nuttx/fs/nfs/nfs.h
@@ -1,6 +1,14 @@
-/*
- * Copyright (c) 1989, 1993, 1995
- * The Regents of the University of California. All rights reserved.
+/****************************************************************************
+ * fs/nfs/nfs.h
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012 Jose Pablo Rojas Vargas. All rights reserved.
+ * Author: Jose Pablo Rojas Vargas <jrojas@nx-engineering.com>
+ *
+ * Leveraged from OpenBSD:
+ *
+ * Copyright (c) 1989, 1993, 1995
+ * 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.
@@ -30,11 +38,18 @@
* OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
* SUCH DAMAGE.
*
- * @(#)nfs.h 8.4 (Berkeley) 5/1/95
- */
+ ****************************************************************************/
+
+#ifndef __FS_NFS_NFS_H
+#define __FS_NFS_NFS_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
-#ifndef _NFS_NFS_H_
-#define _NFS_NFS_H_
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
#define NFS_TICKINTVL 5 /* Desired time for a tick (msec) */
#define NFS_HZ (CLOCKS_PER_SEC / nfs_ticks) /* Ticks/sec */
@@ -62,9 +77,7 @@
#define NFS_DIRBLKSIZ 1024 /* Must be a multiple of DIRBLKSIZ */
#define NFS_READDIRBLKSIZ 512 /* Size of read dir blocks. XXX */
-/*
- * Oddballs
- */
+/* Oddballs */
#define NFS_CMPFH(n, f, s) \
((n)->n_fhsize == (s) && !bcmp((void *)(n)->n_fhp, (void *)(f), (s)))
@@ -73,9 +86,7 @@
(((n)->nd_flag & ND_NFSV3) ? (((n)->nd_nam2) ? \
NFS_MAXDGRAMDATA : NFS_MAXDATA) : NFS_V2MAXDATA)
-/*
- * sys/malloc.h needs M_NFSDIROFF, M_NFSRVDESC and M_NFSBIGFH added.
- */
+/* sys/malloc.h needs M_NFSDIROFF, M_NFSRVDESC and M_NFSBIGFH added. */
#ifndef M_NFSRVDESC
# define M_NFSRVDESC M_TEMP
@@ -87,15 +98,104 @@
# define M_NFSBIGFH M_TEMP
#endif
-/*
- * The B_INVAFTERWRITE flag should be set to whatever is required by the
+/*The B_INVAFTERWRITE flag should be set to whatever is required by the
* buffer cache code to say "Invalidate the block after it is written back".
*/
#define B_INVAFTERWRITE B_INVAL
+/* Flags for nfssvc() system call. */
+
+#define NFSSVC_BIOD 0x002
+#define NFSSVC_NFSD 0x004
+#define NFSSVC_ADDSOCK 0x008
+#define NFSSVC_AUTHIN 0x010
+#define NFSSVC_GOTAUTH 0x040
+#define NFSSVC_AUTHINFAIL 0x080
+#define NFSSVC_MNTD 0x100
+
+/* fs.nfs sysctl(3) identifiers */
+
+#define NFS_NFSSTATS 1 /* struct: struct nfsstats */
+#define NFS_NIOTHREADS 2 /* number of i/o threads */
+#define NFS_MAXID 3
+
+#define FS_NFS_NAMES { \
+ { 0, 0 }, \
+ { "nfsstats", CTLTYPE_STRUCT }, \
+ { "iothreads", CTLTYPE_INT } \
+}
+
+#define NFSINT_SIGMASK (sigmask(SIGINT)|sigmask(SIGTERM)|sigmask(SIGKILL)| \
+ sigmask(SIGHUP)|sigmask(SIGQUIT))
+
/*
- * Structures for the nfssvc(2) syscall.
+ * Socket errors ignored for connectionless sockets??
+ * For now, ignore them all
+ */
+
+#define NFSIGNORE_SOERROR(s, e) \
+ ((e) != EINTR && (e) != ERESTART && (e) != EWOULDBLOCK && \
+ ((s) & PR_CONNREQUIRED) == 0)
+
+/* Flag values for r_flags */
+
+#define R_TIMING 0x01/* timing request (in mntp) */
+#define R_SENT 0x02/* request has been sent */
+#define R_SOFTTERM 0x04/* soft mnt, too many retries */
+#define R_INTR 0x08/* intr mnt, signal pending */
+#define R_SOCKERR 0x10/* Fatal error on socket */
+#define R_TPRINTFMSG 0x20/* Did a tprintf msg. */
+#define R_MUSTRESEND 0x40/* Must resend request */
+
+/* On fast networks, the estimator will try to reduce the
+ * timeout lower than the latency of the server's disks,
+ * which results in too many timeouts, so cap the lower
+ * bound.
+ */
+
+#define NFS_MINRTO (NFS_HZ >> 2)
+
+/* Keep the RTO from increasing to unreasonably large values
+ * when a server is not responding.
+ */
+
+#define NFS_MAXRTO (20 * NFS_HZ)
+
+#define NFS_MAX_TIMER (NFS_WRITE_TIMER)
+#define NFS_INITRTT (NFS_HZ << 3)
+
+/* Bits for "ns_flag" */
+
+#define SLP_VALID 0x01/* connection is usable */
+#define SLP_DOREC 0x02/* receive operation required */
+#define SLP_NEEDQ 0x04/* connection has data to queue from socket */
+#define SLP_DISCONN 0x08/* connection is closed */
+#define SLP_GETSTREAM 0x10/* extracting RPC from TCP connection */
+#define SLP_LASTFRAG 0x20/* last fragment received on TCP connection */
+#define SLP_ALLFLAGS 0xff/* convenience */
+
+#define SLP_INIT 0x01/* NFS data undergoing initialization */
+#define SLP_WANTINIT 0x02/* thread waiting on NFS initialization */
+
+/* Bits for "nfsd_flag" */
+
+#define NFSD_WAITING 0x01
+#define NFSD_REQINPROG 0x02
+#define NFSD_NEEDAUTH 0x04
+#define NFSD_AUTHFAIL 0x08
+
+/* Bits for "nd_flag" */
+
+#define ND_NFSV3 0x08
+
+#define NFSD_CHECKSLP 0x01
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/* Structures for the nfssvc(2) syscall.
* Not that anyone besides nfsd(8) should ever use it.
*/
@@ -119,9 +219,7 @@ struct nfsd_srvargs
uint32_t nsd_ttl; /* credential ttl (sec) */
};
-/*
- * Stats structure
- */
+/* Stats structure */
struct nfsstats
{
@@ -161,34 +259,11 @@ struct nfsstats
uint64_t srvvop_writes;
};
-/*
- * Flags for nfssvc() system call.
- */
-
-#define NFSSVC_BIOD 0x002
-#define NFSSVC_NFSD 0x004
-#define NFSSVC_ADDSOCK 0x008
-#define NFSSVC_AUTHIN 0x010
-#define NFSSVC_GOTAUTH 0x040
-#define NFSSVC_AUTHINFAIL 0x080
-#define NFSSVC_MNTD 0x100
-
-/*
- * fs.nfs sysctl(3) identifiers
- */
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
-#define NFS_NFSSTATS 1 /* struct: struct nfsstats */
-#define NFS_NIOTHREADS 2 /* number of i/o threads */
-#define NFS_MAXID 3
-
-#define FS_NFS_NAMES { \
- { 0, 0 }, \
- { "nfsstats", CTLTYPE_STRUCT }, \
- { "iothreads", CTLTYPE_INT } \
-}
-
-/*
- * The set of signals the interrupt an I/O in progress for NFSMNT_INT mounts.
+/* The set of signals the interrupt an I/O in progress for NFSMNT_INT mounts.
* What should be in this set is open to debate, but I believe that since
* I/O system calls on ufs are never interrupted by signals the set should
* be minimal. My reasoning is that many current programs that use signals
@@ -196,34 +271,16 @@ struct nfsstats
* by them and break.
*/
-#ifdef _KERNEL
-extern int nfs_niothreads;
-
struct uio;
struct buf;
struct vattr;
struct nameidata; /* XXX */
-#define NFSINT_SIGMASK (sigmask(SIGINT)|sigmask(SIGTERM)|sigmask(SIGKILL)| \
- sigmask(SIGHUP)|sigmask(SIGQUIT))
-
-/*
- * Socket errors ignored for connectionless sockets??
- * For now, ignore them all
- */
-
-#define NFSIGNORE_SOERROR(s, e) \
- ((e) != EINTR && (e) != ERESTART && (e) != EWOULDBLOCK && \
- ((s) & PR_CONNREQUIRED) == 0)
-
-/*
- * Nfs outstanding request list element
- */
+/* Nfs outstanding request list element */
struct nfsreq
{
dq_entry_t r_chain;
- void *r_dpos;
struct nfsmount *r_nmp;
uint32_t r_xid;
int r_flags; /* flags on request, see below */
@@ -233,31 +290,6 @@ struct nfsreq
int r_rtt; /* RTT for rpc */
};
-/* Flag values for r_flags */
-
-#define R_TIMING 0x01/* timing request (in mntp) */
-#define R_SENT 0x02/* request has been sent */
-#define R_SOFTTERM 0x04/* soft mnt, too many retries */
-#define R_INTR 0x08/* intr mnt, signal pending */
-#define R_SOCKERR 0x10/* Fatal error on socket */
-#define R_TPRINTFMSG 0x20/* Did a tprintf msg. */
-#define R_MUSTRESEND 0x40/* Must resend request */
-
-/*
- * On fast networks, the estimator will try to reduce the
- * timeout lower than the latency of the server's disks,
- * which results in too many timeouts, so cap the lower
- * bound.
- */
-
-#define NFS_MINRTO (NFS_HZ >> 2)
-
-/*
- * Keep the RTO from increasing to unreasonably large values
- * when a server is not responding.
- */
-#define NFS_MAXRTO (20 * NFS_HZ)
-
enum nfs_rto_timers
{
NFS_DEFAULT_TIMER,
@@ -267,12 +299,7 @@ enum nfs_rto_timers
NFS_WRITE_TIMER,
};
-#define NFS_MAX_TIMER (NFS_WRITE_TIMER)
-#define NFS_INITRTT (NFS_HZ << 3)
-
-/*
- * Network address hash list element
- */
+/* Network address hash list element */
union nethostaddr
{
@@ -285,38 +312,14 @@ struct nfssvc_sock
TAILQ_ENTRY(nfssvc_sock) ns_chain; /* List of all nfssvc_sock's */
struct file *ns_fp; /* fp from the... */
struct socket *ns_so; /* ...socket this struct wraps */
- struct mbuf *ns_nam; /* MT_SONAME of client */
- struct mbuf *ns_raw; /* head of unpeeked mbufs */
- struct mbuf *ns_rawend; /* tail of unpeeked mbufs */
- struct mbuf *ns_rec; /* queued RPC records */
- struct mbuf *ns_recend; /* last queued RPC record */
- struct mbuf *ns_frag; /* end of record fragment */
int ns_flag; /* socket status flags */
int ns_solock; /* lock for connected socket */
int ns_cc; /* actual chars queued */
int ns_reclen; /* length of first queued record */
- u_int32_t ns_sref; /* # of refs to this struct */
+ uint32_t ns_sref; /* # of refs to this struct */
};
-/* Bits for "ns_flag" */
-
-#define SLP_VALID 0x01/* connection is usable */
-#define SLP_DOREC 0x02/* receive operation required */
-#define SLP_NEEDQ 0x04/* connection has data to queue from socket */
-#define SLP_DISCONN 0x08/* connection is closed */
-#define SLP_GETSTREAM 0x10/* extracting RPC from TCP connection */
-#define SLP_LASTFRAG 0x20/* last fragment received on TCP connection */
-#define SLP_ALLFLAGS 0xff/* convenience */
-
-extern TAILQ_HEAD(nfssvc_sockhead, nfssvc_sock) nfssvc_sockhead;
-extern int nfssvc_sockhead_flag;
-
-#define SLP_INIT 0x01/* NFS data undergoing initialization */
-#define SLP_WANTINIT 0x02/* thread waiting on NFS initialization */
-
-/*
- * One of these structures is allocated for each nfsd.
- */
+/* One of these structures is allocated for each nfsd. */
struct nfsd
{
@@ -326,35 +329,31 @@ struct nfsd
struct nfsrv_descript *nfsd_nd; /* Associated nfsrv_descript */
};
-/* Bits for "nfsd_flag" */
-
-#define NFSD_WAITING 0x01
-#define NFSD_REQINPROG 0x02
-#define NFSD_NEEDAUTH 0x04
-#define NFSD_AUTHFAIL 0x08
-
-/*
- * This structure is used by the server for describing each request.
- */
+/* This structure is used by the server for describing each request. */
struct nfsrv_descript
{
unsigned int nd_procnum; /* RPC # */
int nd_flag; /* nd_flag */
int nd_repstat; /* Reply status */
- u_int32_t nd_retxid; /* Reply xid */
+ uint32_t nd_retxid; /* Reply xid */
};
-/* Bits for "nd_flag" */
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
-#define ND_NFSV3 0x08
+extern int nfs_niothreads;
+extern TAILQ_HEAD(nfssvc_sockhead, nfssvc_sock) nfssvc_sockhead;
+extern int nfssvc_sockhead_flag;
extern struct pool nfsreqpl;
extern struct pool nfs_node_pool;
extern TAILQ_HEAD(nfsdhead, nfsd) nfsd_head;
extern int nfsd_head_flag;
-#define NFSD_CHECKSLP 0x01
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
-#endif /* _KERNEL */
#endif /* _NFS_NFS_H */
diff --git a/nuttx/fs/nfs/nfs_args.h b/nuttx/fs/nfs/nfs_args.h
new file mode 100644
index 000000000..ee7d0028c
--- /dev/null
+++ b/nuttx/fs/nfs/nfs_args.h
@@ -0,0 +1,145 @@
+/****************************************************************************
+ * fs/nfs/nfs_args.h
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012 Jose Pablo Rojas Vargas. All rights reserved.
+ * Author: Jose Pablo Rojas Vargas <jrojas@nx-engineering.com>
+ *
+ * Leveraged from OpenBSD:
+ *
+ * Copyright (c) 1989, 1993, 1995
+ * 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.
+ * 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_NFS_ARGS_H
+#define __FS_NFS_NFS_ARGS_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* File identifier */
+
+#define MAXFIDSZ 16
+
+/* 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 */
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+typedef struct
+{
+ int32_t val[2];
+} fsid_t; /* file system id type */
+
+/* File identifier.
+ * These are unique per filesystem on a single machine.
+ */
+
+struct fid
+{
+ unsigned short fid_len; /* length of data in bytes */
+ unsigned short fid_reserved; /* force longword alignment */
+ char fid_data[MAXFIDSZ]; /* data (variable length) */
+};
+
+/* Generic file handle */
+
+struct fhandle
+{
+ fsid_t fh_fsid; /* File system id of mount point */
+ struct fid fh_fid; /* File sys specific id */
+};
+
+typedef struct fhandle fhandle_t;
+
+/* Arguments to mount NFS */
+
+struct nfs_args
+{
+ int version; /* args structure version number */
+ struct sockaddr *addr; /* file server address */
+ int addrlen; /* length of address */
+ int sotype; /* Socket type */
+ int proto; /* and Protocol */
+ unsigned char *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 */
+ int readdirsize; /* readdir size in bytes */
+ int timeo; /* initial timeout in .1 secs */
+ int retrans; /* times to retry send */
+ int maxgrouplist; /* Max. size of group list */
+ int readahead; /* # of blocks to readahead */
+ int leaseterm; /* Term (sec) of lease */
+ int deadthresh; /* Retrans threshold */
+ char *hostname; /* server's name */
+};
+
+#endif /* __FS_NFS_NFS_ARGS_H */
diff --git a/nuttx/fs/nfs/nfsmount.h b/nuttx/fs/nfs/nfs_mount.h
index baa70aa18..77d5744e9 100644
--- a/nuttx/fs/nfs/nfsmount.h
+++ b/nuttx/fs/nfs/nfs_mount.h
@@ -1,6 +1,14 @@
-/*
- * Copyright (c) 1989, 1993
- * The Regents of the University of California. All rights reserved.
+/****************************************************************************
+ * fs/nfs/nfs_mount.h
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012 Jose Pablo Rojas Vargas. All rights reserved.
+ * Author: Jose Pablo Rojas Vargas <jrojas@nx-engineering.com>
+ *
+ * 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.
@@ -29,13 +37,33 @@
* 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_NFS_MOUNT_H
+#define __FS_NFS_NFS_MOUNT_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define NFSOP(nmp, op) (*nmp->nm_nfsops->nn_##op)
+#define NFSHASOP(nmp, op) (nmp->nm_nfsops->nn_##op != NULL)
+#define NFSDAT(nmp, nam) (nmp->nm_nfsops->nn_##nam)
+
+/* Convert mount ptr to nfsmount ptr. */
-#ifndef _NFSCLIENT_NFSMOUNT_H_
-#define _NFSCLIENT_NFSMOUNT_H_
+#define VFSTONFS(mp) ((struct nfsmount *)((mp)->i_private))
-/*
- * Mount structure.
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/* Mount structure.
* One allocated on every NFS mount.
* Holds NFS specific information for mount.
*/
@@ -44,7 +72,7 @@ struct nfsmount
{
int nm_flag; /* Flags for soft/hard... */
int nm_state; /* Internal state flags */
- struct mount *nm_mountp; /* Vfs structure for this filesystem */
+ struct inode *nm_mountp; /* Vfs structure for this filesystem */
int nm_numgrps; /* Max. size of groupslist */
nfsfh_t nm_fh; /* File handle of root dir */
int nm_fhsize; /* Size of root file handle */
@@ -70,37 +98,30 @@ struct nfsmount
int nm_acdirmax; /* Directory attr cache max lifetime */
int nm_acregmin; /* Reg file attr cache min lifetime */
int nm_acregmax; /* Reg file attr cache max lifetime */
- u_char nm_verf[NFSX_V3WRITEVERF]; /* V3 write verifier */
- TAILQ_HEAD(, buf) nm_bufq; /* async io buffer queue */
- short nm_bufqlen; /* number of buffers in queue */
- short nm_bufqwant; /* process wants to add to the queue */
- int nm_bufqiods; /* number of iods processing queue */
- u_int64_t nm_maxfilesize; /* maximum file size */
-
- struct nfsx_nfsops *nm_nfsops; /* Version specific ops. */
-
- /* NFSv4 */
-
- uint64_t nm_clientid;
- fsid_t nm_fsid;
- u_int nm_lease_time;
- time_t nm_last_renewal;
-
- struct vnode *nm_dvp;
+ unsigned char nm_verf[NFSX_V3WRITEVERF]; /* V3 write verifier */
};
-#define NFSOP(nmp, op) (*nmp->nm_nfsops->nn_##op)
-#define NFSHASOP(nmp, op) (nmp->nm_nfsops->nn_##op != NULL)
-#define NFSDAT(nmp, nam) (nmp->nm_nfsops->nn_##nam)
-
-#if defined(_KERNEL)
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
-/*
- * Convert mount ptr to nfsmount ptr.
- */
+/* Prototypes for NFS mount operations: */
-# define VFSTONFS(mp) ((struct nfsmount *)((mp)->mnt_data))
-
-#endif
+int nfs_mount(struct mount *, const char *, void *, struct nameidata *,
+ struct proc *);
+int mountnfs(struct nfs_args *, struct mount *, struct mbuf *, char *, char *);
+void nfs_decode_args(struct nfsmount *, struct nfs_args *, struct nfs_args *);
+int nfs_start(struct mount *, int, struct proc *);
+int nfs_unmount(struct mount *, int, struct proc *);
+int nfs_root(struct mount *, struct vnode **);
+int nfs_quotactl(struct mount *, int, uid_t, caddr_t, struct proc *);
+int nfs_statfs(struct mount *, struct statfs *, struct proc *);
+int nfs_sync(struct mount *, int, struct ucred *, struct proc *);
+int nfs_vget(struct mount *, ino_t, struct vnode **);
+int nfs_fhtovp(struct mount *, struct fid *, struct vnode **);
+int nfs_vptofh(struct vnode *, struct fid *);
+int nfs_fsinfo(struct nfsmount *, struct vnode *, struct ucred *,
+ struct proc *);
+void nfs_init(void);
#endif
diff --git a/nuttx/fs/nfs/nfs_node.h b/nuttx/fs/nfs/nfs_node.h
new file mode 100644
index 000000000..4fe2553c5
--- /dev/null
+++ b/nuttx/fs/nfs/nfs_node.h
@@ -0,0 +1,157 @@
+/****************************************************************************
+ * fs/nfs/nfs_mount.h
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012 Jose Pablo Rojas Vargas. All rights reserved.
+ * Author: Jose Pablo Rojas Vargas <jrojas@nx-engineering.com>
+ *
+ * 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_NFS_NODE_H
+#define __FS_NFS_NFS_NODE_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#ifndef _NFS_NFS_H_
+# include <nfs/nfs.h>
+#endif
+
+#include <sys/rwlock.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Values for n_commitflags */
+
+#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
+#define n_cookieverf n_un1.nd_cookieverf
+#define n_direofoffset n_un2.nd_direof
+
+/* Flags for n_flag */
+
+#define NFLUSHWANT 0x0001/* Want wakeup from a flush in prog. */
+#define NFLUSHINPROG 0x0002/* Avoid multiple calls to vinvalbuf() */
+#define NMODIFIED 0x0004/* Might have a modified buffer in bio */
+#define NWRITEERR 0x0008/* Flag write errors so close will know */
+#define NACC 0x0100/* Special file accessed */
+#define NUPD 0x0200/* Special file updated */
+#define NCHG 0x0400/* Special file times changed */
+
+#define NFS_INVALIDATE_ATTRCACHE(np) ((np)->n_attrstamp = 0)
+
+/* Convert between nfsnode pointers and vnode pointers */
+
+#define VTONFS(vp) ((struct nfsnode *)(vp)->f_priv)
+#define NFSTOV(np) ((np)->n_vnode)
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/* Silly rename structure that hangs off the nfsnode until the name
+ * can be removed by nfs_inactive()
+
+struct sillyrename
+{
+ struct ucred *s_cred;
+ struct vnode *s_dvp;
+ long s_namlen;
+ char s_name[24];
+};
+*/
+
+/* The nfsnode is the nfs equivalent to ufs's inode. Any similarity
+ * is purely coincidental.
+ * There is a unique nfsnode allocated for each active file,
+ * each current directory, each mounted-on file, text file, and the root.
+ * An nfsnode is 'named' by its file handle. (nget/nfs_node.c)
+ * If this structure exceeds 256 bytes (it is currently 256 using 4.4BSD-Lite
+ * type definitions), file handles of > 32 bytes should probably be split out
+ * into a separate malloc()'d data structure. (Reduce the size of nfsfh_t by
+ * changing the definition in sys/mount.h of NFS_SMALLFH.)
+ * NB: Hopefully the current order of the fields is such that everything will
+ * be well aligned and, therefore, tightly packed.
+ */
+
+struct nfsnode
+{
+ RB_ENTRY(nfsnode) n_entry; /* filehandle/node tree. */
+ uint64_t n_size; /* Current size of file */
+//struct vattr n_vattr; /* Vnode attribute cache */
+ time_t n_attrstamp; /* Attr. cache timestamp */
+ struct timespec n_mtime; /* Prev modify time. */
+ time_t n_ctime; /* Prev create time. */
+ nfsfh_t *n_fhp; /* NFS File Handle */
+ struct inode *n_inode; /* associated inode */
+//struct lockf *n_lockf; /* Locking record of file */
+ int n_error; /* Save write error value */
+ union
+ {
+ struct timespec nf_atim; /* Special file times */
+ nfsuint64 nd_cookieverf; /* Cookie verifier (dir only) */
+ } n_un1;
+ union
+ {
+ struct timespec nf_mtim;
+ off_t nd_direof; /* Dir. EOF offset cache */
+ } n_un2;
+//struct sillyrename *n_sillyrename; /* Ptr to silly rename struct */
+ short 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 */
+ uid_t n_accuid; /* Last access requester */
+ int n_accmode; /* Last mode requested */
+ int n_accerror; /* Last returned error */
+//struct ucred *n_rcred;
+//struct ucred *n_wcred;
+
+ off_t n_pushedlo; /* 1st blk in commited range */
+ off_t n_pushedhi; /* Last block in range */
+ off_t n_pushlo; /* 1st block in commit range */
+ off_t n_pushhi; /* Last block in range */
+//struct rwlock n_commitlock; /* Serialize commits */
+ int n_commitflags;
+};
+
+#endif /* __FS_NFS_NFS_NODE_H */
diff --git a/nuttx/fs/nfs/nfs_proto.h b/nuttx/fs/nfs/nfs_proto.h
index f53ace79e..cab8fdd57 100644
--- a/nuttx/fs/nfs/nfs_proto.h
+++ b/nuttx/fs/nfs/nfs_proto.h
@@ -1,6 +1,14 @@
-/*
- * Copyright (c) 1989, 1993
- * The Regents of the University of California. All rights reserved.
+/****************************************************************************
+ * fs/nfs/nfs_proto.h
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012 Jose Pablo Rojas Vargas. All rights reserved.
+ * Author: Jose Pablo Rojas Vargas <jrojas@nx-engineering.com>
+ *
+ * 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.
@@ -29,13 +37,21 @@
* 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_NFS_PROTO_H
+#define __FS_NFS_NFS_PROTO_H
-#ifndef _NFS_NFSPROTO_H_
-#define _NFS_NFSPROTO_H_
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
-/*
- * Constants as defined in the Sun NFS Version 2 and 3 specs.
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Constants as defined in the Sun NFS Version 2 and 3 specs.
* "NFS: Network File System Protocol Specification" RFC1094
* and in the "NFS: Network File System Version 3 Protocol
* Specification"
@@ -124,7 +140,8 @@
#define NFSX_V3FSINFO 48
#define NFSX_V3PATHCONF 24
-/* variants for both versions */
+/* Variants for both versions */
+
#define NFSX_FH(v3) ((v3) ? (NFSX_V3FHMAX + NFSX_UNSIGNED) : \
NFSX_V2FH)
#define NFSX_SRVFH(v3) ((v3) ? NFSX_V3FH : NFSX_V2FH)
@@ -142,7 +159,7 @@
(2 * NFSX_UNSIGNED))
#define NFSX_STATFS(v3) ((v3) ? NFSX_V3STATFS : NFSX_V2STATFS)
-/* nfs rpc procedure numbers (before version mapping) */
+/* NFS RPC procedure numbers (before version mapping) */
#define NFSPROC_NULL 0
#define NFSPROC_GETATTR 1
@@ -191,9 +208,7 @@
#define NFSV2PROC_READDIR 16
#define NFSV2PROC_STATFS 17
-/*
- * Constants used by the Version 3 protocol for various RPCs
- */
+/* Constants used by the Version 3 protocol for various RPCs */
#define NFSV3SATTRTIME_DONTCHANGE 0
#define NFSV3SATTRTIME_TOSERVER 1
@@ -230,6 +245,14 @@
#define nfsv2tov_type(a) nv2tov_type[fxdr_unsigned(uint32_t,(a))&0x7]
#define nfsv3tov_type(a) nv3tov_type[fxdr_unsigned(uint32_t,(a))&0x7]
+#ifndef NFS_MAXFHSIZE
+# define NFS_MAXFHSIZE 64
+#endif
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
/* File types */
typedef enum
@@ -244,15 +267,7 @@ typedef enum
NFFIFO = 7
} nfstype;
-/* Structs for common parts of the rpc's */
-
-/*
- * File Handle (32 bytes for version 2), variable up to 64 for version 3.
- */
-
-#ifndef NFS_MAXFHSIZE
-# define NFS_MAXFHSIZE 64
-#endif
+/* File Handle (32 bytes for version 2), variable up to 64 for version 3. */
union nfsfh
{
@@ -275,8 +290,7 @@ struct nfsv3_time
};
typedef struct nfsv3_time nfstime3;
-/*
- * Quads are defined as arrays of 2 longs to ensure dense packing for the
+/* Quads are defined as arrays of 2 longs to ensure dense packing for the
* protocol and to facilitate xdr conversion.
*/
@@ -286,9 +300,7 @@ struct nfs_uquad
};
typedef struct nfs_uquad nfsuint64;
-/*
- * NFS Version 3 special file number.
- */
+/* NFS Version 3 special file number. */
struct nfsv3_spec
{
@@ -297,8 +309,7 @@ struct nfsv3_spec
};
typedef struct nfsv3_spec nfsv3spec;
-/*
- * File attributes and setable attributes. These structures cover both
+/* File attributes and setable attributes. These structures cover both
* NFS version 2 and the version 3 protocol. Note that the union is only
* used so that one pointer can refer to both variants. These structures
* go out on the wire and must be densely packed, so no quad data types
@@ -342,7 +353,7 @@ struct nfs_fattr
} fa_un;
};
-/* and some ugly defines for accessing union components */
+/* And some ugly defines for accessing union components */
#define fa2_size fa_un.fa_nfsv2.nfsv2fa_size
#define fa2_blocksize fa_un.fa_nfsv2.nfsv2fa_blocksize
@@ -372,9 +383,7 @@ struct nfsv2_sattr
nfstime2 sa_mtime;
};
-/*
- * NFS Version 3 sattr structure for the new node creation case.
- */
+/* NFS Version 3 sattr structure for the new node creation case. */
struct nfsv3_sattr
{
diff --git a/nuttx/fs/nfs/nfs_socket.c b/nuttx/fs/nfs/nfs_socket.c
index b6810fded..03e8dc4d0 100644
--- a/nuttx/fs/nfs/nfs_socket.c
+++ b/nuttx/fs/nfs/nfs_socket.c
@@ -1,7 +1,15 @@
-/*
- * copyright (c) 2004
- * the regents of the university of michigan
- * all rights reserved
+/****************************************************************************
+ * fs/nfs/nfs_socket.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012 Jose Pablo Rojas Vargas. All rights reserved.
+ * Author: Jose Pablo Rojas Vargas <jrojas@nx-engineering.com>
+ *
+ * Leveraged from OpenBSD:
+ *
+ * copyright (c) 2004
+ * 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
@@ -20,54 +28,72 @@
* 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.
- */
+ *
+ ****************************************************************************/
-/* wrappers around rpcclnt */
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
-/* XXX add tryagain code in nfs_request_xx */
-
-/*
- * Socket operations for use by nfs
- */
-
-#include <sys/param.h>
-#include <sys/systm.h>
-#include <sys/kernel.h>
-#include <sys/malloc.h>
-#include <sys/mbuf.h>
-#include <sys/mount.h>
#include <sys/socket.h>
-
-#include "rpc_clnt.h"
+#include <queue.h>
+#include <time.h>
+#include <netinet/in.h>
+#include <arpa/inet.h>
+#include <errno.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <debug.h>
+
+#include "nfs_args.h"
+#include "rpc.h"
#include "rpc_v2.h"
-#include "nfs_proto.h
+#include "nfs_proto.h"
#include "nfs.h"
#include "xdr_subs.h"
-#include "nfsmount.h"
-//#include <nfsx/nfs_common.h>
+#include "nfs_mount.h"
#include "nfs_socket.h"
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
/* Flag translations */
+
#define nfsmnt_to_rpcclnt(nf, rf, name) do { \
- if (nf & NFSMNT_##name)) { \
- rf |= RPCCLNT_##name \
+ if (nf & NFSMNT_##name) { \
+ rf |= RPCCLNT_##name; \
} \
} while(0)
-static struct rpc_program nfs2_program =
-{
- NFS_PROG, NFS_VER2, "NFSv2"
-};
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
static struct rpc_program nfs3_program =
{
NFS_PROG, NFS_VER3, "NFSv3"
};
-static struct rpc_program nfs4_program =
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+int nfs_ticks;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+void nfs_init(void)
{
- NFS_PROG, NFS_VER4, "NFSv4"
-};
+ rpcclnt_init();
+}
/* XXXMARIUS: name collision */
int nfsx_connect(struct nfsmount *nmp)
@@ -91,10 +117,10 @@ int nfsx_connect(struct nfsmount *nmp)
nfsmnt_to_rpcclnt(nmp->nm_flag, rpc->rc_flag, NOCONN);
nfsmnt_to_rpcclnt(nmp->nm_flag, rpc->rc_flag, DUMBTIMR);
- rpc->rc_flag |= RPCCLNT_REDIRECT; /* Make this a mount option. */
+ //rpc->rc_flag |= RPCCLNT_REDIRECT; /* Make this a mount option. */
rpc->rc_authtype = RPCAUTH_NULL; /* for now */
- rpc->rc_servername = nmp->nm_mountp->mnt_stat.f_mntfromname;
+ //rpc->rc_servername = nmp->nm_mountp->mnt_stat.f_mntfromname;
rpc->rc_name = (struct sockaddr *)nmp->nm_nam;
rpc->rc_sotype = nmp->nm_sotype;
@@ -132,93 +158,55 @@ void nfsx_safedisconnect(struct nfsmount *nmp)
}
#endif
-int
-nfsx_request_xx(struct nfsmount *nm, struct vnode *vp, struct mbuf *mrest,
- int procnum, cthread_t * td, struct ucred *cred,
- struct mbuf **mrp, struct mbuf **mdp, caddr_t * dposp)
+int nfsx_request_xx(struct nfsmount *nm, int procnum)
{
int error;
- u_int32_t *tl;
struct nfsmount *nmp;
struct rpcclnt *clnt;
- struct mbuf *md, *mrep;
- caddr_t dpos;
struct rpc_reply reply;
-#if 0
- int t1;
-#endif /* 0 */
-
- if (vp != NULL)
- nmp = VFSTONFS(vp->v_mount);
- else
- nmp = nm;
+ int trylater_delay;
+ nmp = nm;
clnt = &nmp->nm_rpcclnt;
-#if 0
tryagain:
-#endif
memset(&reply, 0, sizeof(reply));
- if ((error = rpcclnt_request(clnt, mrest, procnum, td, cred, &reply)) != 0)
+ if ((error = rpcclnt_request(clnt, procnum, &reply)) != 0)
goto out;
- mrep = reply.mrep;
- md = reply.result_md;
- dpos = reply.result_dpos;
- tl = nfsm_dissect(u_int32_t *, NFSX_UNSIGNED);
- if (*tl != 0)
+ if (reply->rpc_verfi.authtype != 0)
{
- error = fxdr_unsigned(int, *tl);
-#if 0
+ error = fxdr_unsigned(int, reply->rpc_verfi.authtype);
+
if ((nmp->nm_flag & NFSMNT_NFSV3) && error == NFSERR_TRYLATER)
{
- m_freem(mrep);
error = 0;
- waituntil = time_second + trylater_delay;
- while (time_second < waituntil)
- (void)tsleep(&lbolt, PSOCK, "nqnfstry", 0);
- trylater_delay *= nfs_backoff[trylater_cnt];
- if (trylater_cnt < NFS_NBACKOFF - 1)
- trylater_cnt++;
+ trylater_delay *= NFS_TIMEOUTMUL;
+ if (trylater_delay > NFS_MAXTIMEO)
+ {
+ trylater_delay = NFS_MAXTIMEO;
+ }
goto tryagain;
}
-#endif
/*
** If the File Handle was stale, invalidate the
** lookup cache, just in case.
**/
if (error == ESTALE)
- if (vp != NULL)
- cache_purge(vp);
- else
- printf("%s: ESTALE on mount from server %s\n",
- nmp->nm_rpcclnt.rc_prog->prog_name,
- nmp->nm_rpcclnt.rc_servername);
+ printf("%s: ESTALE on mount from server \n",
+ nmp->nm_rpcclnt.rc_prog->prog_name);
else
- printf("%s: unknown error %d from server %s\n",
- nmp->nm_rpcclnt.rc_prog->prog_name, error,
- nmp->nm_rpcclnt.rc_servername);
+ printf("%s: unknown error %d from server \n",
+ nmp->nm_rpcclnt.rc_prog->prog_name, error);
goto out;
}
-
- m_freem(mrest);
-
- *mrp = mrep;
- *mdp = md;
- *dposp = dpos;
return (0);
-nfsmout:
+
out:
- /* XXX: don't free mrest if an error occured, to allow caller to retry */
- m_freem(mrest);
- m_freem(reply.mrep);
- *mrp = NULL;
- *mdp = NULL;
-
return (error);
}
diff --git a/nuttx/fs/nfs/nfs_socket.h b/nuttx/fs/nfs/nfs_socket.h
index 89ef4fe89..5752eb2bb 100644
--- a/nuttx/fs/nfs/nfs_socket.h
+++ b/nuttx/fs/nfs/nfs_socket.h
@@ -1,7 +1,15 @@
-/*
- * copyright (c) 2004
- * the regents of the university of michigan
- * all rights reserved
+/****************************************************************************
+ * fs/nfs/nfs_socket.h
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012 Jose Pablo Rojas Vargas. All rights reserved.
+ * Author: Jose Pablo Rojas Vargas <jrojas@nx-engineering.com>
+ *
+ * Leveraged from OpenBSD:
+ *
+ * copyright (c) 2004
+ * 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
@@ -20,50 +28,42 @@
* 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.
- */
+ *
+ ****************************************************************************/
-#ifndef __NFSX_H_
-#define __NFSX_H_
+#ifndef __FS_NFS_NFS_SOCKET_H
+#define __FS_NFS_NFS_SOCKET_H
-/* nfs_socket interface */
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
-/* XXXMARIUS: name collision */
+/****************************************************************************
+ * Pre-processor definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
int nfsx_connect(struct nfsmount *);
void nfsx_disconnect(struct nfsmount *);
+#ifdef CONFIG_NFS_TCPIP
int nfsx_sigintr(struct nfsmount *, struct nfsreq *, cthread_t *);
void nfsx_safedisconnect(struct nfsmount *);
-int nfsx_request_xx(struct nfsmount *, struct vnode *, struct mbuf *, int,
- cthread_t *, struct ucred *, struct mbuf **, struct mbuf **,
- caddr_t *);
+#define nfs_safedisconnect nfsx_safedisconnect
+#endif
+int nfsx_request_xx(struct nfsmount *, int);
int nfsx_nmcancelreqs(struct nfsmount *);
#define nfs_connect nfs_connect_nfsx
#define nfs_disconnect nfs_disconnect_nfsx
-#define nfs_sigintr nfs_sigintr_nfsx
-
-/* XXX dros: defined in nfs.h */
-
-#if 0
-void nfs_safedisconnect(struct nfsmount *);
-#endif
+#define nfs_nmcancelreqs nfsx_nmcancelreqs
+#define nfsx_request(nmp, m) \
+ nfsx_request_xx(nmp, m)
-#define nfsx_request(vp, m, p, td, cr, m2, m3, c) \
- nfsx_request_xx(NULL, vp, m, p, td, cr, m2, m3, c)
-
-#define nfsx_request_mnt(nmp, m, p, td, cr, m2, m3, c) \
- nfsx_request_xx(nmp, NULL, m, p, td, cr, m2, m3, c)
-
-/* don't use this.. use nfsx_request() of nfsx_request_mnt() */
-
-int nfs_request_xx(struct nfsmount *, struct vnode *, struct mbuf *, int,
- cthread_t *, struct ucred *, struct mbuf **, struct mbuf **,
- caddr_t *);
-
-/* XXX dros: defined in nfs.h */
-
-#if 0
-int nfs_nmcancelreqs(struct nfsmount *);
+#ifdef CONFIG_NFS_TCPIP
+#define nfs_sigintr nfs_sigintr_nfsx
#endif
-#endif /* __NFSX_H_ */
+#endif /* __FS_NFS_NFS_SOCKET_H */
diff --git a/nuttx/fs/nfs/nfs_vfsops.c b/nuttx/fs/nfs/nfs_vfsops.c
new file mode 100644
index 000000000..407963abd
--- /dev/null
+++ b/nuttx/fs/nfs/nfs_vfsops.c
@@ -0,0 +1,927 @@
+/****************************************************************************
+ * fs/nfs/nfs_vfsops.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012 Jose Pablo Rojas Vargas. All rights reserved.
+ * Author: Jose Pablo Rojas Vargas <jrojas@nx-engineering.com>
+ *
+ * Leveraged from OpenBSD:
+ *
+ * Copyright (c) 1989, 1993, 1995
+ * 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <sys/param.h>
+#include <sys/conf.h>
+#include <sys/ioctl.h>
+#include <sys/signal.h>
+#include <sys/proc.h>
+#include <sys/namei.h>
+#include <sys/vnode.h>
+#include <sys/kernel.h>
+#include <sys/mount.h>
+#include <sys/buf.h>
+#include <sys/mbuf.h>
+#include <sys/dirent.h>
+#include <sys/socket.h>
+#include <sys/socketvar.h>
+#include <sys/systm.h>
+#include <sys/sysctl.h>
+
+#include <sys/statfs>
+#include <sys/queue.h>
+
+#include <net/if.h>
+#include <net/route.h>
+#include <netinet/in.h>
+
+#include <nfs/rpcv2.h>
+#include <nfs/nfsproto.h>
+#include <nfs/nfsnode.h>
+#include <nfs/nfs.h>
+#include <nfs/nfsmount.h>
+#include <nfs/xdr_subs.h>
+#include <nfs/nfsm_subs.h>
+#include <nfs/nfsdiskless.h>
+#include <nfs/nfs_var.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Definitions
+ ****************************************************************************/
+
+/* nfs vfs operations. */
+
+const struct vfsops nfs_vfsops =
+{
+ nfs_mount,
+ nfs_start,
+ nfs_unmount,
+ nfs_root,
+ nfs_quotactl,
+ nfs_statfs,
+ nfs_sync,
+ nfs_vget,
+ nfs_fhtovp,
+ nfs_vptofh,
+ nfs_vfs_init,
+ nfs_sysctl,
+ nfs_checkexp
+};
+
+/****************************************************************************
+ * External Public Data (this belong in a header file)
+ ****************************************************************************/
+
+extern struct nfsstats nfsstats;
+extern int nfs_ticks;
+extern uint32_t nfs_procids[NFS_NPROCS];
+
+/****************************************************************************
+ * Public Function Prototypes (this belong in a header file)
+ ****************************************************************************/
+
+int nfs_sysctl(int *, u_int, void *, size_t *, void *, size_t, struct proc *);
+int nfs_checkexp(struct mount *, struct mbuf *, int *, struct ucred **);
+struct mount *nfs_mount_diskless(struct nfs_dlmount *, char *, int);
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Publikc Functions
+ ****************************************************************************/
+
+/* nfs statfs call */
+
+int nfs_statfs(struct file *filep, struct statfs *sbp)
+{
+ struct nfs_statfs *sfp = NULL;
+ struct nfsmount *nmp = VFSTONFS(filep->f_inode);
+ int error = 0;
+ struct nfsnode *np = VTONFS(filep->f_priv);
+ uint64_t tquad;
+
+ error = nfs_nget(mp, (nfsfh_t *) nmp->nm_fh, nmp->nm_fhsize, &np);
+ if (error)
+ return (error);
+
+ if ((nmp->nm_flag & NFSMNT_GOTFSINFO) == 0)
+ (void)nfs_fsinfo(nmp);
+ nfsstats.rpccnt[NFSPROC_FSSTAT]++;
+
+ error = nfs_request(nmp, NFSPROC_FSSTAT);
+ if (error)
+ goto nfsmout;
+
+ sbp->f_iosize = min(nmp->nm_rsize, nmp->nm_wsize);
+ if (info.nmi_v3)
+ {
+ sbp->f_bsize = NFS_FABLKSIZE;
+ tquad = fxdr_hyper(&sfp->sf_tbytes);
+ sbp->f_blocks = tquad / (u_quad_t) NFS_FABLKSIZE;
+ tquad = fxdr_hyper(&sfp->sf_fbytes);
+ sbp->f_bfree = tquad / (u_quad_t) NFS_FABLKSIZE;
+ tquad = fxdr_hyper(&sfp->sf_abytes);
+ sbp->f_bavail = (quad_t) tquad / (quad_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_favail = tquad;
+ sbp->f_namemax = MAXNAMLEN;
+ }
+ else
+ {
+ sbp->f_bsize = fxdr_unsigned(int32_t, sfp->sf_bsize);
+ sbp->f_blocks = fxdr_unsigned(int32_t, sfp->sf_blocks);
+ sbp->f_bfree = fxdr_unsigned(int32_t, sfp->sf_bfree);
+ sbp->f_bavail = fxdr_unsigned(int32_t, sfp->sf_bavail);
+ sbp->f_files = 0;
+ sbp->f_ffree = 0;
+ }
+ copy_statfs_info(sbp, mp);
+nfsmout:
+ return (error);
+}
+
+/* nfs version 3 fsinfo rpc call */
+
+int nfs_fsinfo(struct nfsmount *nmp)
+{
+ struct nfsv3_fsinfo *fsp;
+ struct nfsm_info info;
+ uint32_t pref, max;
+ int error = 0;
+
+ nfsstats.rpccnt[NFSPROC_FSINFO]++;
+
+ error = nfs_request(nmp, NFSPROC_FSINFO);
+ if (error)
+ {
+ goto nfsmout;
+ }
+
+ pref = fxdr_unsigned(uint32_t, fsp->fs_wtpref);
+ if (pref < nmp->nm_wsize)
+ nmp->nm_wsize = (pref + NFS_FABLKSIZE - 1) & ~(NFS_FABLKSIZE - 1);
+ max = fxdr_unsigned(uint32_t, fsp->fs_wtmax);
+ if (max < nmp->nm_wsize)
+ {
+ nmp->nm_wsize = max & ~(NFS_FABLKSIZE - 1);
+ if (nmp->nm_wsize == 0)
+ nmp->nm_wsize = max;
+ }
+ pref = fxdr_unsigned(uint32_t, fsp->fs_rtpref);
+ if (pref < nmp->nm_rsize)
+ nmp->nm_rsize = (pref + NFS_FABLKSIZE - 1) & ~(NFS_FABLKSIZE - 1);
+ max = fxdr_unsigned(uint32_t, fsp->fs_rtmax);
+ if (max < nmp->nm_rsize)
+ {
+ nmp->nm_rsize = max & ~(NFS_FABLKSIZE - 1);
+ if (nmp->nm_rsize == 0)
+ nmp->nm_rsize = max;
+ }
+ pref = fxdr_unsigned(uint32_t, fsp->fs_dtpref);
+ if (pref < nmp->nm_readdirsize)
+ nmp->nm_readdirsize = (pref + NFS_DIRBLKSIZ - 1) & ~(NFS_DIRBLKSIZ - 1);
+ if (max < nmp->nm_readdirsize)
+ {
+ nmp->nm_readdirsize = max & ~(NFS_DIRBLKSIZ - 1);
+ if (nmp->nm_readdirsize == 0)
+ nmp->nm_readdirsize = max;
+ }
+ nmp->nm_flag |= NFSMNT_GOTFSINFO;
+
+nfsmout:
+ return (error);
+}
+
+/* Mount a remote root fs via. NFS. It goes like this:
+ * - Call nfs_boot_init() to fill in the nfs_diskless struct
+ * (using RARP, bootparam RPC, mountd RPC)
+ * - hand craft the swap nfs vnode hanging off a fake mount point
+ * if swdevt[0].sw_dev == NODEV
+ * - build the rootfs mount point and call mountnfs() to do the rest.
+ */
+
+int nfs_mountroot(void)
+{
+ struct nfs_diskless nd;
+ struct vattr attr;
+ struct mount *mp;
+ struct vnode *vp;
+ struct proc *procp;
+ long n;
+ int error;
+
+ procp = curproc; /* XXX */
+
+ /* Call nfs_boot_init() to fill in the nfs_diskless struct.
+ * Side effect: Finds and configures a network interface.
+ */
+
+ bzero((caddr_t) & nd, sizeof(nd));
+ nfs_boot_init(&nd, procp);
+
+ /* Create the root mount point. */
+
+ if (nfs_boot_getfh(&nd.nd_boot, "root", &nd.nd_root, -1))
+ panic("nfs_mountroot: root");
+ mp = nfs_mount_diskless(&nd.nd_root, "/", 0);
+ nfs_root(mp, &rootvp);
+ printf("root on %s\n", nd.nd_root.ndm_host);
+
+ /* Link it into the mount list. */
+
+ CIRCLEQ_INSERT_TAIL(&mountlist, mp, mnt_list);
+ vfs_unbusy(mp);
+
+ /* Get root attributes (for the time). */
+
+ error = VOP_GETATTR(rootvp, &attr, procp->p_ucred, procp);
+ if (error)
+ panic("nfs_mountroot: getattr for root");
+ n = attr.va_atime.tv_sec;
+#ifdef DEBUG
+ printf("root time: 0x%lx\n", n);
+#endif
+ inittodr(n);
+
+#ifdef notyet
+ /* Set up swap credentials. */
+
+ proc0.p_ucred->cr_uid = ntohl(nd.swap_ucred.cr_uid);
+ proc0.p_ucred->cr_gid = ntohl(nd.swap_ucred.cr_gid);
+ if ((proc0.p_ucred->cr_ngroups = ntohs(nd.swap_ucred.cr_ngroups)) > NGROUPS)
+ proc0.p_ucred->cr_ngroups = NGROUPS;
+ for (i = 0; i < proc0.p_ucred->cr_ngroups; i++)
+ proc0.p_ucred->cr_groups[i] = ntohl(nd.swap_ucred.cr_groups[i]);
+#endif
+
+ /* "Mount" the swap device.
+ *
+ * On a "dataless" configuration (swap on disk) we will have:
+ * (swdevt[0].sw_dev != NODEV) identifying the swap device.
+ */
+
+ if (bdevvp(swapdev, &swapdev_vp))
+ panic("nfs_mountroot: can't setup swap vp");
+ if (swdevt[0].sw_dev != NODEV)
+ {
+ printf("swap on device 0x%x\n", swdevt[0].sw_dev);
+ return (0);
+ }
+
+ /* If swapping to an nfs node: (swdevt[0].sw_dev == NODEV)
+ * Create a fake mount point just for the swap vnode so that the
+ * swap file can be on a different server from the rootfs.
+ *
+ * Wait 5 retries, finally no swap is cool. -mickey
+ */
+
+ error = nfs_boot_getfh(&nd.nd_boot, "swap", &nd.nd_swap, 5);
+ if (!error)
+ {
+ mp = nfs_mount_diskless(&nd.nd_swap, "/swap", 0);
+ nfs_root(mp, &vp);
+ vfs_unbusy(mp);
+
+ /* Since the swap file is not the root dir of a file system,
+ * hack it to a regular file.
+ */
+
+ vp->v_type = VREG;
+ vp->v_flag = 0;
+
+ /* Next line is a hack to make swapmount() work on NFS
+ * swap files.
+ * XXX-smurph
+ */
+
+ swdevt[0].sw_dev = NETDEV;
+ /* end hack */
+ swdevt[0].sw_vp = vp;
+
+ /* Find out how large the swap file is. */
+
+ error = VOP_GETATTR(vp, &attr, procp->p_ucred, procp);
+ if (error)
+ printf("nfs_mountroot: getattr for swap\n");
+ n = (long)(attr.va_size >> DEV_BSHIFT);
+
+ printf("swap on %s\n", nd.nd_swap.ndm_host);
+#ifdef DEBUG
+ printf("swap size: 0x%lx (blocks)\n", n);
+#endif
+ return (0);
+ }
+
+ printf("WARNING: no swap\n");
+ swdevt[0].sw_dev = NODEV;
+ swdevt[0].sw_vp = NULL;
+
+ return (0);
+}
+
+/* Internal version of mount system call for diskless setup. */
+
+struct mount *nfs_mount_diskless(struct nfs_dlmount *ndmntp, char *mntname,
+ int mntflag)
+{
+ struct nfs_args args;
+ struct mount *mp;
+ struct mbuf *m;
+ int error;
+
+ if (vfs_rootmountalloc("nfs", mntname, &mp))
+ panic("nfs_mount_diskless: vfs_rootmountalloc failed");
+ mp->mnt_flag |= mntflag;
+
+ /* Initialize mount args. */
+
+ bzero((caddr_t) & args, sizeof(args));
+ args.addr = (struct sockaddr *)&ndmntp->ndm_saddr;
+ args.addrlen = args.addr->sa_len;
+ args.sotype = SOCK_DGRAM;
+ args.fh = ndmntp->ndm_fh;
+ args.fhsize = NFSX_V2FH;
+ args.hostname = ndmntp->ndm_host;
+
+#ifdef NFS_BOOT_OPTIONS
+ args.flags |= NFS_BOOT_OPTIONS;
+#endif
+#ifdef NFS_BOOT_RWSIZE
+ /* Reduce rsize,wsize for interfaces that consistently
+ * drop fragments of long UDP messages. (i.e. wd8003).
+ * You can always change these later via remount.
+ */
+
+ args.flags |= NFSMNT_WSIZE | NFSMNT_RSIZE;
+ args.wsize = NFS_BOOT_RWSIZE;
+ args.rsize = NFS_BOOT_RWSIZE;
+#endif
+
+ /* Get mbuf for server sockaddr. */
+
+ m = m_get(M_WAIT, MT_SONAME);
+ bcopy((caddr_t) args.addr, mtod(m, caddr_t), (m->m_len = args.addr->sa_len));
+
+ error = mountnfs(&args, mp, m, mntname, args.hostname);
+ if (error)
+ panic("nfs_mountroot: mount %s failed: %d", mntname, error);
+
+ return (mp);
+}
+
+void
+nfs_decode_args(struct nfsmount *nmp, struct nfs_args *argp,
+ struct nfs_args *nargp)
+{
+ int s;
+ int adjsock = 0;
+ int maxio;
+
+ s = splsoftnet();
+
+#if 0
+ /* 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);
+ splx(s);
+
+ 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, NULL))
+ {
+ printf("nfs_args: retrying connect\n");
+ (void)tsleep((caddr_t) & lbolt, PSOCK, "nfscon", 0);
+ }
+ }
+
+ /* Update nargp based on nmp */
+
+ nargp->wsize = nmp->nm_wsize;
+ nargp->rsize = nmp->nm_rsize;
+ nargp->readdirsize = nmp->nm_readdirsize;
+ nargp->timeo = nmp->nm_timeo;
+ nargp->retrans = nmp->nm_retry;
+ nargp->maxgrouplist = nmp->nm_numgrps;
+ nargp->readahead = nmp->nm_readahead;
+ nargp->acregmin = nmp->nm_acregmin;
+ nargp->acregmax = nmp->nm_acregmax;
+ nargp->acdirmin = nmp->nm_acdirmin;
+ nargp->acdirmax = nmp->nm_acdirmax;
+}
+
+/* VFS Operations.
+ *
+ * mount system call
+ * It seems a bit dumb to copyinstr() the host and path here and then
+ * bcopy() them in mountnfs(), but I wanted to detect errors before
+ * doing the sockargs() call because sockargs() allocates an mbuf and
+ * an error after that means that I have to release the mbuf.
+ */
+
+/* ARGSUSED */
+int
+nfs_mount(struct mount *mp, const char *path, void *data,
+ struct nameidata *ndp, struct proc *p)
+{
+ int error;
+ struct nfs_args args;
+ struct mbuf *nam;
+ char pth[MNAMELEN], hst[MNAMELEN];
+ size_t len;
+ u_char nfh[NFSX_V3FHMAX];
+
+ error = copyin(data, &args, sizeof(args.version));
+ if (error)
+ return (error);
+ if (args.version == 3)
+ {
+ error = copyin(data, (caddr_t) & args, sizeof(struct nfs_args3));
+ args.flags &= ~(NFSMNT_INTERNAL | NFSMNT_NOAC);
+ }
+ else if (args.version == NFS_ARGSVERSION)
+ {
+ error = copyin(data, (caddr_t) & args, sizeof(struct nfs_args));
+ args.flags &= ~NFSMNT_NOAC; /* XXX - compatibility */
+ }
+ else
+ return (EPROGMISMATCH);
+ if (error)
+ return (error);
+
+ if ((args.flags & (NFSMNT_NFSV3 | NFSMNT_RDIRPLUS)) == NFSMNT_RDIRPLUS)
+ return (EINVAL);
+
+ if (nfs_niothreads < 0)
+ {
+ nfs_niothreads = 4;
+ nfs_getset_niothreads(1);
+ }
+
+ if (mp->mnt_flag & MNT_UPDATE)
+ {
+ struct nfsmount *nmp = VFSTONFS(mp);
+
+ if (nmp == NULL)
+ return (EIO);
+
+ /* When doing an update, we can't change from or to v3. */
+
+ args.flags = (args.flags & ~(NFSMNT_NFSV3)) |
+ (nmp->nm_flag & (NFSMNT_NFSV3));
+ nfs_decode_args(nmp, &args, &mp->mnt_stat.mount_info.nfs_args);
+ return (0);
+ }
+ if (args.fhsize < 0 || args.fhsize > NFSX_V3FHMAX)
+ return (EINVAL);
+ error = copyin((caddr_t) args.fh, (caddr_t) nfh, args.fhsize);
+ if (error)
+ return (error);
+ error = copyinstr(path, pth, MNAMELEN - 1, &len);
+ if (error)
+ return (error);
+ bzero(&pth[len], MNAMELEN - len);
+ error = copyinstr(args.hostname, hst, MNAMELEN - 1, &len);
+ if (error)
+ return (error);
+ bzero(&hst[len], MNAMELEN - len);
+
+ /* sockargs() call must be after above copyin() calls */
+
+ error = sockargs(&nam, args.addr, args.addrlen, MT_SONAME);
+ if (error)
+ return (error);
+ args.fh = nfh;
+ error = mountnfs(&args, mp, nam, pth, hst);
+ return (error);
+}
+
+/* Common code for mount and mountroot */
+
+int
+mountnfs(struct nfs_args *argp, struct mount *mp, struct mbuf *nam, char *pth,
+ char *hst)
+{
+ struct nfsmount *nmp;
+ int error;
+
+ if (mp->mnt_flag & MNT_UPDATE)
+ {
+ nmp = VFSTONFS(mp);
+
+ /* update paths, file handles, etc, here XXX */
+
+ m_freem(nam);
+ return (0);
+ }
+ else
+ {
+ nmp = malloc(sizeof(struct nfsmount), M_NFSMNT, M_WAITOK | M_ZERO);
+ mp->mnt_data = (qaddr_t) nmp;
+ }
+
+ vfs_getnewfsid(mp);
+ nmp->nm_mountp = mp;
+ 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;
+ bcopy((caddr_t) argp->fh, (caddr_t) nmp->nm_fh, argp->fhsize);
+ strncpy(&mp->mnt_stat.f_fstypename[0], mp->mnt_vfc->vfc_name, MFSNAMELEN);
+ bcopy(hst, mp->mnt_stat.f_mntfromname, MNAMELEN);
+ bcopy(pth, mp->mnt_stat.f_mntonname, MNAMELEN);
+ bcopy(argp, &mp->mnt_stat.mount_info.nfs_args, sizeof(*argp));
+ nmp->nm_nam = nam;
+ nfs_decode_args(nmp, argp, &mp->mnt_stat.mount_info.nfs_args);
+
+ RB_INIT(&nmp->nm_ntree);
+ TAILQ_INIT(&nmp->nm_reqsq);
+ timeout_set(&nmp->nm_rtimeout, nfs_timer, nmp);
+
+ /* 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, NULL)))
+ goto bad;
+
+ /* This is silly, but it has to be set so that vinifod() works.
+ * We do not want to do an nfs_statfs() here since we can get
+ * stuck on a dead server and we are holding a lock on the mount
+ * point.
+ */
+
+ mp->mnt_stat.f_iosize = NFS_MAXDGRAMDATA;
+
+ return (0);
+bad:
+ nfs_disconnect(nmp);
+ free((caddr_t) nmp, M_NFSMNT);
+ m_freem(nam);
+ return (error);
+}
+
+/* unmount system call */
+
+int nfs_unmount(struct mount *mp, int mntflags, struct proc *p)
+{
+ struct nfsmount *nmp;
+ int error, flags;
+
+ nmp = VFSTONFS(mp);
+ flags = 0;
+
+ if (mntflags & MNT_FORCE)
+ flags |= FORCECLOSE;
+
+ error = vflush(mp, NULL, flags);
+ if (error)
+ return (error);
+
+ nfs_disconnect(nmp);
+ m_freem(nmp->nm_nam);
+ timeout_del(&nmp->nm_rtimeout);
+ free(nmp, M_NFSMNT);
+ return (0);
+}
+
+/* Return root of a filesystem */
+
+int nfs_root(struct mount *mp, struct vnode **vpp)
+{
+ struct nfsmount *nmp;
+ struct nfsnode *np;
+ int error;
+
+ nmp = VFSTONFS(mp);
+ error = nfs_nget(mp, (nfsfh_t *) nmp->nm_fh, nmp->nm_fhsize, &np);
+ if (error)
+ return (error);
+ *vpp = NFSTOV(np);
+ return (0);
+}
+
+/* Flush out the buffer cache */
+
+int nfs_sync(struct mount *mp, int waitfor, struct ucred *cred, struct proc *p)
+{
+ struct vnode *vp;
+ int error, allerror = 0;
+
+ /* Don't traverse the vnode list if we want to skip all of them. */
+
+ if (waitfor == MNT_LAZY)
+ return (allerror);
+
+ /* Force stale buffer cache information to be flushed. */
+
+loop:
+ LIST_FOREACH(vp, &mp->mnt_vnodelist, v_mntvnodes)
+ {
+ /* If the vnode that we are about to sync is no longer
+ * associated with this mount point, start over.
+ */
+
+ if (vp->v_mount != mp)
+ goto loop;
+ if (VOP_ISLOCKED(vp) || LIST_FIRST(&vp->v_dirtyblkhd) == NULL)
+ continue;
+ if (vget(vp, LK_EXCLUSIVE, p))
+ goto loop;
+ error = VOP_FSYNC(vp, cred, waitfor, p);
+ if (error)
+ allerror = error;
+ vput(vp);
+ }
+
+ return (allerror);
+}
+
+/* NFS flat namespace lookup.
+ * Currently unsupported.
+ */
+
+/* ARGSUSED */
+int nfs_vget(struct mount *mp, ino_t ino, struct vnode **vpp)
+{
+ return (EOPNOTSUPP);
+}
+
+/* Do that sysctl thang... */
+
+int
+nfs_sysctl(int *name, u_int namelen, void *oldp, size_t * oldlenp, void *newp,
+ size_t newlen, struct proc *p)
+{
+ int rv;
+
+ /* All names at this level are terminal. */
+
+ if (namelen > 1)
+ return ENOTDIR; /* overloaded */
+
+ switch (name[0])
+ {
+ case NFS_NFSSTATS:
+ if (!oldp)
+ {
+ *oldlenp = sizeof nfsstats;
+ return 0;
+ }
+
+ if (*oldlenp < sizeof nfsstats)
+ {
+ *oldlenp = sizeof nfsstats;
+ return ENOMEM;
+ }
+
+ rv = copyout(&nfsstats, oldp, sizeof nfsstats);
+ if (rv)
+ return rv;
+
+ if (newp && newlen != sizeof nfsstats)
+ return EINVAL;
+
+ if (newp)
+ {
+ return copyin(newp, &nfsstats, sizeof nfsstats);
+ }
+ return 0;
+
+ case NFS_NIOTHREADS:
+ nfs_getset_niothreads(0);
+
+ rv = sysctl_int(oldp, oldlenp, newp, newlen, &nfs_niothreads);
+ if (newp)
+ nfs_getset_niothreads(1);
+
+ return rv;
+
+ default:
+ return EOPNOTSUPP;
+ }
+}
+
+/* At this point, this should never happen */
+
+/* ARGSUSED */
+int nfs_fhtovp(struct mount *mp, struct fid *fhp, struct vnode **vpp)
+{
+ return (EINVAL);
+}
+
+/* Vnode pointer to File handle, should never happen either */
+
+/* ARGSUSED */
+int nfs_vptofh(struct vnode *vp, struct fid *fhp)
+{
+ return (EINVAL);
+}
+
+/* Vfs start routine, a no-op. */
+
+/* ARGSUSED */
+int nfs_start(struct mount *mp, int flags, struct proc *p)
+{
+ return (0);
+}
+
+/* Do operations associated with quotas, not supported */
+
+/* ARGSUSED */
+int
+nfs_quotactl(struct mount *mp, int cmd, uid_t uid, caddr_t arg, struct proc *p)
+{
+ return (EOPNOTSUPP);
+}
+
+/* check export permission, not supported */
+
+/* ARGUSED */
+int
+nfs_checkexp(struct mount *mp, struct mbuf *nam, int *exflagsp,
+ struct ucred **credanonp)
+{
+ return (EOPNOTSUPP);
+}
diff --git a/nuttx/fs/nfs/nfs_vnops.c b/nuttx/fs/nfs/nfs_vnops.c
new file mode 100644
index 000000000..7a41f7630
--- /dev/null
+++ b/nuttx/fs/nfs/nfs_vnops.c
@@ -0,0 +1,3035 @@
+/****************************************************************************
+ * fs/nfs/nfs_vfmops.c
+ * vnode op calls for Sun NFS version 2 and 3
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012 Jose Pablo Rojas Vargas. All rights reserved.
+ * Author: Jose Pablo Rojas Vargas <jrojas@nx-engineering.com>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <sys/param.h>
+#include <sys/proc.h>
+#include <sys/kernel.h>
+#include <sys/systm.h>
+#include <sys/resourcevar.h>
+#include <sys/poll.h>
+#include <sys/proc.h>
+#include <sys/mount.h>
+#include <sys/buf.h>
+#include <sys/malloc.h>
+#include <sys/pool.h>
+#include <sys/mbuf.h>
+#include <sys/conf.h>
+#include <sys/namei.h>
+#include <sys/vnode.h>
+#include <sys/dirent.h>
+#include <sys/fcntl.h>
+#include <sys/lockf.h>
+#include <sys/hash.h>
+#include <sys/queue.h>
+
+#include <nuttx/fs/fs.h>
+#include "rpc_v2.h"
+#include "nfs_proto.h"
+#include "nfs.h"
+#include <nfs/nfsnode.h>
+#include "nfs_mount.h"
+#include "xdr_subs.h"
+//#include <nfs/nfsm_subs.h>
+//#include <nfs/nfs_var.h>
+
+#include <net/if.h>
+#include <netinet/in.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/* Global vfs data structures for nfs.
+struct vops nfs_vops =
+{
+ .vop_create = nfs_create,
+ .vop_open = nfs_open,
+ .vop_close = nfs_close,
+ .vop_getattr = nfs_getattr,
+ .vop_setattr = nfs_setattr,
+ .vop_read = nfs_read,
+ .vop_write = nfs_write,
+ .vop_ioctl = nfs_ioctl,
+//.vop_poll = nfs_poll,
+ .vop_fsync = nfs_fsync,
+ .vop_remove = nfs_remove,
+ .vop_rename = nfs_rename,
+ .vop_mkdir = nfs_mkdir,
+ .vop_rmdir = nfs_rmdir,
+ .vop_readdir = nfs_readdir,
+ .vop_print = nfs_print,
+};
+*/
+
+const struct mountpt_operations nfs_operations =
+{
+ nfs_open, /* open */
+ nfs_close, /* close */
+ nfs_read, /* read */
+ nfs_write, /* write */
+ NULL, /* seek */
+ nfs_ioctl, /* ioctl */
+ nfs_sync, /* sync */
+
+ NULL, /* opendir */
+ NULL, /* closedir */
+ nfs_readdir, /* readdir */
+ NULL, /* rewinddir */
+
+ NULL, /* bind */
+ NULL, /* unbind */
+ NULL, /* statfs */
+
+ nfs_remove, /* unlink */
+ nfs_mkdir, /* mkdir */
+ nfs_rmdir, /* rmdir */
+ nfs_rename, /* rename */
+ nfs_print /* stat */
+};
+
+int nfs_numasync = 0;
+
+/****************************************************************************
+ * External Public Data (this belongs in a header file)
+ ****************************************************************************/
+
+/* Global variables */
+extern uint32_t nfs_true, nfs_false;
+extern uint32_t nfs_xdrneg1;
+extern struct nfsstats nfsstats;
+extern nfstype nfsv3_type[9];
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/* nfs null call from vfs. */
+
+int nfs_null(FAR struct file *filep)
+{
+ int error = 0;
+ struct nfsmount *nm nm = VFSTONFS(filep->f_inode);
+ error = nfs_request(nm, NFSPROC_NULL);
+ return (error);
+}
+
+/* nfs open vnode op
+ * Check to see if the type is ok
+ * and that deletion is not in progress.
+ * For paged in text files, you will need to flush the page cache
+ * if consistency is lost.
+ */
+
+int
+nfs_open(FAR struct file *filp, FAR const char *relpath,
+ int oflags, mode_t mode)
+{
+ struct vop_open_args *ap = v;
+ struct inode *inode;
+ struct nfsnode *np = VTONFS(filp);
+//struct vattr vattr;
+ int error;
+
+ if (vp->v_type != VREG && vp->v_type != VDIR && vp->v_type != VLNK)
+ {
+#ifdef DIAGNOSTIC
+ printf("open eacces vtyp=%d\n", vp->v_type);
+#endif
+ return (EACCES);
+ }
+
+ /* Initialize read and write creds here, for swapfiles
+ * and other paths that don't set the creds themselves.
+ */
+
+ if (np->n_flag & NMODIFIED)
+ {
+ error = nfs_vinvalbuf(vp, V_SAVE, ap->a_cred, ap->a_p);
+ if (error == EINTR)
+ return (error);
+ uvm_vnp_uncache(vp);
+ NFS_INVALIDATE_ATTRCACHE(np);
+ if (vp->v_type == VDIR)
+ np->n_direofoffset = 0;
+ error = VOP_GETATTR(vp, &vattr, ap->a_cred, ap->a_p);
+ if (error)
+ return (error);
+ np->n_mtime = vattr.va_mtime;
+ }
+ else
+ {
+ error = VOP_GETATTR(vp, &vattr, ap->a_cred, ap->a_p);
+ if (error)
+ return (error);
+ if (timespeccmp(&np->n_mtime, &vattr.va_mtime, !=))
+ {
+ if (vp->v_type == VDIR)
+ np->n_direofoffset = 0;
+ error = nfs_vinvalbuf(vp, V_SAVE, ap->a_cred, ap->a_p);
+ if (error == EINTR)
+ return (error);
+ uvm_vnp_uncache(vp);
+ np->n_mtime = vattr.va_mtime;
+ }
+ }
+
+ /* For open/close consistency. */
+
+ NFS_INVALIDATE_ATTRCACHE(np);
+ return (0);
+}
+
+/* nfs close vnode op
+ * What an NFS client should do upon close after writing is a debatable issue.
+ * Most NFS clients push delayed writes to the server upon close, basically for
+ * two reasons:
+ * 1 - So that any write errors may be reported back to the client process
+ * doing the close system call. By far the two most likely errors are
+ * NFSERR_NOSPC and NFSERR_DQUOT to indicate space allocation failure.
+ * 2 - To put a worst case upper bound on cache inconsistency between
+ * multiple clients for the file.
+ * There is also a consistency problem for Version 2 of the protocol w.r.t.
+ * not being able to tell if other clients are writing a file concurrently,
+ * since there is no way of knowing if the changed modify time in the reply
+ * is only due to the write for this client.
+ * (NFS Version 3 provides weak cache consistency data in the reply that
+ * should be sufficient to detect and handle this case.)
+ *
+ * The current code does the following:
+ * for NFS Version 2 - play it safe and flush/invalidate all dirty buffers
+ * for NFS Version 3 - flush dirty buffers to the server but don't invalidate
+ * or commit them (this satisfies 1 and 2 except for the
+ * case where the server crashes after this close but
+ * before the commit RPC, which is felt to be "good
+ * enough". Changing the last argument to nfs_flush() to
+ * a 1 would force a commit operation, if it is felt a
+ * commit is necessary now.
+ */
+
+int
+nfs_close(FAR struct file *filep, const char *relpath, int oflags, mode_t mode)
+{
+ struct vop_close_args *ap = v;
+ struct vnode *vp = ap->a_vp;
+ struct nfsnode *np = VTONFS(vp);
+ int error = 0;
+
+ if (vp->v_type == VREG)
+ {
+ if (np->n_flag & NMODIFIED)
+ {
+ if (NFS_ISV3(vp))
+ {
+ error = nfs_flush(vp, ap->a_cred, MNT_WAIT, ap->a_p, 0);
+ np->n_flag &= ~NMODIFIED;
+ }
+ else
+ error = nfs_vinvalbuf(vp, V_SAVE, ap->a_cred, ap->a_p);
+ NFS_INVALIDATE_ATTRCACHE(np);
+ }
+ if (np->n_flag & NWRITEERR)
+ {
+ np->n_flag &= ~NWRITEERR;
+ error = np->n_error;
+ }
+ }
+ return (error);
+}
+
+/* nfs getattr call from vfs. */
+
+int nfs_getattr(void *v)
+{
+ struct vop_getattr_args *ap = v;
+ struct vnode *vp = ap->a_vp;
+ struct nfsnode *np = VTONFS(vp);
+ struct nfsm_info info;
+ int32_t t1;
+ int error = 0;
+
+ info.nmi_v3 = NFS_ISV3(vp);
+
+ /* Update local times for special files. */
+
+ if (np->n_flag & (NACC | NUPD))
+ np->n_flag |= NCHG;
+
+ /* First look in the cache. */
+
+ if (nfs_getattrcache(vp, ap->a_vap) == 0)
+ return (0);
+
+ nfsstats.rpccnt[NFSPROC_GETATTR]++;
+ info.nmi_mb = info.nmi_mreq = nfsm_reqhead(NFSX_FH(info.nmi_v3));
+ nfsm_fhtom(&info, vp, info.nmi_v3);
+ info.nmi_procp = ap->a_p;
+ info.nmi_cred = ap->a_cred;
+ error = nfs_request(vp, NFSPROC_GETATTR, &info);
+ if (!error)
+ nfsm_loadattr(vp, ap->a_vap);
+ m_freem(info.nmi_mrep);
+nfsmout:
+ return (error);
+}
+
+/* nfs setattr call. */
+
+int nfs_setattr(void *v)
+{
+ struct vop_setattr_args *ap = v;
+ struct vnode *vp = ap->a_vp;
+ struct nfsnode *np = VTONFS(vp);
+ struct vattr *vap = ap->a_vap;
+ int hint = NOTE_ATTRIB;
+ int error = 0;
+ u_quad_t tsize = 0;
+
+ /* Setting of flags is not supported. */
+
+ if (vap->va_flags != VNOVAL)
+ return (EOPNOTSUPP);
+
+ /* Disallow write attempts if the filesystem is mounted read-only. */
+
+ if ((vap->va_uid != (uid_t) VNOVAL ||
+ vap->va_gid != (gid_t) VNOVAL || vap->va_atime.tv_sec != VNOVAL ||
+ vap->va_mtime.tv_sec != VNOVAL || vap->va_mode != (mode_t) VNOVAL) &&
+ (vp->v_mount->mnt_flag & MNT_RDONLY))
+ return (EROFS);
+ if (vap->va_size != VNOVAL)
+ {
+ switch (vp->v_type)
+ {
+ case VDIR:
+ return (EISDIR);
+ case VCHR:
+ case VBLK:
+ case VSOCK:
+ case VFIFO:
+ if (vap->va_mtime.tv_sec == VNOVAL &&
+ vap->va_atime.tv_sec == VNOVAL &&
+ vap->va_mode == (mode_t) VNOVAL &&
+ vap->va_uid == (uid_t) VNOVAL && vap->va_gid == (gid_t) VNOVAL)
+ return (0);
+ vap->va_size = VNOVAL;
+ break;
+ default:
+ /* Disallow write attempts if the filesystem is
+ * mounted read-only.
+ */
+
+ if (vp->v_mount->mnt_flag & MNT_RDONLY)
+ return (EROFS);
+ if (vap->va_size == 0)
+ error = nfs_vinvalbuf(vp, 0, ap->a_cred, ap->a_p);
+ else
+ error = nfs_vinvalbuf(vp, V_SAVE, ap->a_cred, ap->a_p);
+ if (error)
+ return (error);
+ tsize = np->n_size;
+ np->n_size = np->n_vattr.va_size = vap->va_size;
+ uvm_vnp_setsize(vp, np->n_size);
+ };
+ }
+ else if ((vap->va_mtime.tv_sec != VNOVAL ||
+ vap->va_atime.tv_sec != VNOVAL) &&
+ vp->v_type == VREG &&
+ (error = nfs_vinvalbuf(vp, V_SAVE, ap->a_cred, ap->a_p)) == EINTR)
+ return (error);
+ error = nfs_setattrrpc(vp, vap, ap->a_cred, ap->a_p);
+ if (error && vap->va_size != VNOVAL)
+ {
+ np->n_size = np->n_vattr.va_size = tsize;
+ uvm_vnp_setsize(vp, np->n_size);
+ }
+
+ if (vap->va_size != VNOVAL && vap->va_size < tsize)
+ hint |= NOTE_TRUNCATE;
+
+ VN_KNOTE(vp, hint); /* XXX setattrrpc? */
+
+ return (error);
+}
+
+/* Do an nfs setattr rpc. */
+
+int
+nfs_setattrrpc(struct vnode *vp, struct vattr *vap, struct ucred *cred,
+ struct proc *procp)
+{
+ struct nfsv2_sattr *sp;
+ struct nfsm_info info;
+ int32_t t1;
+ caddr_t cp2;
+ u_int32_t *tl;
+ int error = 0, wccflag = NFSV3_WCCRATTR;
+ int v3 = NFS_ISV3(vp);
+
+ info.nmi_v3 = NFS_ISV3(vp);
+
+ nfsstats.rpccnt[NFSPROC_SETATTR]++;
+ info.nmi_mb = info.nmi_mreq = nfsm_reqhead(NFSX_FH(v3) + NFSX_SATTR(v3));
+ nfsm_fhtom(&info, vp, v3);
+
+ if (info.nmi_v3)
+ {
+ nfsm_v3attrbuild(&info.nmi_mb, vap, 1);
+ tl = nfsm_build(&info.nmi_mb, NFSX_UNSIGNED);
+ *tl = nfs_false;
+ }
+ else
+ {
+ sp = nfsm_build(&info.nmi_mb, NFSX_V2SATTR);
+ if (vap->va_mode == (mode_t) VNOVAL)
+ sp->sa_mode = nfs_xdrneg1;
+ else
+ sp->sa_mode = vtonfsv2_mode(vp->v_type, vap->va_mode);
+ if (vap->va_uid == (uid_t) VNOVAL)
+ sp->sa_uid = nfs_xdrneg1;
+ else
+ sp->sa_uid = txdr_unsigned(vap->va_uid);
+ if (vap->va_gid == (gid_t) VNOVAL)
+ sp->sa_gid = nfs_xdrneg1;
+ else
+ sp->sa_gid = txdr_unsigned(vap->va_gid);
+ sp->sa_size = txdr_unsigned(vap->va_size);
+ txdr_nfsv2time(&vap->va_atime, &sp->sa_atime);
+ txdr_nfsv2time(&vap->va_mtime, &sp->sa_mtime);
+ }
+
+ info.nmi_procp = procp;
+ info.nmi_cred = cred;
+ error = nfs_request(vp, NFSPROC_SETATTR, &info);
+
+ if (info.nmi_v3)
+ nfsm_wcc_data(vp, wccflag);
+ else if (error == 0)
+ nfsm_loadattr(vp, NULL);
+
+ m_freem(info.nmi_mrep);
+nfsmout:
+ return (error);
+}
+
+/* nfs lookup call, one step at a time...
+ * First look in cache
+ * If not found, unlock the directory nfsnode and do the rpc
+ */
+
+int nfs_lookup(void *v)
+{
+ struct vop_lookup_args *ap = v;
+ struct componentname *cnp = ap->a_cnp;
+ struct vnode *dvp = ap->a_dvp;
+ struct vnode **vpp = ap->a_vpp;
+ struct proc *p = cnp->cn_proc;
+ struct nfsm_info info;
+ int flags;
+ struct vnode *newvp;
+ u_int32_t *tl;
+ int32_t t1;
+ struct nfsmount *nmp;
+ caddr_t cp2;
+ long len;
+ nfsfh_t *fhp;
+ struct nfsnode *np;
+ int lockparent, wantparent, error = 0, attrflag, fhsize;
+
+ info.nmi_v3 = NFS_ISV3(dvp);
+
+ cnp->cn_flags &= ~PDIRUNLOCK;
+ flags = cnp->cn_flags;
+
+ *vpp = NULLVP;
+ if ((flags & ISLASTCN) && (dvp->v_mount->mnt_flag & MNT_RDONLY) &&
+ (cnp->cn_nameiop == DELETE || cnp->cn_nameiop == RENAME))
+ return (EROFS);
+ if (dvp->v_type != VDIR)
+ return (ENOTDIR);
+ lockparent = flags & LOCKPARENT;
+ wantparent = flags & (LOCKPARENT | WANTPARENT);
+ nmp = VFSTONFS(dvp->v_mount);
+ np = VTONFS(dvp);
+
+ /* Before tediously performing a linear scan of the directory,
+ * check the name cache to see if the directory/name pair
+ * we are looking for is known already.
+ * If the directory/name pair is found in the name cache,
+ * we have to ensure the directory has not changed from
+ * the time the cache entry has been created. If it has,
+ * the cache entry has to be ignored.
+ */
+
+ if ((error = cache_lookup(dvp, vpp, cnp)) >= 0)
+ {
+ struct vattr vattr;
+ int err2;
+
+ if (error && error != ENOENT)
+ {
+ *vpp = NULLVP;
+ return (error);
+ }
+
+ if (cnp->cn_flags & PDIRUNLOCK)
+ {
+ err2 = vn_lock(dvp, LK_EXCLUSIVE | LK_RETRY, p);
+ if (err2 != 0)
+ {
+ *vpp = NULLVP;
+ return (err2);
+ }
+ cnp->cn_flags &= ~PDIRUNLOCK;
+ }
+
+ err2 = VOP_ACCESS(dvp, VEXEC, cnp->cn_cred, cnp->cn_proc);
+ if (err2 != 0)
+ {
+ if (error == 0)
+ {
+ if (*vpp != dvp)
+ vput(*vpp);
+ else
+ vrele(*vpp);
+ }
+ *vpp = NULLVP;
+ return (err2);
+ }
+
+ if (error == ENOENT)
+ {
+ if (!VOP_GETATTR(dvp, &vattr, cnp->cn_cred,
+ cnp->cn_proc) && vattr.va_mtime.tv_sec ==
+ VTONFS(dvp)->n_ctime)
+ return (ENOENT);
+ cache_purge(dvp);
+ np->n_ctime = 0;
+ goto dorpc;
+ }
+
+ newvp = *vpp;
+ if (!VOP_GETATTR(newvp, &vattr, cnp->cn_cred, cnp->cn_proc)
+ && vattr.va_ctime.tv_sec == VTONFS(newvp)->n_ctime)
+ {
+ nfsstats.lookupcache_hits++;
+ if (cnp->cn_nameiop != LOOKUP && (flags & ISLASTCN))
+ cnp->cn_flags |= SAVENAME;
+ if ((!lockparent || !(flags & ISLASTCN)) && newvp != dvp)
+ VOP_UNLOCK(dvp, 0, p);
+ return (0);
+ }
+ cache_purge(newvp);
+ if (newvp != dvp)
+ vput(newvp);
+ else
+ vrele(newvp);
+ *vpp = NULLVP;
+ }
+dorpc:
+ error = 0;
+ newvp = NULLVP;
+ nfsstats.lookupcache_misses++;
+ nfsstats.rpccnt[NFSPROC_LOOKUP]++;
+ len = cnp->cn_namelen;
+ info.nmi_mb = info.nmi_mreq = nfsm_reqhead(NFSX_FH(info.nmi_v3) +
+ NFSX_UNSIGNED + nfsm_rndup(len));
+ nfsm_fhtom(&info, dvp, info.nmi_v3);
+ nfsm_strtom(cnp->cn_nameptr, len, NFS_MAXNAMLEN);
+
+ info.nmi_procp = cnp->cn_proc;
+ info.nmi_cred = cnp->cn_cred;
+ error = nfs_request(dvp, NFSPROC_LOOKUP, &info);
+
+ if (error)
+ {
+ if (info.nmi_v3)
+ nfsm_postop_attr(dvp, attrflag);
+ m_freem(info.nmi_mrep);
+ goto nfsmout;
+ }
+
+ nfsm_getfh(fhp, fhsize, info.nmi_v3);
+
+ /* Handle RENAME case... */
+
+ if (cnp->cn_nameiop == RENAME && wantparent && (flags & ISLASTCN))
+ {
+ if (NFS_CMPFH(np, fhp, fhsize))
+ {
+ m_freem(info.nmi_mrep);
+ return (EISDIR);
+ }
+ error = nfs_nget(dvp->v_mount, fhp, fhsize, &np);
+ if (error)
+ {
+ m_freem(info.nmi_mrep);
+ return (error);
+ }
+ newvp = NFSTOV(np);
+ if (info.nmi_v3)
+ {
+ nfsm_postop_attr(newvp, attrflag);
+ nfsm_postop_attr(dvp, attrflag);
+ }
+ else
+ nfsm_loadattr(newvp, NULL);
+ *vpp = newvp;
+ m_freem(info.nmi_mrep);
+ cnp->cn_flags |= SAVENAME;
+ if (!lockparent)
+ {
+ VOP_UNLOCK(dvp, 0, p);
+ cnp->cn_flags |= PDIRUNLOCK;
+ }
+ return (0);
+ }
+
+ /* The postop attr handling is duplicated for each if case,
+ * because it should be done while dvp is locked (unlocking
+ * dvp is different for each case).
+ */
+
+ if (NFS_CMPFH(np, fhp, fhsize))
+ {
+ vref(dvp);
+ newvp = dvp;
+ if (info.nmi_v3)
+ {
+ nfsm_postop_attr(newvp, attrflag);
+ nfsm_postop_attr(dvp, attrflag);
+ }
+ else
+ nfsm_loadattr(newvp, NULL);
+ }
+ else if (flags & ISDOTDOT)
+ {
+ VOP_UNLOCK(dvp, 0, p);
+ cnp->cn_flags |= PDIRUNLOCK;
+
+ error = nfs_nget(dvp->v_mount, fhp, fhsize, &np);
+ if (error)
+ {
+ if (vn_lock(dvp, LK_EXCLUSIVE | LK_RETRY, p) == 0)
+ cnp->cn_flags &= ~PDIRUNLOCK;
+ m_freem(info.nmi_mrep);
+ return (error);
+ }
+ newvp = NFSTOV(np);
+
+ if (info.nmi_v3)
+ {
+ nfsm_postop_attr(newvp, attrflag);
+ nfsm_postop_attr(dvp, attrflag);
+ }
+ else
+ nfsm_loadattr(newvp, NULL);
+
+ if (lockparent && (flags & ISLASTCN))
+ {
+ if ((error = vn_lock(dvp, LK_EXCLUSIVE, p)))
+ {
+ m_freem(info.nmi_mrep);
+ vput(newvp);
+ return error;
+ }
+ cnp->cn_flags &= ~PDIRUNLOCK;
+ }
+
+ }
+ else
+ {
+ error = nfs_nget(dvp->v_mount, fhp, fhsize, &np);
+ if (error)
+ {
+ m_freem(info.nmi_mrep);
+ return error;
+ }
+ newvp = NFSTOV(np);
+ if (info.nmi_v3)
+ {
+ nfsm_postop_attr(newvp, attrflag);
+ nfsm_postop_attr(dvp, attrflag);
+ }
+ else
+ nfsm_loadattr(newvp, NULL);
+ if (!lockparent || !(flags & ISLASTCN))
+ {
+ VOP_UNLOCK(dvp, 0, p);
+ cnp->cn_flags |= PDIRUNLOCK;
+ }
+ }
+
+ if (cnp->cn_nameiop != LOOKUP && (flags & ISLASTCN))
+ cnp->cn_flags |= SAVENAME;
+ if ((cnp->cn_flags & MAKEENTRY) &&
+ (cnp->cn_nameiop != DELETE || !(flags & ISLASTCN)))
+ {
+ nfs_cache_enter(dvp, newvp, cnp);
+ }
+
+ *vpp = newvp;
+ m_freem(info.nmi_mrep);
+
+nfsmout:
+ if (error)
+ {
+ /* We get here only because of errors returned by
+ * the RPC. Otherwise we'll have returned above
+ * (the nfsm_* macros will jump to nfsmout
+ * on error).
+ */
+
+ if (error == ENOENT && (cnp->cn_flags & MAKEENTRY) &&
+ cnp->cn_nameiop != CREATE)
+ {
+ nfs_cache_enter(dvp, NULL, cnp);
+ }
+ if (newvp != NULLVP)
+ {
+ vrele(newvp);
+ if (newvp != dvp)
+ VOP_UNLOCK(newvp, 0, p);
+ }
+ if ((cnp->cn_nameiop == CREATE || cnp->cn_nameiop == RENAME) &&
+ (flags & ISLASTCN) && error == ENOENT)
+ {
+ if (dvp->v_mount->mnt_flag & MNT_RDONLY)
+ error = EROFS;
+ else
+ error = EJUSTRETURN;
+ }
+ if (cnp->cn_nameiop != LOOKUP && (flags & ISLASTCN))
+ cnp->cn_flags |= SAVENAME;
+ *vpp = NULL;
+ }
+ return (error);
+}
+
+/* nfs read call.
+ * Just call nfs_bioread() to do the work.
+ */
+
+int nfs_read(void *v)
+{
+ struct vop_read_args *ap = v;
+ struct vnode *vp = ap->a_vp;
+
+ if (vp->v_type != VREG)
+ return (EPERM);
+ return (nfs_bioread(vp, ap->a_uio, ap->a_ioflag, ap->a_cred));
+}
+
+/* nfs readlink call */
+
+int nfs_readlink(void *v)
+{
+ struct vop_readlink_args *ap = v;
+ struct vnode *vp = ap->a_vp;
+
+ if (vp->v_type != VLNK)
+ return (EPERM);
+ return (nfs_bioread(vp, ap->a_uio, 0, ap->a_cred));
+}
+
+/*Do a readlink rpc.
+ * Called by nfs_doio() from below the buffer cache.
+ */
+
+int nfs_readlinkrpc(struct vnode *vp, struct uio *uiop, struct ucred *cred)
+{
+ struct nfsm_info info;
+ u_int32_t *tl;
+ int32_t t1;
+ caddr_t cp2;
+ int error = 0, len, attrflag;
+
+ info.nmi_v3 = NFS_ISV3(vp);
+
+ nfsstats.rpccnt[NFSPROC_READLINK]++;
+ info.nmi_mb = info.nmi_mreq = nfsm_reqhead(NFSX_FH(info.nmi_v3));
+ nfsm_fhtom(&info, vp, info.nmi_v3);
+
+ info.nmi_procp = curproc;
+ info.nmi_cred = cred;
+ error = nfs_request(vp, NFSPROC_READLINK, &info);
+
+ if (info.nmi_v3)
+ nfsm_postop_attr(vp, attrflag);
+ if (!error)
+ {
+ nfsm_strsiz(len, NFS_MAXPATHLEN);
+ nfsm_mtouio(uiop, len);
+ }
+
+ m_freem(info.nmi_mrep);
+
+nfsmout:
+ return (error);
+}
+
+/*nfs read rpc call
+ * Ditto above
+ */
+
+int nfs_readrpc(struct vnode *vp, struct uio *uiop)
+{
+ struct nfsm_info info;
+ u_int32_t *tl;
+ int32_t t1;
+ caddr_t cp2;
+ struct nfsmount *nmp;
+ int error = 0, len, retlen, tsiz, eof, attrflag;
+
+ info.nmi_v3 = NFS_ISV3(vp);
+
+ eof = 0;
+
+ nmp = VFSTONFS(vp->v_mount);
+ tsiz = uiop->uio_resid;
+ if (uiop->uio_offset + tsiz > 0xffffffff && !info.nmi_v3)
+ return (EFBIG);
+ while (tsiz > 0)
+ {
+ nfsstats.rpccnt[NFSPROC_READ]++;
+ len = (tsiz > nmp->nm_rsize) ? nmp->nm_rsize : tsiz;
+ info.nmi_mb = info.nmi_mreq = nfsm_reqhead(NFSX_FH(info.nmi_v3) +
+ NFSX_UNSIGNED * 3);
+ nfsm_fhtom(&info, vp, info.nmi_v3);
+ tl = nfsm_build(&info.nmi_mb, NFSX_UNSIGNED * 3);
+ if (info.nmi_v3)
+ {
+ txdr_hyper(uiop->uio_offset, tl);
+ *(tl + 2) = txdr_unsigned(len);
+ }
+ else
+ {
+ *tl++ = txdr_unsigned(uiop->uio_offset);
+ *tl++ = txdr_unsigned(len);
+ *tl = 0;
+ }
+
+ info.nmi_procp = curproc;
+ info.nmi_cred = VTONFS(vp)->n_rcred;
+ error = nfs_request(vp, NFSPROC_READ, &info);
+ if (info.nmi_v3)
+ nfsm_postop_attr(vp, attrflag);
+ if (error)
+ {
+ m_freem(info.nmi_mrep);
+ goto nfsmout;
+ }
+
+ if (info.nmi_v3)
+ {
+ nfsm_dissect(tl, u_int32_t *, 2 * NFSX_UNSIGNED);
+ eof = fxdr_unsigned(int, *(tl + 1));
+ }
+ else
+ {
+ nfsm_loadattr(vp, NULL);
+ }
+
+ nfsm_strsiz(retlen, nmp->nm_rsize);
+ nfsm_mtouio(uiop, retlen);
+ m_freem(info.nmi_mrep);
+ tsiz -= retlen;
+ if (info.nmi_v3)
+ {
+ if (eof || retlen == 0)
+ tsiz = 0;
+ }
+ else if (retlen < len)
+ tsiz = 0;
+ }
+
+nfsmout:
+ return (error);
+}
+
+/* nfs write call */
+
+int
+nfs_writerpc(struct vnode *vp, struct uio *uiop, int *iomode, int *must_commit)
+{
+ struct nfsm_info info;
+ u_int32_t *tl;
+ int32_t t1, backup;
+ caddr_t cp2;
+ struct nfsmount *nmp = VFSTONFS(vp->v_mount);
+ int error = 0, len, tsiz, wccflag = NFSV3_WCCRATTR, rlen, commit;
+ int committed = NFSV3WRITE_FILESYNC;
+
+ info.nmi_v3 = NFS_ISV3(vp);
+
+#ifdef DIAGNOSTIC
+ if (uiop->uio_iovcnt != 1)
+ panic("nfs: writerpc iovcnt > 1");
+#endif
+ *must_commit = 0;
+ tsiz = uiop->uio_resid;
+ if (uiop->uio_offset + tsiz > 0xffffffff && !info.nmi_v3)
+ return (EFBIG);
+ while (tsiz > 0)
+ {
+ nfsstats.rpccnt[NFSPROC_WRITE]++;
+ len = (tsiz > nmp->nm_wsize) ? nmp->nm_wsize : tsiz;
+ info.nmi_mb = info.nmi_mreq = nfsm_reqhead(NFSX_FH(info.nmi_v3)
+ + 5 * NFSX_UNSIGNED +
+ nfsm_rndup(len));
+ nfsm_fhtom(&info, vp, info.nmi_v3);
+ if (info.nmi_v3)
+ {
+ tl = nfsm_build(&info.nmi_mb, 5 * NFSX_UNSIGNED);
+ txdr_hyper(uiop->uio_offset, tl);
+ tl += 2;
+ *tl++ = txdr_unsigned(len);
+ *tl++ = txdr_unsigned(*iomode);
+ *tl = txdr_unsigned(len);
+ }
+ else
+ {
+ u_int32_t x;
+
+ tl = nfsm_build(&info.nmi_mb, 4 * NFSX_UNSIGNED);
+
+ /* Set both "begin" and "current" to non-garbage. */
+
+ x = txdr_unsigned((u_int32_t) uiop->uio_offset);
+ *tl++ = x; /* "begin offset" */
+ *tl++ = x; /* "current offset" */
+ x = txdr_unsigned(len);
+ *tl++ = x; /* total to this offset */
+ *tl = x; /* size of this write */
+
+ }
+ nfsm_uiotombuf(&info.nmi_mb, uiop, len);
+
+ info.nmi_procp = curproc;
+ info.nmi_cred = VTONFS(vp)->n_wcred;
+ error = nfs_request(vp, NFSPROC_WRITE, &info);
+ if (info.nmi_v3)
+ {
+ wccflag = NFSV3_WCCCHK;
+ nfsm_wcc_data(vp, wccflag);
+ }
+
+ if (error)
+ {
+ m_freem(info.nmi_mrep);
+ goto nfsmout;
+ }
+
+ if (info.nmi_v3)
+ {
+ wccflag = NFSV3_WCCCHK;
+ nfsm_dissect(tl, u_int32_t *, 2 * NFSX_UNSIGNED + NFSX_V3WRITEVERF);
+ rlen = fxdr_unsigned(int, *tl++);
+ if (rlen == 0)
+ {
+ error = NFSERR_IO;
+ break;
+ }
+ else if (rlen < len)
+ {
+ backup = len - rlen;
+ uiop->uio_iov->iov_base =
+ (char *)uiop->uio_iov->iov_base - backup;
+ uiop->uio_iov->iov_len += backup;
+ uiop->uio_offset -= backup;
+ uiop->uio_resid += backup;
+ len = rlen;
+ }
+ commit = fxdr_unsigned(int, *tl++);
+
+ /* Return the lowest committment level
+ * obtained by any of the RPCs.
+ */
+
+ if (committed == NFSV3WRITE_FILESYNC)
+ committed = commit;
+ else if (committed == NFSV3WRITE_DATASYNC &&
+ commit == NFSV3WRITE_UNSTABLE)
+ committed = commit;
+ if ((nmp->nm_flag & NFSMNT_HASWRITEVERF) == 0)
+ {
+ bcopy((caddr_t) tl, (caddr_t) nmp->nm_verf, NFSX_V3WRITEVERF);
+ nmp->nm_flag |= NFSMNT_HASWRITEVERF;
+ }
+ else if (bcmp((caddr_t) tl, (caddr_t) nmp->nm_verf, NFSX_V3WRITEVERF))
+ {
+ *must_commit = 1;
+ bcopy((caddr_t) tl, (caddr_t) nmp->nm_verf, NFSX_V3WRITEVERF);
+ }
+ }
+ else
+ {
+ nfsm_loadattr(vp, NULL);
+ }
+ if (wccflag)
+ VTONFS(vp)->n_mtime = VTONFS(vp)->n_vattr.va_mtime;
+ m_freem(info.nmi_mrep);
+ tsiz -= len;
+ }
+nfsmout:
+ *iomode = committed;
+ if (error)
+ uiop->uio_resid = tsiz;
+ return (error);
+}
+
+/* nfs mknod rpc
+ * For NFS v2 this is a kludge. Use a create rpc but with the IFMT bits of the
+ * mode set to specify the file type and the size field for rdev.
+ */
+
+int
+nfs_mknodrpc(struct vnode *dvp, struct vnode **vpp, struct componentname *cnp,
+ struct vattr *vap)
+{
+ struct nfsv2_sattr *sp;
+ struct nfsm_info info;
+ u_int32_t *tl;
+ int32_t t1;
+ struct vnode *newvp = NULL;
+ struct nfsnode *np = NULL;
+ char *cp2;
+ int error = 0, wccflag = NFSV3_WCCRATTR, gotvp = 0;
+ u_int32_t rdev;
+
+ info.nmi_v3 = NFS_ISV3(dvp);
+
+ if (vap->va_type == VCHR || vap->va_type == VBLK)
+ rdev = txdr_unsigned(vap->va_rdev);
+ else if (vap->va_type == VFIFO || vap->va_type == VSOCK)
+ rdev = nfs_xdrneg1;
+ else
+ {
+ VOP_ABORTOP(dvp, cnp);
+ vput(dvp);
+ return (EOPNOTSUPP);
+ }
+ nfsstats.rpccnt[NFSPROC_MKNOD]++;
+ info.nmi_mb = info.nmi_mreq = nfsm_reqhead(NFSX_FH(info.nmi_v3) +
+ 4 * NFSX_UNSIGNED +
+ nfsm_rndup(cnp->cn_namelen) +
+ NFSX_SATTR(info.nmi_v3));
+ nfsm_fhtom(&info, dvp, info.nmi_v3);
+ nfsm_strtom(cnp->cn_nameptr, cnp->cn_namelen, NFS_MAXNAMLEN);
+
+ if (info.nmi_v3)
+ {
+ tl = nfsm_build(&info.nmi_mb, NFSX_UNSIGNED);
+ *tl++ = vtonfsv3_type(vap->va_type);
+ nfsm_v3attrbuild(&info.nmi_mb, vap, 0);
+ if (vap->va_type == VCHR || vap->va_type == VBLK)
+ {
+ tl = nfsm_build(&info.nmi_mb, 2 * NFSX_UNSIGNED);
+ *tl++ = txdr_unsigned(major(vap->va_rdev));
+ *tl = txdr_unsigned(minor(vap->va_rdev));
+ }
+ }
+ else
+ {
+ sp = nfsm_build(&info.nmi_mb, NFSX_V2SATTR);
+ sp->sa_mode = vtonfsv2_mode(vap->va_type, vap->va_mode);
+ sp->sa_uid = nfs_xdrneg1;
+ sp->sa_gid = nfs_xdrneg1;
+ sp->sa_size = rdev;
+ txdr_nfsv2time(&vap->va_atime, &sp->sa_atime);
+ txdr_nfsv2time(&vap->va_mtime, &sp->sa_mtime);
+ }
+
+ KASSERT(cnp->cn_proc == curproc);
+ info.nmi_procp = cnp->cn_proc;
+ info.nmi_cred = cnp->cn_cred;
+ error = nfs_request(dvp, NFSPROC_MKNOD, &info);
+ if (!error)
+ {
+ nfsm_mtofh(dvp, newvp, info.nmi_v3, gotvp);
+ if (!gotvp)
+ {
+ if (newvp)
+ {
+ vrele(newvp);
+ newvp = NULL;
+ }
+ error = nfs_lookitup(dvp, cnp->cn_nameptr,
+ cnp->cn_namelen, cnp->cn_cred, cnp->cn_proc,
+ &np);
+ if (!error)
+ newvp = NFSTOV(np);
+ }
+ }
+ if (info.nmi_v3)
+ nfsm_wcc_data(dvp, wccflag);
+ m_freem(info.nmi_mrep);
+
+nfsmout:
+ if (error)
+ {
+ if (newvp)
+ vrele(newvp);
+ }
+ else
+ {
+ if (cnp->cn_flags & MAKEENTRY)
+ nfs_cache_enter(dvp, newvp, cnp);
+ *vpp = newvp;
+ }
+ pool_put(&namei_pool, cnp->cn_pnbuf);
+ VTONFS(dvp)->n_flag |= NMODIFIED;
+ if (!wccflag)
+ NFS_INVALIDATE_ATTRCACHE(VTONFS(dvp));
+ vrele(dvp);
+ return (error);
+}
+
+/* nfs mknod vop
+ * just call nfs_mknodrpc() to do the work.
+ */
+
+int nfs_mknod(void *v)
+{
+ struct vop_mknod_args *ap = v;
+ struct vnode *newvp;
+ int error;
+
+ error = nfs_mknodrpc(ap->a_dvp, &newvp, ap->a_cnp, ap->a_vap);
+ if (!error)
+ vrele(newvp);
+
+ VN_KNOTE(ap->a_dvp, NOTE_WRITE);
+
+ return (error);
+}
+
+int nfs_create(void *v)
+{
+ struct vop_create_args *ap = v;
+ struct vnode *dvp = ap->a_dvp;
+ struct vattr *vap = ap->a_vap;
+ struct componentname *cnp = ap->a_cnp;
+ struct nfsv2_sattr *sp;
+ struct nfsm_info info;
+ u_int32_t *tl;
+ int32_t t1;
+ struct nfsnode *np = NULL;
+ struct vnode *newvp = NULL;
+ caddr_t cp2;
+ int error = 0, wccflag = NFSV3_WCCRATTR, gotvp = 0, fmode = 0;
+
+ info.nmi_v3 = NFS_ISV3(dvp);
+
+ /*
+ * Oops, not for me..
+ */
+ if (vap->va_type == VSOCK)
+ return (nfs_mknodrpc(dvp, ap->a_vpp, cnp, vap));
+
+ if (vap->va_vaflags & VA_EXCLUSIVE)
+ fmode |= O_EXCL;
+
+again:
+ nfsstats.rpccnt[NFSPROC_CREATE]++;
+ info.nmi_mb = info.nmi_mreq = nfsm_reqhead(NFSX_FH(info.nmi_v3) +
+ 2 * NFSX_UNSIGNED +
+ nfsm_rndup(cnp->cn_namelen) +
+ NFSX_SATTR(info.nmi_v3));
+ nfsm_fhtom(&info, dvp, info.nmi_v3);
+ nfsm_strtom(cnp->cn_nameptr, cnp->cn_namelen, NFS_MAXNAMLEN);
+ if (info.nmi_v3)
+ {
+ tl = nfsm_build(&info.nmi_mb, NFSX_UNSIGNED);
+ if (fmode & O_EXCL)
+ {
+ *tl = txdr_unsigned(NFSV3CREATE_EXCLUSIVE);
+ tl = nfsm_build(&info.nmi_mb, NFSX_V3CREATEVERF);
+ *tl++ = arc4random();
+ *tl = arc4random();
+ }
+ else
+ {
+ *tl = txdr_unsigned(NFSV3CREATE_UNCHECKED);
+ nfsm_v3attrbuild(&info.nmi_mb, vap, 0);
+ }
+ }
+ else
+ {
+ sp = nfsm_build(&info.nmi_mb, NFSX_V2SATTR);
+ sp->sa_mode = vtonfsv2_mode(vap->va_type, vap->va_mode);
+ sp->sa_uid = nfs_xdrneg1;
+ sp->sa_gid = nfs_xdrneg1;
+ sp->sa_size = 0;
+ txdr_nfsv2time(&vap->va_atime, &sp->sa_atime);
+ txdr_nfsv2time(&vap->va_mtime, &sp->sa_mtime);
+ }
+
+ KASSERT(cnp->cn_proc == curproc);
+ info.nmi_procp = cnp->cn_proc;
+ info.nmi_cred = cnp->cn_cred;
+ error = nfs_request(dvp, NFSPROC_CREATE, &info);
+ if (!error)
+ {
+ nfsm_mtofh(dvp, newvp, info.nmi_v3, gotvp);
+ if (!gotvp)
+ {
+ if (newvp)
+ {
+ vrele(newvp);
+ newvp = NULL;
+ }
+ error = nfs_lookitup(dvp, cnp->cn_nameptr,
+ cnp->cn_namelen, cnp->cn_cred, cnp->cn_proc,
+ &np);
+ if (!error)
+ newvp = NFSTOV(np);
+ }
+ }
+ if (info.nmi_v3)
+ nfsm_wcc_data(dvp, wccflag);
+ m_freem(info.nmi_mrep);
+
+nfsmout:
+ if (error)
+ {
+ if (info.nmi_v3 && (fmode & O_EXCL) && error == NFSERR_NOTSUPP)
+ {
+ fmode &= ~O_EXCL;
+ goto again;
+ }
+ if (newvp)
+ vrele(newvp);
+ }
+ else if (info.nmi_v3 && (fmode & O_EXCL))
+ error = nfs_setattrrpc(newvp, vap, cnp->cn_cred, cnp->cn_proc);
+ if (!error)
+ {
+ if (cnp->cn_flags & MAKEENTRY)
+ nfs_cache_enter(dvp, newvp, cnp);
+ *ap->a_vpp = newvp;
+ }
+ pool_put(&namei_pool, cnp->cn_pnbuf);
+ VTONFS(dvp)->n_flag |= NMODIFIED;
+ if (!wccflag)
+ NFS_INVALIDATE_ATTRCACHE(VTONFS(dvp));
+ VN_KNOTE(ap->a_dvp, NOTE_WRITE);
+ vrele(dvp);
+ return (error);
+}
+
+/* nfs file remove call
+ * To try and make nfs semantics closer to ufs semantics, a file that has
+ * other processes using the vnode is renamed instead of removed and then
+ * removed later on the last close.
+ * - If v_usecount > 1
+ * If a rename is not already in the works
+ * call nfs_sillyrename() to set it up
+ * else
+ * do the remove rpc
+ */
+
+int nfs_remove(void *v)
+{
+ struct vop_remove_args *ap = v;
+ struct vnode *vp = ap->a_vp;
+ struct vnode *dvp = ap->a_dvp;
+ struct componentname *cnp = ap->a_cnp;
+ struct nfsnode *np = VTONFS(vp);
+ int error = 0;
+ struct vattr vattr;
+
+#ifdef DIAGNOSTIC
+ if ((cnp->cn_flags & HASBUF) == 0)
+ panic("nfs_remove: no name");
+ if (vp->v_usecount < 1)
+ panic("nfs_remove: bad v_usecount");
+#endif
+ if (vp->v_type == VDIR)
+ error = EPERM;
+ else if (vp->v_usecount == 1 || (np->n_sillyrename &&
+ VOP_GETATTR(vp, &vattr, cnp->cn_cred,
+ cnp->cn_proc) == 0 &&
+ vattr.va_nlink > 1))
+ {
+ /* Purge the name cache so that the chance of a lookup for
+ * the name succeeding while the remove is in progress is
+ * minimized. Without node locking it can still happen, such
+ * that an I/O op returns ESTALE, but since you get this if
+ * another host removes the file..
+ */
+
+ cache_purge(vp);
+
+ /* throw away biocache buffers, mainly to avoid
+ * unnecessary delayed writes later.
+ */
+ error = nfs_vinvalbuf(vp, 0, cnp->cn_cred, cnp->cn_proc);
+ /* Do the rpc */
+ if (error != EINTR)
+ error = nfs_removerpc(dvp, cnp->cn_nameptr,
+ cnp->cn_namelen, cnp->cn_cred, cnp->cn_proc);
+
+ /* Kludge City: If the first reply to the remove rpc is lost..
+ * the reply to the retransmitted request will be ENOENT
+ * since the file was in fact removed
+ * Therefore, we cheat and return success.
+ */
+
+ if (error == ENOENT)
+ error = 0;
+ }
+ else if (!np->n_sillyrename)
+ error = nfs_sillyrename(dvp, vp, cnp);
+ pool_put(&namei_pool, cnp->cn_pnbuf);
+ NFS_INVALIDATE_ATTRCACHE(np);
+ vrele(dvp);
+ vrele(vp);
+
+ VN_KNOTE(vp, NOTE_DELETE);
+ VN_KNOTE(dvp, NOTE_WRITE);
+
+ return (error);
+}
+
+/* nfs file remove rpc called from nfs_inactive */
+
+int nfs_removeit(struct sillyrename *sp)
+{
+ /* Make sure that the directory vnode is still valid.
+ * XXX we should lock sp->s_dvp here.
+ *
+ * NFS can potentially try to nuke a silly *after* the directory
+ * has already been pushed out on a forced unmount. Since the silly
+ * is going to go away anyway, this is fine.
+ */
+
+ if (sp->s_dvp->v_type == VBAD)
+ return (0);
+ return (nfs_removerpc(sp->s_dvp, sp->s_name, sp->s_namlen, sp->s_cred, NULL));
+}
+
+/* Nfs remove rpc, called from nfs_remove() and nfs_removeit(). */
+
+int
+nfs_removerpc(struct vnode *dvp, char *name, int namelen, struct ucred *cred,
+ struct proc *proc)
+{
+ struct nfsm_info info;
+ u_int32_t *tl;
+ int32_t t1;
+ caddr_t cp2;
+ int error = 0, wccflag = NFSV3_WCCRATTR;
+
+ info.nmi_v3 = NFS_ISV3(dvp);
+
+ nfsstats.rpccnt[NFSPROC_REMOVE]++;
+ info.nmi_mb = info.nmi_mreq = nfsm_reqhead(NFSX_FH(info.nmi_v3) +
+ NFSX_UNSIGNED +
+ nfsm_rndup(namelen));
+ nfsm_fhtom(&info, dvp, info.nmi_v3);
+ nfsm_strtom(name, namelen, NFS_MAXNAMLEN);
+
+ info.nmi_procp = proc;
+ info.nmi_cred = cred;
+ error = nfs_request(dvp, NFSPROC_REMOVE, &info);
+ if (info.nmi_v3)
+ nfsm_wcc_data(dvp, wccflag);
+ m_freem(info.nmi_mrep);
+
+nfsmout:
+ VTONFS(dvp)->n_flag |= NMODIFIED;
+ if (!wccflag)
+ NFS_INVALIDATE_ATTRCACHE(VTONFS(dvp));
+ return (error);
+}
+
+/* nfs file rename call */
+
+int nfs_rename(void *v)
+{
+ struct vop_rename_args *ap = v;
+ struct vnode *fvp = ap->a_fvp;
+ struct vnode *tvp = ap->a_tvp;
+ struct vnode *fdvp = ap->a_fdvp;
+ struct vnode *tdvp = ap->a_tdvp;
+ struct componentname *tcnp = ap->a_tcnp;
+ struct componentname *fcnp = ap->a_fcnp;
+ int error;
+
+#ifdef DIAGNOSTIC
+ if ((tcnp->cn_flags & HASBUF) == 0 || (fcnp->cn_flags & HASBUF) == 0)
+ panic("nfs_rename: no name");
+#endif
+
+ /* Check for cross-device rename */
+
+ if ((fvp->v_mount != tdvp->v_mount) ||
+ (tvp && (fvp->v_mount != tvp->v_mount)))
+ {
+ error = EXDEV;
+ goto out;
+ }
+
+ /* If the tvp exists and is in use, sillyrename it before doing the
+ * rename of the new file over it.
+ */
+
+ if (tvp && tvp->v_usecount > 1 && !VTONFS(tvp)->n_sillyrename &&
+ tvp->v_type != VDIR && !nfs_sillyrename(tdvp, tvp, tcnp))
+ {
+ VN_KNOTE(tvp, NOTE_DELETE);
+ vrele(tvp);
+ tvp = NULL;
+ }
+
+ error = nfs_renamerpc(fdvp, fcnp->cn_nameptr, fcnp->cn_namelen,
+ tdvp, tcnp->cn_nameptr, tcnp->cn_namelen, tcnp->cn_cred,
+ tcnp->cn_proc);
+
+ VN_KNOTE(fdvp, NOTE_WRITE);
+ VN_KNOTE(tdvp, NOTE_WRITE);
+
+ if (fvp->v_type == VDIR)
+ {
+ if (tvp != NULL && tvp->v_type == VDIR)
+ cache_purge(tdvp);
+ cache_purge(fdvp);
+ }
+out:
+ if (tdvp == tvp)
+ vrele(tdvp);
+ else
+ vput(tdvp);
+ if (tvp)
+ vput(tvp);
+ vrele(fdvp);
+ vrele(fvp);
+
+ /* Kludge: Map ENOENT => 0 assuming that it is a reply to a retry. */
+
+ if (error == ENOENT)
+ error = 0;
+ return (error);
+}
+
+/* nfs file rename rpc called from nfs_remove() above */
+
+int
+nfs_renameit(struct vnode *sdvp, struct componentname *scnp,
+ struct sillyrename *sp)
+{
+ return (nfs_renamerpc(sdvp, scnp->cn_nameptr, scnp->cn_namelen,
+ sdvp, sp->s_name, sp->s_namlen, scnp->cn_cred,
+ curproc));
+}
+
+/* Do an nfs rename rpc. Called from nfs_rename() and nfs_renameit(). */
+
+int
+nfs_renamerpc(struct vnode *fdvp, char *fnameptr, int fnamelen,
+ struct vnode *tdvp, char *tnameptr, int tnamelen,
+ struct ucred *cred, struct proc *proc)
+{
+ struct nfsm_info info;
+ u_int32_t *tl;
+ int32_t t1;
+ caddr_t cp2;
+ int error = 0, fwccflag = NFSV3_WCCRATTR, twccflag = NFSV3_WCCRATTR;
+
+ info.nmi_v3 = NFS_ISV3(fdvp);
+
+ nfsstats.rpccnt[NFSPROC_RENAME]++;
+ info.nmi_mb = info.nmi_mreq = nfsm_reqhead((NFSX_FH(info.nmi_v3) +
+ NFSX_UNSIGNED) * 2 +
+ nfsm_rndup(fnamelen) +
+ nfsm_rndup(tnamelen));
+ nfsm_fhtom(&info, fdvp, info.nmi_v3);
+ nfsm_strtom(fnameptr, fnamelen, NFS_MAXNAMLEN);
+ nfsm_fhtom(&info, tdvp, info.nmi_v3);
+ nfsm_strtom(tnameptr, tnamelen, NFS_MAXNAMLEN);
+
+ info.nmi_procp = proc;
+ info.nmi_cred = cred;
+ error = nfs_request(fdvp, NFSPROC_RENAME, &info);
+ if (info.nmi_v3)
+ {
+ nfsm_wcc_data(fdvp, fwccflag);
+ nfsm_wcc_data(tdvp, twccflag);
+ }
+ m_freem(info.nmi_mrep);
+
+nfsmout:
+ VTONFS(fdvp)->n_flag |= NMODIFIED;
+ VTONFS(tdvp)->n_flag |= NMODIFIED;
+ if (!fwccflag)
+ NFS_INVALIDATE_ATTRCACHE(VTONFS(fdvp));
+ if (!twccflag)
+ NFS_INVALIDATE_ATTRCACHE(VTONFS(tdvp));
+ return (error);
+}
+
+/* nfs hard link create call */
+
+int nfs_link(void *v)
+{
+ struct vop_link_args *ap = v;
+ struct vnode *vp = ap->a_vp;
+ struct vnode *dvp = ap->a_dvp;
+ struct componentname *cnp = ap->a_cnp;
+ struct nfsm_info info;
+ u_int32_t *tl;
+ int32_t t1;
+ caddr_t cp2;
+ int error = 0, wccflag = NFSV3_WCCRATTR, attrflag = 0;
+
+ info.nmi_v3 = NFS_ISV3(vp);
+
+ if (dvp->v_mount != vp->v_mount)
+ {
+ pool_put(&namei_pool, cnp->cn_pnbuf);
+ if (vp == dvp)
+ vrele(dvp);
+ else
+ vput(dvp);
+ return (EXDEV);
+ }
+
+ /* Push all writes to the server, so that the attribute cache
+ * doesn't get "out of sync" with the server.
+ * XXX There should be a better way!
+ */
+
+ VOP_FSYNC(vp, cnp->cn_cred, MNT_WAIT, cnp->cn_proc);
+
+ nfsstats.rpccnt[NFSPROC_LINK]++;
+ info.nmi_mb = info.nmi_mreq = nfsm_reqhead(2 * NFSX_FH(info.nmi_v3) +
+ NFSX_UNSIGNED +
+ nfsm_rndup(cnp->cn_namelen));
+ nfsm_fhtom(&info, vp, info.nmi_v3);
+ nfsm_fhtom(&info, dvp, info.nmi_v3);
+ nfsm_strtom(cnp->cn_nameptr, cnp->cn_namelen, NFS_MAXNAMLEN);
+
+ info.nmi_procp = cnp->cn_proc;
+ info.nmi_cred = cnp->cn_cred;
+ error = nfs_request(vp, NFSPROC_LINK, &info);
+ if (info.nmi_v3)
+ {
+ nfsm_postop_attr(vp, attrflag);
+ nfsm_wcc_data(dvp, wccflag);
+ }
+ m_freem(info.nmi_mrep);
+nfsmout:
+ pool_put(&namei_pool, cnp->cn_pnbuf);
+ VTONFS(dvp)->n_flag |= NMODIFIED;
+ if (!attrflag)
+ NFS_INVALIDATE_ATTRCACHE(VTONFS(vp));
+ if (!wccflag)
+ NFS_INVALIDATE_ATTRCACHE(VTONFS(dvp));
+
+ VN_KNOTE(vp, NOTE_LINK);
+ VN_KNOTE(dvp, NOTE_WRITE);
+ vput(dvp);
+ return (error);
+}
+
+/* nfs symbolic link create call */
+
+int nfs_symlink(void *v)
+{
+ struct vop_symlink_args *ap = v;
+ struct vnode *dvp = ap->a_dvp;
+ struct vattr *vap = ap->a_vap;
+ struct componentname *cnp = ap->a_cnp;
+ struct nfsv2_sattr *sp;
+ struct nfsm_info info;
+ u_int32_t *tl;
+ int32_t t1;
+ caddr_t cp2;
+ int slen, error = 0, wccflag = NFSV3_WCCRATTR, gotvp;
+ struct vnode *newvp = NULL;
+
+ info.nmi_v3 = NFS_ISV3(dvp);
+
+ nfsstats.rpccnt[NFSPROC_SYMLINK]++;
+ slen = strlen(ap->a_target);
+ info.nmi_mb = info.nmi_mreq = nfsm_reqhead(NFSX_FH(info.nmi_v3) +
+ 2 * NFSX_UNSIGNED +
+ nfsm_rndup(cnp->cn_namelen) +
+ nfsm_rndup(slen) +
+ NFSX_SATTR(info.nmi_v3));
+ nfsm_fhtom(&info, dvp, info.nmi_v3);
+ nfsm_strtom(cnp->cn_nameptr, cnp->cn_namelen, NFS_MAXNAMLEN);
+ if (info.nmi_v3)
+ nfsm_v3attrbuild(&info.nmi_mb, vap, 0);
+ nfsm_strtom(ap->a_target, slen, NFS_MAXPATHLEN);
+ if (!info.nmi_v3)
+ {
+ sp = nfsm_build(&info.nmi_mb, NFSX_V2SATTR);
+ sp->sa_mode = vtonfsv2_mode(VLNK, vap->va_mode);
+ sp->sa_uid = nfs_xdrneg1;
+ sp->sa_gid = nfs_xdrneg1;
+ sp->sa_size = nfs_xdrneg1;
+ txdr_nfsv2time(&vap->va_atime, &sp->sa_atime);
+ txdr_nfsv2time(&vap->va_mtime, &sp->sa_mtime);
+ }
+
+ info.nmi_procp = cnp->cn_proc;
+ info.nmi_cred = cnp->cn_cred;
+ error = nfs_request(dvp, NFSPROC_SYMLINK, &info);
+ if (info.nmi_v3)
+ {
+ if (!error)
+ nfsm_mtofh(dvp, newvp, info.nmi_v3, gotvp);
+ nfsm_wcc_data(dvp, wccflag);
+ }
+ m_freem(info.nmi_mrep);
+
+nfsmout:
+ if (newvp)
+ vrele(newvp);
+ pool_put(&namei_pool, cnp->cn_pnbuf);
+ VTONFS(dvp)->n_flag |= NMODIFIED;
+ if (!wccflag)
+ NFS_INVALIDATE_ATTRCACHE(VTONFS(dvp));
+ VN_KNOTE(dvp, NOTE_WRITE);
+ vrele(dvp);
+ return (error);
+}
+
+/* nfs make dir call */
+
+int nfs_mkdir(void *v)
+{
+ struct vop_mkdir_args *ap = v;
+ struct vnode *dvp = ap->a_dvp;
+ struct vattr *vap = ap->a_vap;
+ struct componentname *cnp = ap->a_cnp;
+ struct nfsv2_sattr *sp;
+ struct nfsm_info info;
+ u_int32_t *tl;
+ int32_t t1;
+ int len;
+ struct nfsnode *np = NULL;
+ struct vnode *newvp = NULL;
+ caddr_t cp2;
+ int error = 0, wccflag = NFSV3_WCCRATTR;
+ int gotvp = 0;
+
+ info.nmi_v3 = NFS_ISV3(dvp);
+
+ len = cnp->cn_namelen;
+ nfsstats.rpccnt[NFSPROC_MKDIR]++;
+ info.nmi_mb = info.nmi_mreq = nfsm_reqhead(NFSX_FH(info.nmi_v3) +
+ NFSX_UNSIGNED + nfsm_rndup(len) +
+ NFSX_SATTR(info.nmi_v3));
+ nfsm_fhtom(&info, dvp, info.nmi_v3);
+ nfsm_strtom(cnp->cn_nameptr, len, NFS_MAXNAMLEN);
+
+ if (info.nmi_v3)
+ {
+ nfsm_v3attrbuild(&info.nmi_mb, vap, 0);
+ }
+ else
+ {
+ sp = nfsm_build(&info.nmi_mb, NFSX_V2SATTR);
+ sp->sa_mode = vtonfsv2_mode(VDIR, vap->va_mode);
+ sp->sa_uid = nfs_xdrneg1;
+ sp->sa_gid = nfs_xdrneg1;
+ sp->sa_size = nfs_xdrneg1;
+ txdr_nfsv2time(&vap->va_atime, &sp->sa_atime);
+ txdr_nfsv2time(&vap->va_mtime, &sp->sa_mtime);
+ }
+
+ info.nmi_procp = cnp->cn_proc;
+ info.nmi_cred = cnp->cn_cred;
+ error = nfs_request(dvp, NFSPROC_MKDIR, &info);
+ if (!error)
+ nfsm_mtofh(dvp, newvp, info.nmi_v3, gotvp);
+ if (info.nmi_v3)
+ nfsm_wcc_data(dvp, wccflag);
+ m_freem(info.nmi_mrep);
+
+nfsmout:
+ VTONFS(dvp)->n_flag |= NMODIFIED;
+ if (!wccflag)
+ NFS_INVALIDATE_ATTRCACHE(VTONFS(dvp));
+
+ if (error == 0 && newvp == NULL)
+ {
+ error = nfs_lookitup(dvp, cnp->cn_nameptr, len, cnp->cn_cred,
+ cnp->cn_proc, &np);
+ if (!error)
+ {
+ newvp = NFSTOV(np);
+ if (newvp->v_type != VDIR)
+ error = EEXIST;
+ }
+ }
+ if (error)
+ {
+ if (newvp)
+ vrele(newvp);
+ }
+ else
+ {
+ VN_KNOTE(dvp, NOTE_WRITE | NOTE_LINK);
+ if (cnp->cn_flags & MAKEENTRY)
+ nfs_cache_enter(dvp, newvp, cnp);
+ *ap->a_vpp = newvp;
+ }
+ pool_put(&namei_pool, cnp->cn_pnbuf);
+ vrele(dvp);
+ return (error);
+}
+
+/* nfs remove directory call */
+
+int nfs_rmdir(void *v)
+{
+ struct vop_rmdir_args *ap = v;
+ struct vnode *vp = ap->a_vp;
+ struct vnode *dvp = ap->a_dvp;
+ struct componentname *cnp = ap->a_cnp;
+ struct nfsm_info info;
+ u_int32_t *tl;
+ int32_t t1;
+ caddr_t cp2;
+ int error = 0, wccflag = NFSV3_WCCRATTR;
+
+ info.nmi_v3 = NFS_ISV3(dvp);
+
+ if (dvp == vp)
+ {
+ vrele(dvp);
+ vrele(dvp);
+ pool_put(&namei_pool, cnp->cn_pnbuf);
+ return (EINVAL);
+ }
+
+ nfsstats.rpccnt[NFSPROC_RMDIR]++;
+ info.nmi_mb = info.nmi_mreq = nfsm_reqhead(NFSX_FH(info.nmi_v3) +
+ NFSX_UNSIGNED +
+ nfsm_rndup(cnp->cn_namelen));
+ nfsm_fhtom(&info, dvp, info.nmi_v3);
+ nfsm_strtom(cnp->cn_nameptr, cnp->cn_namelen, NFS_MAXNAMLEN);
+
+ info.nmi_procp = cnp->cn_proc;
+ info.nmi_cred = cnp->cn_cred;
+ error = nfs_request(dvp, NFSPROC_RMDIR, &info);
+ if (info.nmi_v3)
+ nfsm_wcc_data(dvp, wccflag);
+ m_freem(info.nmi_mrep);
+
+nfsmout:
+ pool_put(&namei_pool, cnp->cn_pnbuf);
+ VTONFS(dvp)->n_flag |= NMODIFIED;
+ if (!wccflag)
+ NFS_INVALIDATE_ATTRCACHE(VTONFS(dvp));
+
+ VN_KNOTE(dvp, NOTE_WRITE | NOTE_LINK);
+ VN_KNOTE(vp, NOTE_DELETE);
+
+ cache_purge(vp);
+ vrele(vp);
+ vrele(dvp);
+
+ /* Kludge: Map ENOENT => 0 assuming that you have a reply to a retry. */
+
+ if (error == ENOENT)
+ error = 0;
+ return (error);
+}
+
+/* The readdir logic below has a big design bug. It stores the NFS cookie in
+ * the returned uio->uio_offset but does not store the verifier (it cannot).
+ * Instead, the code stores the verifier in the nfsnode and applies that
+ * verifies to all cookies, no matter what verifier was originally with
+ * the cookie.
+ *
+ * From a practical standpoint, this is not a problem since almost all
+ * NFS servers do not change the validity of cookies across deletes
+ * and inserts.
+ */
+
+struct nfs_dirent
+ {
+ u_int32_t cookie[2];
+ struct dirent dirent;
+ };
+
+#define NFS_DIRHDSIZ (sizeof (struct nfs_dirent) - (MAXNAMLEN + 1))
+#define NFS_DIRENT_OVERHEAD offsetof(struct nfs_dirent, dirent)
+
+/* nfs readdir call */
+
+int nfs_readdir(void *v)
+{
+ struct vop_readdir_args *ap = v;
+ struct vnode *vp = ap->a_vp;
+ struct nfsnode *np = VTONFS(vp);
+ struct uio *uio = ap->a_uio;
+ int tresid, error = 0;
+ struct vattr vattr;
+ u_long *cookies = NULL;
+ int ncookies = 0, cnt;
+ u_int64_t newoff = uio->uio_offset;
+ struct nfsmount *nmp = VFSTONFS(vp->v_mount);
+ struct uio readdir_uio;
+ struct iovec readdir_iovec;
+ struct proc *p = uio->uio_procp;
+ int done = 0, eof = 0;
+ struct ucred *cred = ap->a_cred;
+ void *data;
+
+ if (vp->v_type != VDIR)
+ return (EPERM);
+
+ /* First, check for hit on the EOF offset cache */
+
+ if (np->n_direofoffset != 0 && uio->uio_offset == np->n_direofoffset)
+ {
+ if (VOP_GETATTR(vp, &vattr, ap->a_cred, uio->uio_procp) == 0 &&
+ timespeccmp(&np->n_mtime, &vattr.va_mtime, ==))
+ {
+ nfsstats.direofcache_hits++;
+ *ap->a_eofflag = 1;
+ return (0);
+ }
+ }
+
+ if (uio->uio_resid < NFS_FABLKSIZE)
+ return (EINVAL);
+
+ tresid = uio->uio_resid;
+
+ if (uio->uio_rw != UIO_READ)
+ return (EINVAL);
+
+ if (ap->a_cookies)
+ {
+ ncookies = uio->uio_resid / 20;
+
+ cookies = malloc(sizeof(*cookies) * ncookies, M_TEMP, M_WAITOK);
+ *ap->a_ncookies = ncookies;
+ *ap->a_cookies = cookies;
+ }
+
+ if ((nmp->nm_flag & (NFSMNT_NFSV3 | NFSMNT_GOTFSINFO)) == NFSMNT_NFSV3)
+ (void)nfs_fsinfo(nmp, vp, cred, p);
+
+ cnt = 5;
+
+ data = malloc(NFS_DIRBLKSIZ, M_TEMP, M_WAITOK);
+ do
+ {
+ struct nfs_dirent *ndp = data;
+
+ readdir_iovec.iov_len = NFS_DIRBLKSIZ;
+ readdir_iovec.iov_base = data;
+ readdir_uio.uio_offset = newoff;
+ readdir_uio.uio_iov = &readdir_iovec;
+ readdir_uio.uio_iovcnt = 1;
+ readdir_uio.uio_segflg = UIO_SYSSPACE;
+ readdir_uio.uio_rw = UIO_READ;
+ readdir_uio.uio_resid = NFS_DIRBLKSIZ;
+ readdir_uio.uio_procp = curproc;
+
+ if (nmp->nm_flag & NFSMNT_RDIRPLUS)
+ {
+ error = nfs_readdirplusrpc(vp, &readdir_uio, cred, &eof);
+ if (error == NFSERR_NOTSUPP)
+ nmp->nm_flag &= ~NFSMNT_RDIRPLUS;
+ }
+ if ((nmp->nm_flag & NFSMNT_RDIRPLUS) == 0)
+ error = nfs_readdirrpc(vp, &readdir_uio, cred, &eof);
+
+ if (error == NFSERR_BAD_COOKIE)
+ error = EINVAL;
+
+ while (error == 0 &&
+ (ap->a_cookies == NULL || ncookies != 0) &&
+ ndp < (struct nfs_dirent *)readdir_iovec.iov_base)
+ {
+ struct dirent *dp = &ndp->dirent;
+ int reclen = dp->d_reclen;
+
+ dp->d_reclen -= NFS_DIRENT_OVERHEAD;
+
+ if (uio->uio_resid < dp->d_reclen)
+ {
+ eof = 0;
+ done = 1;
+ break;
+ }
+
+ error = uiomove((caddr_t) dp, dp->d_reclen, uio);
+ if (error)
+ break;
+
+ newoff = fxdr_hyper(&ndp->cookie[0]);
+
+ if (ap->a_cookies != NULL)
+ {
+ *cookies = newoff;
+ cookies++;
+ ncookies--;
+ }
+
+ ndp = (struct nfs_dirent *)((u_int8_t *) ndp + reclen);
+ }
+ }
+ while (!error && !done && !eof && cnt--);
+
+ free(data, M_TEMP);
+ data = NULL;
+
+ if (ap->a_cookies)
+ {
+ if (error)
+ {
+ free(*ap->a_cookies, M_TEMP);
+ *ap->a_cookies = NULL;
+ *ap->a_ncookies = 0;
+ }
+ else
+ {
+ *ap->a_ncookies -= ncookies;
+ }
+ }
+
+ if (!error)
+ uio->uio_offset = newoff;
+
+ if (!error && (eof || uio->uio_resid == tresid))
+ {
+ nfsstats.direofcache_misses++;
+ *ap->a_eofflag = 1;
+ return (0);
+ }
+
+ *ap->a_eofflag = 0;
+ return (error);
+}
+
+/* Readdir rpc call. */
+
+int
+nfs_readdirrpc(struct vnode *vp, struct uio *uiop, struct ucred *cred,
+ int *end_of_directory)
+{
+ int len, left;
+ struct nfs_dirent *ndp = NULL;
+ struct dirent *dp = NULL;
+ struct nfsm_info info;
+ u_int32_t *tl;
+ caddr_t cp;
+ int32_t t1;
+ caddr_t cp2;
+ nfsuint64 cookie;
+ struct nfsmount *nmp = VFSTONFS(vp->v_mount);
+ struct nfsnode *dnp = VTONFS(vp);
+ u_quad_t fileno;
+ int error = 0, tlen, more_dirs = 1, blksiz = 0, bigenough = 1;
+ int attrflag;
+
+ info.nmi_v3 = NFS_ISV3(vp);
+
+#ifdef DIAGNOSTIC
+ if (uiop->uio_iovcnt != 1 || (uiop->uio_resid & (NFS_DIRBLKSIZ - 1)))
+ panic("nfs readdirrpc bad uio");
+#endif
+
+ txdr_hyper(uiop->uio_offset, &cookie.nfsuquad[0]);
+
+ /* Loop around doing readdir rpc's of size nm_readdirsize
+ * truncated to a multiple of NFS_READDIRBLKSIZ.
+ * The stopping criteria is EOF or buffer full.
+ */
+
+ while (more_dirs && bigenough)
+ {
+ nfsstats.rpccnt[NFSPROC_READDIR]++;
+ info.nmi_mb = info.nmi_mreq = nfsm_reqhead(NFSX_FH(info.nmi_v3)
+ + NFSX_READDIR(info.nmi_v3));
+ nfsm_fhtom(&info, vp, info.nmi_v3);
+ if (info.nmi_v3)
+ {
+ tl = nfsm_build(&info.nmi_mb, 5 * NFSX_UNSIGNED);
+ *tl++ = cookie.nfsuquad[0];
+ *tl++ = cookie.nfsuquad[1];
+ if (cookie.nfsuquad[0] == 0 && cookie.nfsuquad[1] == 0)
+ {
+ *tl++ = 0;
+ *tl++ = 0;
+ }
+ else
+ {
+ *tl++ = dnp->n_cookieverf.nfsuquad[0];
+ *tl++ = dnp->n_cookieverf.nfsuquad[1];
+ }
+ }
+ else
+ {
+ tl = nfsm_build(&info.nmi_mb, 2 * NFSX_UNSIGNED);
+ *tl++ = cookie.nfsuquad[1];
+ }
+ *tl = txdr_unsigned(nmp->nm_readdirsize);
+
+ info.nmi_procp = uiop->uio_procp;
+ info.nmi_cred = cred;
+ error = nfs_request(vp, NFSPROC_READDIR, &info);
+ if (info.nmi_v3)
+ nfsm_postop_attr(vp, attrflag);
+
+ if (error)
+ {
+ m_freem(info.nmi_mrep);
+ goto nfsmout;
+ }
+
+ if (info.nmi_v3)
+ {
+ nfsm_dissect(tl, u_int32_t *, 2 * NFSX_UNSIGNED);
+ dnp->n_cookieverf.nfsuquad[0] = *tl++;
+ dnp->n_cookieverf.nfsuquad[1] = *tl;
+ }
+
+ nfsm_dissect(tl, u_int32_t *, NFSX_UNSIGNED);
+ more_dirs = fxdr_unsigned(int, *tl);
+
+ /* loop thru the dir entries, doctoring them to 4bsd form */
+
+ while (more_dirs && bigenough)
+ {
+ if (info.nmi_v3)
+ {
+ nfsm_dissect(tl, u_int32_t *, 3 * NFSX_UNSIGNED);
+ fileno = fxdr_hyper(tl);
+ len = fxdr_unsigned(int, *(tl + 2));
+ }
+ else
+ {
+ nfsm_dissect(tl, u_int32_t *, 2 * NFSX_UNSIGNED);
+ fileno = fxdr_unsigned(u_quad_t, *tl++);
+ len = fxdr_unsigned(int, *tl);
+ }
+ if (len <= 0 || len > NFS_MAXNAMLEN)
+ {
+ error = EBADRPC;
+ m_freem(info.nmi_mrep);
+ goto nfsmout;
+ }
+ tlen = nfsm_rndup(len + 1);
+ left = NFS_READDIRBLKSIZ - blksiz;
+ if ((tlen + NFS_DIRHDSIZ) > left)
+ {
+ dp->d_reclen += left;
+ uiop->uio_iov->iov_base += left;
+ uiop->uio_iov->iov_len -= left;
+ uiop->uio_resid -= left;
+ blksiz = 0;
+ }
+ if ((tlen + NFS_DIRHDSIZ) > uiop->uio_resid)
+ bigenough = 0;
+ if (bigenough)
+ {
+ ndp = (struct nfs_dirent *)uiop->uio_iov->iov_base;
+ dp = &ndp->dirent;
+ dp->d_fileno = (int)fileno;
+ dp->d_namlen = len;
+ dp->d_reclen = tlen + NFS_DIRHDSIZ;
+ dp->d_type = DT_UNKNOWN;
+ blksiz += dp->d_reclen;
+ if (blksiz == NFS_READDIRBLKSIZ)
+ blksiz = 0;
+ uiop->uio_resid -= NFS_DIRHDSIZ;
+ uiop->uio_iov->iov_base =
+ (char *)uiop->uio_iov->iov_base + NFS_DIRHDSIZ;
+ uiop->uio_iov->iov_len -= NFS_DIRHDSIZ;
+ nfsm_mtouio(uiop, len);
+ cp = uiop->uio_iov->iov_base;
+ tlen -= len;
+ *cp = '\0'; /* null terminate */
+ uiop->uio_iov->iov_base += tlen;
+ uiop->uio_iov->iov_len -= tlen;
+ uiop->uio_resid -= tlen;
+ }
+ else
+ nfsm_adv(nfsm_rndup(len));
+ if (info.nmi_v3)
+ {
+ nfsm_dissect(tl, u_int32_t *, 3 * NFSX_UNSIGNED);
+ }
+ else
+ {
+ nfsm_dissect(tl, u_int32_t *, 2 * NFSX_UNSIGNED);
+ }
+ if (bigenough)
+ {
+ if (info.nmi_v3)
+ {
+ ndp->cookie[0] = cookie.nfsuquad[0] = *tl++;
+ }
+ else
+ ndp->cookie[0] = 0;
+
+ ndp->cookie[1] = cookie.nfsuquad[1] = *tl++;
+ }
+ else if (info.nmi_v3)
+ tl += 2;
+ else
+ tl++;
+ more_dirs = fxdr_unsigned(int, *tl);
+ }
+
+ /* If at end of rpc data, get the eof boolean */
+
+ if (!more_dirs)
+ {
+ nfsm_dissect(tl, u_int32_t *, NFSX_UNSIGNED);
+ more_dirs = (fxdr_unsigned(int, *tl) == 0);
+ }
+ m_freem(info.nmi_mrep);
+ }
+
+ /* Fill last record, iff any, out to a multiple of NFS_READDIRBLKSIZ
+ * by increasing d_reclen for the last record.
+ */
+
+ if (blksiz > 0)
+ {
+ left = NFS_READDIRBLKSIZ - blksiz;
+ dp->d_reclen += left;
+ uiop->uio_iov->iov_base = (char *)uiop->uio_iov->iov_base + left;
+ uiop->uio_iov->iov_len -= left;
+ uiop->uio_resid -= left;
+ }
+
+ /* We are now either at the end of the directory or have filled the
+ * block.
+ */
+
+ if (bigenough)
+ {
+ dnp->n_direofoffset = fxdr_hyper(&cookie.nfsuquad[0]);
+ if (end_of_directory)
+ *end_of_directory = 1;
+ }
+ else
+ {
+ if (uiop->uio_resid > 0)
+ printf("EEK! readdirrpc resid > 0\n");
+ }
+
+nfsmout:
+ return (error);
+}
+
+/* NFS V3 readdir plus RPC. Used in place of nfs_readdirrpc(). */
+
+int
+nfs_readdirplusrpc(struct vnode *vp, struct uio *uiop, struct ucred *cred,
+ int *end_of_directory)
+{
+ int len, left;
+ struct nfs_dirent *ndirp = NULL;
+ struct dirent *dp = NULL;
+ struct nfsm_info info;
+ u_int32_t *tl;
+ caddr_t cp;
+ int32_t t1;
+ struct vnode *newvp;
+ caddr_t cp2, dpossav1, dpossav2;
+ struct mbuf *mdsav1, *mdsav2;
+ struct nameidata nami, *ndp = &nami;
+ struct componentname *cnp = &ndp->ni_cnd;
+ nfsuint64 cookie;
+ struct nfsmount *nmp = VFSTONFS(vp->v_mount);
+ struct nfsnode *dnp = VTONFS(vp), *np;
+ nfsfh_t *fhp;
+ u_quad_t fileno;
+ int error = 0, tlen, more_dirs = 1, blksiz = 0, doit, bigenough = 1, i;
+ int attrflag, fhsize;
+
+#ifdef DIAGNOSTIC
+ if (uiop->uio_iovcnt != 1 || (uiop->uio_resid & (NFS_DIRBLKSIZ - 1)))
+ panic("nfs readdirplusrpc bad uio");
+#endif
+ ndp->ni_dvp = vp;
+ newvp = NULLVP;
+
+ txdr_hyper(uiop->uio_offset, &cookie.nfsuquad[0]);
+
+ /* Loop around doing readdir rpc's of size nm_readdirsize
+ * truncated to a multiple of NFS_READDIRBLKSIZ.
+ * The stopping criteria is EOF or buffer full.
+ */
+
+ while (more_dirs && bigenough)
+ {
+ nfsstats.rpccnt[NFSPROC_READDIRPLUS]++;
+ info.nmi_mb = info.nmi_mreq =
+ nfsm_reqhead(NFSX_FH(1) + 6 * NFSX_UNSIGNED);
+ nfsm_fhtom(&info, vp, 1);
+ tl = nfsm_build(&info.nmi_mb, 6 * NFSX_UNSIGNED);
+ *tl++ = cookie.nfsuquad[0];
+ *tl++ = cookie.nfsuquad[1];
+ if (cookie.nfsuquad[0] == 0 && cookie.nfsuquad[1] == 0)
+ {
+ *tl++ = 0;
+ *tl++ = 0;
+ }
+ else
+ {
+ *tl++ = dnp->n_cookieverf.nfsuquad[0];
+ *tl++ = dnp->n_cookieverf.nfsuquad[1];
+ }
+ *tl++ = txdr_unsigned(nmp->nm_readdirsize);
+ *tl = txdr_unsigned(nmp->nm_rsize);
+
+ info.nmi_procp = uiop->uio_procp;
+ info.nmi_cred = cred;
+ error = nfs_request(vp, NFSPROC_READDIRPLUS, &info);
+ nfsm_postop_attr(vp, attrflag);
+ if (error)
+ {
+ m_freem(info.nmi_mrep);
+ goto nfsmout;
+ }
+
+ nfsm_dissect(tl, u_int32_t *, 3 * NFSX_UNSIGNED);
+ dnp->n_cookieverf.nfsuquad[0] = *tl++;
+ dnp->n_cookieverf.nfsuquad[1] = *tl++;
+ more_dirs = fxdr_unsigned(int, *tl);
+
+ /* loop thru the dir entries, doctoring them to 4bsd form */
+
+ while (more_dirs && bigenough)
+ {
+ nfsm_dissect(tl, u_int32_t *, 3 * NFSX_UNSIGNED);
+ fileno = fxdr_hyper(tl);
+ len = fxdr_unsigned(int, *(tl + 2));
+ if (len <= 0 || len > NFS_MAXNAMLEN)
+ {
+ error = EBADRPC;
+ m_freem(info.nmi_mrep);
+ goto nfsmout;
+ }
+ tlen = nfsm_rndup(len + 1);
+ left = NFS_READDIRBLKSIZ - blksiz;
+ if ((tlen + NFS_DIRHDSIZ) > left)
+ {
+ dp->d_reclen += left;
+ uiop->uio_iov->iov_base = (char *)uiop->uio_iov->iov_base + left;
+ uiop->uio_iov->iov_len -= left;
+ uiop->uio_resid -= left;
+ blksiz = 0;
+ }
+ if ((tlen + NFS_DIRHDSIZ) > uiop->uio_resid)
+ bigenough = 0;
+ if (bigenough)
+ {
+ ndirp = (struct nfs_dirent *)uiop->uio_iov->iov_base;
+ dp = &ndirp->dirent;
+ dp->d_fileno = (int)fileno;
+ dp->d_namlen = len;
+ dp->d_reclen = tlen + NFS_DIRHDSIZ;
+ dp->d_type = DT_UNKNOWN;
+ blksiz += dp->d_reclen;
+ if (blksiz == NFS_READDIRBLKSIZ)
+ blksiz = 0;
+ uiop->uio_resid -= NFS_DIRHDSIZ;
+ uiop->uio_iov->iov_base =
+ (char *)uiop->uio_iov->iov_base + NFS_DIRHDSIZ;
+ uiop->uio_iov->iov_len -= NFS_DIRHDSIZ;
+ cnp->cn_nameptr = uiop->uio_iov->iov_base;
+ cnp->cn_namelen = len;
+ nfsm_mtouio(uiop, len);
+ cp = uiop->uio_iov->iov_base;
+ tlen -= len;
+ *cp = '\0';
+ uiop->uio_iov->iov_base += tlen;
+ uiop->uio_iov->iov_len -= tlen;
+ uiop->uio_resid -= tlen;
+ }
+ else
+ nfsm_adv(nfsm_rndup(len));
+ nfsm_dissect(tl, u_int32_t *, 3 * NFSX_UNSIGNED);
+ if (bigenough)
+ {
+ ndirp->cookie[0] = cookie.nfsuquad[0] = *tl++;
+ ndirp->cookie[1] = cookie.nfsuquad[1] = *tl++;
+ }
+ else
+ tl += 2;
+
+ /* Since the attributes are before the file handle
+ * (sigh), we must skip over the attributes and then
+ * come back and get them.
+ */
+
+ attrflag = fxdr_unsigned(int, *tl);
+ if (attrflag)
+ {
+ dpossav1 = info.nmi_dpos;
+ mdsav1 = info.nmi_md;
+ nfsm_adv(NFSX_V3FATTR);
+ nfsm_dissect(tl, u_int32_t *, NFSX_UNSIGNED);
+ doit = fxdr_unsigned(int, *tl);
+ if (doit)
+ {
+ nfsm_getfh(fhp, fhsize, 1);
+ if (NFS_CMPFH(dnp, fhp, fhsize))
+ {
+ vref(vp);
+ newvp = vp;
+ np = dnp;
+ }
+ else
+ {
+ error = nfs_nget(vp->v_mount, fhp, fhsize, &np);
+ if (error)
+ doit = 0;
+ else
+ newvp = NFSTOV(np);
+ }
+ }
+ if (doit && bigenough)
+ {
+ dpossav2 = info.nmi_dpos;
+ info.nmi_dpos = dpossav1;
+ mdsav2 = info.nmi_md;
+ info.nmi_md = mdsav1;
+ nfsm_loadattr(newvp, NULL);
+ info.nmi_dpos = dpossav2;
+ info.nmi_md = mdsav2;
+ dp->d_type = IFTODT(VTTOIF(np->n_vattr.va_type));
+ if (cnp->cn_namelen <= NCHNAMLEN)
+ {
+ ndp->ni_vp = newvp;
+ cache_purge(ndp->ni_dvp);
+ nfs_cache_enter(ndp->ni_dvp, ndp->ni_vp, cnp);
+ }
+ }
+ }
+ else
+ {
+ /* Just skip over the file handle */
+
+ nfsm_dissect(tl, u_int32_t *, NFSX_UNSIGNED);
+ i = fxdr_unsigned(int, *tl);
+ nfsm_adv(nfsm_rndup(i));
+ }
+ if (newvp != NULLVP)
+ {
+ vrele(newvp);
+ newvp = NULLVP;
+ }
+ nfsm_dissect(tl, u_int32_t *, NFSX_UNSIGNED);
+ more_dirs = fxdr_unsigned(int, *tl);
+ }
+
+ /* If at end of rpc data, get the eof boolean*/
+
+ if (!more_dirs)
+ {
+ nfsm_dissect(tl, u_int32_t *, NFSX_UNSIGNED);
+ more_dirs = (fxdr_unsigned(int, *tl) == 0);
+ }
+ m_freem(info.nmi_mrep);
+ }
+
+ /* Fill last record, iff any, out to a multiple of NFS_READDIRBLKSIZ
+ * by increasing d_reclen for the last record.
+ */
+
+ if (blksiz > 0)
+ {
+ left = NFS_READDIRBLKSIZ - blksiz;
+ dp->d_reclen += left;
+ uiop->uio_iov->iov_base = (char *)uiop->uio_iov->iov_base + left;
+ uiop->uio_iov->iov_len -= left;
+ uiop->uio_resid -= left;
+ }
+
+ /* We are now either at the end of the directory or have filled the
+ * block.
+ */
+
+ if (bigenough)
+ {
+ dnp->n_direofoffset = fxdr_hyper(&cookie.nfsuquad[0]);
+ if (end_of_directory)
+ *end_of_directory = 1;
+ }
+ else
+ {
+ if (uiop->uio_resid > 0)
+ printf("EEK! readdirplusrpc resid > 0\n");
+ }
+
+nfsmout:
+ if (newvp != NULLVP)
+ vrele(newvp);
+ return (error);
+}
+
+/* Silly rename. To make the NFS filesystem that is stateless look a little
+ * more like the "ufs" a remove of an active vnode is translated to a rename
+ * to a funny looking filename that is removed by nfs_inactive on the
+ * nfsnode. There is the potential for another process on a different client
+ * to create the same funny name between the nfs_lookitup() fails and the
+ * nfs_rename() completes, but...
+ */
+
+int
+nfs_sillyrename(struct vnode *dvp, struct vnode *vp, struct componentname *cnp)
+{
+ struct sillyrename *sp;
+ struct nfsnode *np;
+ int error;
+
+ cache_purge(dvp);
+ np = VTONFS(vp);
+ sp = malloc(sizeof(struct sillyrename), M_NFSREQ, M_WAITOK);
+ sp->s_cred = crdup(cnp->cn_cred);
+ sp->s_dvp = dvp;
+ vref(dvp);
+
+ if (vp->v_type == VDIR)
+ {
+#ifdef DIAGNOSTIC
+ printf("nfs: sillyrename dir\n");
+#endif
+ error = EINVAL;
+ goto bad;
+ }
+
+ /* Try lookitups until we get one that isn't there */
+
+ while (1)
+ {
+ /* Fudge together a funny name */
+
+ sp->s_namlen = snprintf(sp->s_name, sizeof sp->s_name,
+ ".nfs%08X%08X", arc4random(), arc4random());
+ if (sp->s_namlen > sizeof sp->s_name)
+ sp->s_namlen = strlen(sp->s_name);
+
+ if (nfs_lookitup(dvp, sp->s_name, sp->s_namlen, sp->s_cred,
+ cnp->cn_proc, NULL))
+ break;
+ }
+
+ error = nfs_renameit(dvp, cnp, sp);
+ if (error)
+ goto bad;
+ error = nfs_lookitup(dvp, sp->s_name, sp->s_namlen, sp->s_cred,
+ cnp->cn_proc, &np);
+ np->n_sillyrename = sp;
+ return (0);
+bad:
+ vrele(sp->s_dvp);
+ crfree(sp->s_cred);
+ free(sp, M_NFSREQ);
+ return (error);
+}
+
+/* Look up a file name and optionally either update the file handle or
+ * allocate an nfsnode, depending on the value of npp.
+ * npp == NULL --> just do the lookup
+ * *npp == NULL --> allocate a new nfsnode and make sure attributes are
+ * handled too
+ * *npp != NULL --> update the file handle in the vnode
+ */
+
+int
+nfs_lookitup(struct vnode *dvp, char *name, int len, struct ucred *cred,
+ struct proc *procp, struct nfsnode **npp)
+{
+ struct nfsm_info info;
+ u_int32_t *tl;
+ int32_t t1;
+ struct vnode *newvp = NULL;
+ struct nfsnode *np, *dnp = VTONFS(dvp);
+ caddr_t cp2;
+ int error = 0, fhlen, attrflag;
+ nfsfh_t *nfhp;
+
+ info.nmi_v3 = NFS_ISV3(dvp);
+
+ nfsstats.rpccnt[NFSPROC_LOOKUP]++;
+ info.nmi_mb = info.nmi_mreq =
+ nfsm_reqhead(NFSX_FH(info.nmi_v3) + NFSX_UNSIGNED + nfsm_rndup(len));
+ nfsm_fhtom(&info, dvp, info.nmi_v3);
+ nfsm_strtom(name, len, NFS_MAXNAMLEN);
+
+ info.nmi_procp = procp;
+ info.nmi_cred = cred;
+ error = nfs_request(dvp, NFSPROC_LOOKUP, &info);
+ if (error && !info.nmi_v3)
+ {
+ m_freem(info.nmi_mrep);
+ goto nfsmout;
+ }
+
+ if (npp && !error)
+ {
+ nfsm_getfh(nfhp, fhlen, info.nmi_v3);
+ if (*npp)
+ {
+ np = *npp;
+ np->n_fhp = &np->n_fh;
+ bcopy((caddr_t) nfhp, (caddr_t) np->n_fhp, fhlen);
+ np->n_fhsize = fhlen;
+ newvp = NFSTOV(np);
+ }
+ else if (NFS_CMPFH(dnp, nfhp, fhlen))
+ {
+ vref(dvp);
+ newvp = dvp;
+ np = dnp;
+ }
+ else
+ {
+ error = nfs_nget(dvp->v_mount, nfhp, fhlen, &np);
+ if (error)
+ {
+ m_freem(info.nmi_mrep);
+ return (error);
+ }
+ newvp = NFSTOV(np);
+ }
+ if (info.nmi_v3)
+ {
+ nfsm_postop_attr(newvp, attrflag);
+ if (!attrflag && *npp == NULL)
+ {
+ m_freem(info.nmi_mrep);
+ vrele(newvp);
+ return (ENOENT);
+ }
+ }
+ else
+ nfsm_loadattr(newvp, NULL);
+ }
+ m_freem(info.nmi_mrep);
+nfsmout:
+ if (npp && *npp == NULL)
+ {
+ if (error)
+ {
+ if (newvp)
+ vrele(newvp);
+ }
+ else
+ *npp = np;
+ }
+ return (error);
+}
+
+/* Nfs Version 3 commit rpc */
+
+int nfs_commit(struct vnode *vp, u_quad_t offset, int cnt, struct proc *procp)
+{
+ struct nfsm_info info;
+ u_int32_t *tl;
+ int32_t t1;
+ struct nfsmount *nmp = VFSTONFS(vp->v_mount);
+ caddr_t cp2;
+ int error = 0, wccflag = NFSV3_WCCRATTR;
+
+ if ((nmp->nm_flag & NFSMNT_HASWRITEVERF) == 0)
+ return (0);
+ nfsstats.rpccnt[NFSPROC_COMMIT]++;
+ info.nmi_mb = info.nmi_mreq = nfsm_reqhead(NFSX_FH(1));
+ nfsm_fhtom(&info, vp, 1);
+
+ tl = nfsm_build(&info.nmi_mb, 3 * NFSX_UNSIGNED);
+ txdr_hyper(offset, tl);
+ tl += 2;
+ *tl = txdr_unsigned(cnt);
+
+ info.nmi_procp = procp;
+ info.nmi_cred = VTONFS(vp)->n_wcred;
+ error = nfs_request(vp, NFSPROC_COMMIT, &info);
+ nfsm_wcc_data(vp, wccflag);
+
+ if (!error)
+ {
+ nfsm_dissect(tl, u_int32_t *, NFSX_V3WRITEVERF);
+ if (bcmp((caddr_t) nmp->nm_verf, (caddr_t) tl, NFSX_V3WRITEVERF))
+ {
+ bcopy((caddr_t) tl, (caddr_t) nmp->nm_verf, NFSX_V3WRITEVERF);
+ error = NFSERR_STALEWRITEVERF;
+ }
+ }
+ m_freem(info.nmi_mrep);
+
+nfsmout:
+ return (error);
+}
+
+/* Kludge City..
+ * - make nfs_bmap() essentially a no-op that does no translation
+ * - do nfs_strategy() by doing I/O with nfs_readrpc/nfs_writerpc
+ * (Maybe I could use the process's page mapping, but I was concerned that
+ * Kernel Write might not be enabled and also figured copyout() would do
+ * a lot more work than bcopy() and also it currently happens in the
+ * context of the swapper process (2).
+ */
+
+int nfs_bmap(void *v)
+{
+ struct vop_bmap_args *ap = v;
+ struct vnode *vp = ap->a_vp;
+
+ if (ap->a_vpp != NULL)
+ *ap->a_vpp = vp;
+ if (ap->a_bnp != NULL)
+ *ap->a_bnp = ap->a_bn * btodb(vp->v_mount->mnt_stat.f_iosize);
+ return (0);
+}
+
+/* fsync vnode op. Just call nfs_flush() with commit == 1. */
+
+int nfs_fsync(void *v)
+{
+ struct vop_fsync_args *ap = v;
+
+ return (nfs_flush(ap->a_vp, ap->a_cred, ap->a_waitfor, ap->a_p, 1));
+}
+
+/* Flush all the blocks associated with a vnode.
+ * Walk through the buffer pool and push any dirty pages
+ * associated with the vnode.
+ */
+
+int
+nfs_flush(struct vnode *vp, struct ucred *cred, int waitfor, struct proc *p,
+ int commit)
+{
+ struct nfsnode *np = VTONFS(vp);
+ struct buf *bp;
+ int i;
+ struct buf *nbp;
+ struct nfsmount *nmp = VFSTONFS(vp->v_mount);
+ int s, error = 0, slptimeo = 0, slpflag = 0, retv, bvecpos;
+ int passone = 1;
+ u_quad_t off = (u_quad_t) - 1, endoff = 0, toff;
+#ifndef NFS_COMMITBVECSIZ
+# define NFS_COMMITBVECSIZ 20
+#endif
+ struct buf *bvec[NFS_COMMITBVECSIZ];
+
+ if (nmp->nm_flag & NFSMNT_INT)
+ slpflag = PCATCH;
+ if (!commit)
+ passone = 0;
+
+ /* A b_flags == (B_DELWRI | B_NEEDCOMMIT) block has been written to the
+ * server, but nas not been committed to stable storage on the server
+ * yet. On the first pass, the byte range is worked out and the commit
+ * rpc is done. On the second pass, nfs_writebp() is called to do the
+ * job.
+ */
+
+again:
+ bvecpos = 0;
+ if (NFS_ISV3(vp) && commit)
+ {
+ s = splbio();
+ for (bp = LIST_FIRST(&vp->v_dirtyblkhd); bp != NULL; bp = nbp)
+ {
+ nbp = LIST_NEXT(bp, b_vnbufs);
+ if (bvecpos >= NFS_COMMITBVECSIZ)
+ break;
+ if ((bp->b_flags & (B_BUSY | B_DELWRI | B_NEEDCOMMIT))
+ != (B_DELWRI | B_NEEDCOMMIT))
+ continue;
+ bremfree(bp);
+ bp->b_flags |= B_WRITEINPROG;
+ buf_acquire(bp);
+
+ /* A list of these buffers is kept so that the
+ * second loop knows which buffers have actually
+ * been committed. This is necessary, since there
+ * may be a race between the commit rpc and new
+ * uncommitted writes on the file.
+ */
+
+ bvec[bvecpos++] = bp;
+ toff = ((u_quad_t) bp->b_blkno) * DEV_BSIZE + bp->b_dirtyoff;
+ if (toff < off)
+ off = toff;
+ toff += (u_quad_t) (bp->b_dirtyend - bp->b_dirtyoff);
+ if (toff > endoff)
+ endoff = toff;
+ }
+ splx(s);
+ }
+ if (bvecpos > 0)
+ {
+ /* Commit data on the server, as required. */
+
+ bcstats.pendingwrites++;
+ bcstats.numwrites++;
+ retv = nfs_commit(vp, off, (int)(endoff - off), p);
+ if (retv == NFSERR_STALEWRITEVERF)
+ nfs_clearcommit(vp->v_mount);
+
+ /* Now, either mark the blocks I/O done or mark the
+ * blocks dirty, depending on whether the commit
+ * succeeded.
+ */
+
+ for (i = 0; i < bvecpos; i++)
+ {
+ bp = bvec[i];
+ bp->b_flags &= ~(B_NEEDCOMMIT | B_WRITEINPROG);
+ if (retv)
+ {
+ if (i == 0)
+ bcstats.pendingwrites--;
+ brelse(bp);
+ }
+ else
+ {
+ if (i > 0)
+ bcstats.pendingwrites++;
+ s = splbio();
+ buf_undirty(bp);
+ vp->v_numoutput++;
+ bp->b_flags |= B_ASYNC;
+ bp->b_flags &= ~(B_READ | B_DONE | B_ERROR);
+ bp->b_dirtyoff = bp->b_dirtyend = 0;
+ biodone(bp);
+ splx(s);
+ }
+ }
+ }
+
+ /* Start/do any write(s) that are required. */
+
+loop:
+ s = splbio();
+ for (bp = LIST_FIRST(&vp->v_dirtyblkhd); bp != NULL; bp = nbp)
+ {
+ nbp = LIST_NEXT(bp, b_vnbufs);
+ if (bp->b_flags & B_BUSY)
+ {
+ if (waitfor != MNT_WAIT || passone)
+ continue;
+ bp->b_flags |= B_WANTED;
+ error = tsleep((caddr_t) bp, slpflag | (PRIBIO + 1),
+ "nfsfsync", slptimeo);
+ splx(s);
+ if (error)
+ {
+ if (nfs_sigintr(nmp, NULL, p))
+ return (EINTR);
+ if (slpflag == PCATCH)
+ {
+ slpflag = 0;
+ slptimeo = 2 * hz;
+ }
+ }
+ goto loop;
+ }
+ if ((bp->b_flags & B_DELWRI) == 0)
+ panic("nfs_fsync: not dirty");
+ if ((passone || !commit) && (bp->b_flags & B_NEEDCOMMIT))
+ continue;
+ bremfree(bp);
+ if (passone || !commit)
+ {
+ bp->b_flags |= B_ASYNC;
+ }
+ else
+ {
+ bp->b_flags |= (B_ASYNC | B_WRITEINPROG | B_NEEDCOMMIT);
+ }
+ buf_acquire(bp);
+ splx(s);
+ VOP_BWRITE(bp);
+ goto loop;
+ }
+ splx(s);
+ if (passone)
+ {
+ passone = 0;
+ goto again;
+ }
+ if (waitfor == MNT_WAIT)
+ {
+ loop2:
+ s = splbio();
+ error = vwaitforio(vp, slpflag, "nfs_fsync", slptimeo);
+ splx(s);
+ if (error)
+ {
+ if (nfs_sigintr(nmp, NULL, p))
+ return (EINTR);
+ if (slpflag == PCATCH)
+ {
+ slpflag = 0;
+ slptimeo = 2 * hz;
+ }
+ goto loop2;
+ }
+
+ if (LIST_FIRST(&vp->v_dirtyblkhd) && commit)
+ {
+#if 0
+ vprint("nfs_fsync: dirty", vp);
+#endif
+ goto loop;
+ }
+ }
+ if (np->n_flag & NWRITEERR)
+ {
+ error = np->n_error;
+ np->n_flag &= ~NWRITEERR;
+ }
+ return (error);
+}
+
+/* Print out the contents of an nfsnode. */
+
+int nfs_print(void *v)
+{
+ struct vop_print_args *ap = v;
+ struct vnode *vp = ap->a_vp;
+ struct nfsnode *np = VTONFS(vp);
+
+ printf("tag VT_NFS, fileid %ld fsid 0x%lx",
+ np->n_vattr.va_fileid, np->n_vattr.va_fsid);
+ printf("\n");
+ return (0);
+}
+
+/* Just call nfs_writebp() with the force argument set to 1. */
+
+int nfs_bwrite(void *v)
+{
+ struct vop_bwrite_args *ap = v;
+
+ return (nfs_writebp(ap->a_bp, 1));
+}
+
+/* This is a clone of vop_generic_bwrite(), except that B_WRITEINPROG isn't set unless
+ * the force flag is one and it also handles the B_NEEDCOMMIT flag.
+ */
+
+int nfs_writebp(struct buf *bp, int force)
+{
+ int oldflags = bp->b_flags, retv = 1;
+ struct proc *p = curproc; /* XXX */
+ off_t off;
+ size_t cnt;
+ int s;
+ struct vnode *vp;
+ struct nfsnode *np;
+
+ if (!(bp->b_flags & B_BUSY))
+ panic("bwrite: buffer is not busy???");
+
+ vp = bp->b_vp;
+ np = VTONFS(vp);
+
+ bp->b_flags &= ~(B_READ | B_DONE | B_ERROR);
+
+ s = splbio();
+ buf_undirty(bp);
+
+ if ((oldflags & B_ASYNC) && !(oldflags & B_DELWRI) && p)
+ ++p->p_stats->p_ru.ru_oublock;
+
+ bp->b_vp->v_numoutput++;
+ splx(s);
+
+ /* If B_NEEDCOMMIT is set, a commit rpc may do the trick. If not
+ * an actual write will have to be scheduled via. VOP_STRATEGY().
+ * If B_WRITEINPROG is already set, then push it with a write anyhow.
+ */
+
+ if ((oldflags & (B_NEEDCOMMIT | B_WRITEINPROG)) == B_NEEDCOMMIT)
+ {
+ off = ((u_quad_t) bp->b_blkno) * DEV_BSIZE + bp->b_dirtyoff;
+ cnt = bp->b_dirtyend - bp->b_dirtyoff;
+
+ rw_enter_write(&np->n_commitlock);
+ if (!(bp->b_flags & B_NEEDCOMMIT))
+ {
+ rw_exit_write(&np->n_commitlock);
+ return (0);
+ }
+
+ /* If it's already been commited by somebody else, bail. */
+
+ if (!nfs_in_committed_range(vp, bp))
+ {
+ int pushedrange = 0;
+
+ /* Since we're going to do this, push as much as we can. */
+
+ if (nfs_in_tobecommitted_range(vp, bp))
+ {
+ pushedrange = 1;
+ off = np->n_pushlo;
+ cnt = np->n_pushhi - np->n_pushlo;
+ }
+
+ bp->b_flags |= B_WRITEINPROG;
+ bcstats.pendingwrites++;
+ bcstats.numwrites++;
+ retv = nfs_commit(bp->b_vp, off, cnt, curproc);
+ bp->b_flags &= ~B_WRITEINPROG;
+
+ if (retv == 0)
+ {
+ if (pushedrange)
+ nfs_merge_commit_ranges(vp);
+ else
+ nfs_add_committed_range(vp, bp);
+ }
+ else
+ bcstats.pendingwrites--;
+ }
+ else
+ retv = 0; /* It has already been commited. */
+
+ rw_exit_write(&np->n_commitlock);
+ if (!retv)
+ {
+ bp->b_dirtyoff = bp->b_dirtyend = 0;
+ bp->b_flags &= ~B_NEEDCOMMIT;
+ s = splbio();
+ biodone(bp);
+ splx(s);
+ }
+ else if (retv == NFSERR_STALEWRITEVERF)
+ nfs_clearcommit(bp->b_vp->v_mount);
+ }
+ if (retv)
+ {
+ if (force)
+ bp->b_flags |= B_WRITEINPROG;
+ VOP_STRATEGY(bp);
+ }
+
+ if ((oldflags & B_ASYNC) == 0)
+ {
+ int rtval;
+
+ bp->b_flags |= B_RAW;
+ rtval = biowait(bp);
+ if (!(oldflags & B_DELWRI) && p)
+ {
+ ++p->p_stats->p_ru.ru_oublock;
+ }
+ brelse(bp);
+ return (rtval);
+ }
+
+ return (0);
+}
+
+/* nfs special file access vnode op.
+ * Essentially just get vattr and then imitate iaccess() since the device is
+ * local to the client.
+ */
+
+int nfsspec_access(void *v)
+{
+ struct vop_access_args *ap = v;
+ struct vattr va;
+ struct vnode *vp = ap->a_vp;
+ int error;
+
+ /* Disallow write attempts on filesystems mounted read-only;
+ * unless the file is a socket, fifo, or a block or character
+ * device resident on the filesystem.
+ */
+
+ if ((ap->a_mode & VWRITE) && (vp->v_mount->mnt_flag & MNT_RDONLY))
+ {
+ switch (vp->v_type)
+ {
+ case VREG:
+ case VDIR:
+ case VLNK:
+ return (EROFS);
+ default:
+ break;
+ }
+ }
+
+ error = VOP_GETATTR(vp, &va, ap->a_cred, ap->a_p);
+ if (error)
+ return (error);
+
+ return (vaccess(vp->v_type, va.va_mode, va.va_uid, va.va_gid,
+ ap->a_mode, ap->a_cred));
+}
+
+int nfs_poll(void *v)
+{
+ struct vop_poll_args *ap = v;
+
+ /* We should really check to see if I/O is possible. */
+
+ return (ap->a_events & (POLLIN | POLLOUT | POLLRDNORM | POLLWRNORM));
+}
diff --git a/nuttx/fs/nfs/rpc.h b/nuttx/fs/nfs/rpc.h
index 0a907c126..f48a45b0f 100644
--- a/nuttx/fs/nfs/rpc.h
+++ b/nuttx/fs/nfs/rpc.h
@@ -1,7 +1,15 @@
-/*
- * copyright (c) 2003
- * the regents of the university of michigan
- * all rights reserved
+/****************************************************************************
+ * fs/nfs/rpc.h
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012 Jose Pablo Rojas Vargas. All rights reserved.
+ * Author: Jose Pablo Rojas Vargas <jrojas@nx-engineering.com>
+ *
+ * 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
@@ -20,11 +28,9 @@
* 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.
+ *
+ * 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.
@@ -57,13 +63,22 @@
* 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 _RPCCLNT_H_
-#define _RPCCLNT_H_
+#ifndef __FS_NFS_RPC_H
+#define __FS_NFS_RPC_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
#include <sys/types.h>
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
/* for rpcclnt's rc_flags */
#define RPCCLNT_SOFT 0x001 /* soft mount (hard is details) */
@@ -78,6 +93,10 @@
#define RPCCLNT_RCVLOCK 0x400
#define RPCCLNT_WANTRCV 0x800
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
struct rpc_program
{
uint32_t prog_id;
@@ -155,8 +174,7 @@ struct rpc_reply
struct rpc_auth_info rpc_verfi;
};
-/*
- * RPC Client connection context.
+/* RPC Client connection context.
* One allocated on every NFS mount.
* Holds RPC specific information for mount.
*/
@@ -202,19 +220,22 @@ struct rpcclnt
struct rpc_program * rc_prog;
- char *rc_servername;
+ //char *rc_servername;
int rc_proctlen; /* if == 0 then rc_proct == NULL */
int * rc_proct;
};
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
/*
void rpcclnt_create(struct rpcclnt ** rpc);
void rpcclnt_destroy(struct rpcclnt * rpc);
#define rpcclnt_get(X) rpcclnt_create(&(X))
#define rpcclnt_put(X) rpcclnt_destroy(X)
-
*/
void rpcclnt_init(void);
diff --git a/nuttx/fs/nfs/rpc_clnt.c b/nuttx/fs/nfs/rpc_clnt.c
index a852c8036..3ad5bbaa9 100644
--- a/nuttx/fs/nfs/rpc_clnt.c
+++ b/nuttx/fs/nfs/rpc_clnt.c
@@ -1,12 +1,18 @@
-/*
- * rpcclnt.c
+/****************************************************************************
+ * fs/nfs/rpc_clnt.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012 Jose Pablo Rojas Vargas. All rights reserved.
+ * Author: Jose Pablo Rojas Vargas <jrojas@nx-engineering.com>
+ *
+ * Leveraged from OpenBSD:
*
- * Copyright (c) 2004 The Regents of the University of Michigan.
- * All rights reserved.
+ * Copyright (c) 2004 The Regents of the University of Michigan.
+ * All rights reserved.
*
- * Copyright (c) 2004 Weston Andros Adamson <muzzle@umich.edu>.
- * Copyright (c) 2004 Marius Aamodt Eriksen <marius@umich.edu>.
- * All rights reserved.
+ * Copyright (c) 2004 Weston Andros Adamson <muzzle@umich.edu>.
+ * Copyright (c) 2004 Marius Aamodt Eriksen <marius@umich.edu>.
+ * All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -32,11 +38,9 @@
* 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.
- */
-
-/*
- * Copyright (c) 1989, 1991, 1993, 1995 The Regents of the University of
- * California. All rights reserved.
+ *
+ * Copyright (c) 1989, 1991, 1993, 1995 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.
@@ -66,7 +70,15 @@
* 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_NFS_SOCKET_H
+#define __FS_NFS_NFS_SOCKET_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
#include <sys/socket.h>
#include <queue.h>
@@ -80,17 +92,20 @@
#include <debug.h>
#include "xdr_subs.h"
-#include "rpc_types.h"
+#include "nfs_args.h"
#include "nfs_proto.h"
#include "nfs.h"
#include "rpc.h"
#include "rpc_clnt_private.h"
#include "rpc_v2.h"
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
#define RPC_RETURN(X) do { dbg("returning %d", X); return X; }while(0)
-/*
- * Estimate rto for an nfs rpc sent via. an unreliable datagram. Use the mean
+/* Estimate rto for an nfs rpc sent via. an unreliable datagram. Use the mean
* and mean deviation of rtt for the appropriate type of rpc for the frequent
* rpcs and a default for the others. The justification for doing "other"
* this way is that these rpcs happen so infrequently that timer est. would
@@ -98,6 +113,7 @@
* conservative timeout is desired. getattr, lookup - A+2D read, write -
* A+4D other - nm_timeo
*/
+
#define RPC_RTO(n, t) \
((t) == 0 ? (n)->rc_timeo : \
((t) < 3 ? \
@@ -110,8 +126,7 @@
#define RPC_SDRTT(s,r) (r)->r_rpcclnt->rc_sdrtt[rpcclnt_proct((s),\
(r)->r_procnum) - 1]
-/*
- * There is a congestion window for outstanding rpcs maintained per mount
+/* There is a congestion window for outstanding rpcs maintained per mount
* point. The cwnd size is adjusted in roughly the way that: Van Jacobson,
* Congestion avoidance and Control, In "Proceedings of SIGCOMM '88". ACM,
* August 1988. describes for TCP. The cwnd size is chopped in half on a
@@ -121,12 +136,19 @@
* were found to be too much of a performance hit (ave. rtt 3 times larger),
* I suspect due to the large rtt that nfs rpcs have.
*/
+
#define RPC_CWNDSCALE 256
#define RPC_MAXCWND (RPC_CWNDSCALE * 32)
-static int rpcclnt_backoff[8] = { 2, 4, 8, 16, 32, 64, 128, 256, };
#define RPC_ERRSTR_ACCEPTED_SIZE 6
-char *rpc_errstr_accepted[RPC_ERRSTR_ACCEPTED_SIZE] = {
+#define RPC_ERRSTR_AUTH_SIZE 6
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+char *rpc_errstr_accepted[RPC_ERRSTR_ACCEPTED_SIZE] =
+{
"", /* no good message... */
"remote server hasn't exported program.",
"remote server can't support version number.",
@@ -135,13 +157,14 @@ char *rpc_errstr_accepted[RPC_ERRSTR_ACCEPTED_SIZE] = {
"remote error. remote side memory allocation failure?"
};
-char *rpc_errstr_denied[2] = {
+char *rpc_errstr_denied[2] =
+{
"remote server doesnt support rpc version 2!",
"remote server authentication error."
};
-#define RPC_ERRSTR_AUTH_SIZE 6
-char *rpc_errstr_auth[RPC_ERRSTR_AUTH_SIZE] = {
+char *rpc_errstr_auth[RPC_ERRSTR_AUTH_SIZE] =
+{
"",
"auth error: bad credential (seal broken).",
"auth error: client must begin new session.",
@@ -150,9 +173,14 @@ char *rpc_errstr_auth[RPC_ERRSTR_AUTH_SIZE] = {
"auth error: rejected for security reasons.",
};
-/*
- * Static data, mostly RPC constants in XDR form
- */
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static int rpcclnt_backoff[8] = { 2, 4, 8, 16, 32, 64, 128, 256, };
+
+/* Static data, mostly RPC constants in XDR form */
+
static uint32_t rpc_reply, rpc_call, rpc_vers, rpc_msgdenied,
rpc_mismatch, rpc_auth_unix, rpc_msgaccepted, rpc_autherr, rpc_auth_null;
@@ -163,12 +191,15 @@ int rpcclnt_ticks;
struct rpc_call *callmgs;
struct rpc_reply *replymsg;
-/*
- * Queue head for rpctask's
- */
+/* Queue head for rpctask's */
+
static dq_queue_t *rpctask_q;
//struct callout_handle rpcclnt_timer_handle;
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
static int rpcclnt_send(struct socket *, struct sockaddr *, struct rpc_call *,
struct rpctask *);
static int rpcclnt_receive(struct rpctask *, struct sockaddr *,
@@ -181,230 +212,18 @@ static int rpcclnt_sndlock(int *, struct rpctask *);
static void rpcclnt_sndunlock(int *);
static int rpcclnt_rcvlock(struct rpctask *);
static void rpcclnt_rcvunlock(int *);
+static int rpcclnt_sigintr(struct rpcclnt *, struct rpctask *, cthread_t *);
#endif
static void rpcclnt_softterm(struct rpctask *task);
static uint32_t rpcclnt_proct(struct rpcclnt *, uint32_t);
static int rpcclnt_buildheader(struct rpcclnt *, int, int, struct rpc_call *);
-void rpcclnt_init(void)
-{
- rpcclnt_ticks = (CLOCKS_PER_SEC * RPC_TICKINTVL + 500) / 1000;
- if (rpcclnt_ticks < 1)
- rpcclnt_ticks = 1;
- rpcstats.rpcretries = 0;
- rpcstats.rpcrequests = 0;
- rpcstats.rpctimeouts = 0;
- rpcstats.rpcunexpected = 0;
- rpcstats.rpcinvalid = 0;
-
- /*
- * rpc constants how about actually using more than one of these!
- */
-
- rpc_reply = txdr_unsigned(RPC_REPLY);
- rpc_vers = txdr_unsigned(RPC_VER2);
- rpc_call = txdr_unsigned(RPC_CALL);
- rpc_msgdenied = txdr_unsigned(RPC_MSGDENIED);
- rpc_msgaccepted = txdr_unsigned(RPC_MSGACCEPTED);
- rpc_mismatch = txdr_unsigned(RPC_MISMATCH);
- rpc_autherr = txdr_unsigned(RPC_AUTHERR);
- rpc_auth_unix = txdr_unsigned(RPCAUTH_UNIX);
- rpc_auth_null = txdr_unsigned(RPCAUTH_NULL);
-
- /* initialize rpctask queue */
- dq_init(rpctask_q);
-
- rpcclnt_timer(NULL, callmgs);
-
- printf("rpc initialed");
- return;
-}
-
-/*
-void
-rpcclnt_uninit(void)
-{
- printf("uninit");
- untimeout(rpcclnt_timer, (void *)NULL, rpcclnt_timer_handle);
-
-}
-*/
-
-/*
- * Initialize sockets and congestion for a new RPC connection. We do not free
- * the sockaddr if error.
- */
-int rpcclnt_connect(struct rpcclnt *rpc)
-{
- struct socket *so;
- int error;
- struct sockaddr *saddr;
- struct sockaddr_in *sin;
- struct timeval *tv;
- uint16_t tport;
-
- /* create the socket */
- rpc->rc_so = NULL;
- saddr = rpc->rc_name;
- rpc->rc_sotype = SOCK_DGRAM;
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
- error =
- psock_socket(saddr->sa_family, rpc->rc_sotype, rpc->rc_soproto, rpc->rc_so);
-
- if (error != 0)
- {
- printf("error %d in psock_socket()", error);
- RPC_RETURN(error);
- }
-
- so = rpc->rc_so;
- rpc->rc_soflags = so->s_flags;
-
- /*
- * Some servers require that the client port be a reserved port
- * number. We always allocate a reserved port, as this prevents
- * filehandle disclosure through UDP port capture.
- */
- sin->sin_family = AF_INET;
- sin->sin_addr.s_addr = INADDR_ANY;
- tport = 1024;
-
- do
- {
- tport--;
- sin->sin_port = htons(tport);
- error = psock_bind(so, (struct sockaddr *)sin, sizeof(*sin));
- }
- while (error == EADDRINUSE && tport > 1024 / 2);
-
- if (error)
- {
- printf("bind failed\n");
- goto bad;
- }
-
- /*
- * Protocols that do not require connections may be optionally left
- * unconnected for servers that reply from a port other than
- * NFS_PORT.
- */
-
-#ifdef CONFIG_NFS_TCPIP
- if (rpc->rc_soflags == PR_CONNREQUIRED)
- {
- error = ENOTCONN;
- goto bad;
-
- }
- else
- {
-#endif
- error = psock_connect(so, saddr, sizeof(*saddr));
-
- if (error)
- {
- dbg("psock_connect returns %d", error);
- goto bad;
-
- }
-
-#ifdef CONFIG_NFS_TCPIP
- }
-#endif
-
- /*
- * Always set receive timeout to detect server crash and reconnect.
- * Otherwise, we can get stuck in psock_receive forever.
- */
-
- tv->tv_sec = 1;
- tv->tv_usec = 0;
-
- if ((error =
- psock_setsockopt(so, SOL_SOCKET, SO_RCVTIMEO, (const void *)tv,
- sizeof(*tv))))
- {
- goto bad;
- }
-
- /* Initialize other non-zero congestion variables */
- rpc->rc_srtt[0] = rpc->rc_srtt[1] = rpc->rc_srtt[2] = rpc->rc_srtt[3] =
- rpc->rc_srtt[4] = (RPC_TIMEO << 3);
- rpc->rc_sdrtt[0] = rpc->rc_sdrtt[1] = rpc->rc_sdrtt[2] = rpc->rc_sdrtt[3] =
- rpc->rc_sdrtt[4] = 0;
- rpc->rc_cwnd = RPC_MAXCWND / 2; /* Initial send window */
- rpc->rc_sent = 0;
- rpc->rc_timeouts = 0;
-
- RPC_RETURN(0);
-
-bad:
- rpcclnt_disconnect(rpc);
- RPC_RETURN(error);
-}
-
-/*
- * Reconnect routine: Called when a connection is broken on a reliable
- * protocol. - clean up the old socket - nfs_connect() again - set
- * TASK_MUSTRESEND for all outstanding requests on mount point If this
- * fails the mount point is DEAD! nb: Must be called with the
- * nfs_sndlock() set on the mount point.
- */
-int rpcclnt_reconnect(struct rpctask *rep)
-{
- struct rpctask *rp;
- struct rpcclnt *rpc = rep->r_rpcclnt;
- int error;
-
- rpcclnt_disconnect(rpc);
- while ((error = rpcclnt_connect(rpc)) != 0)
- {
- if (error == EINTR || error == ERESTART)
- return (EINTR);
- }
-
- /*
- * Loop through outstanding request list and fix up all
- * requests on old socket.
- */
- for (rp = (struct rpctask *)rpctask_q->head; rp != NULL;
- rp = (struct rpctask *)rp->r_chain.blink)
- {
- if (rp->r_rpcclnt == rpc)
- rp->r_flags |= TASK_MUSTRESEND;
- }
- return (0);
-}
-
-void rpcclnt_disconnect(struct rpcclnt *rpc)
-{
- struct socket *so;
-
- if (rpc->rc_so != NULL)
- {
- so = rpc->rc_so;
- rpc->rc_so = NULL;
- (void)psock_close(so);
- }
-}
-
-#ifdef CONFIG_NFS_TCPIP
-void rpcclnt_safedisconnect(struct rpcclnt *rpc)
-{
- struct rpctask dummytask;
-
- memset((void *)dummytask, 0, sizeof(*call));
- dummytask.r_rpcclnt = rpc;
- rpcclnt_rcvlock(&dummytask);
- rpcclnt_disconnect(rpc);
- rpcclnt_rcvunlock(&rpc->rc_flag);
-}
-
-#endif
-
-/*
- * This is the nfs send routine. For connection based socket types, it must
+/* This is the nfs send routine. For connection based socket types, it must
* be called with an nfs_sndlock() on the socket. "rep == NULL" indicates
* that it has been called from a server. For the client side: - return EINTR
* if the RPC is terminated, 0 otherwise - set TASK_MUSTRESEND if the send fails
@@ -413,6 +232,7 @@ void rpcclnt_safedisconnect(struct rpcclnt *rpc)
* signal - return EPIPE if a connection is lost for connection based sockets
* (TCP...) - do any cleanup required by recoverable socket errors (???)
*/
+
static int
rpcclnt_send(struct socket *so, struct sockaddr *nam, struct rpc_call *call,
struct rpctask *rep)
@@ -479,13 +299,13 @@ rpcclnt_send(struct socket *so, struct sockaddr *nam, struct rpc_call *call,
RPC_RETURN(error);
}
-/*
- * Receive a Sun RPC Request/Reply. For SOCK_DGRAM, the work is all
+/* Receive a Sun RPC Request/Reply. For SOCK_DGRAM, the work is all
* done by soreceive().For SOCK_STREAM, first get the
* Record Mark to find out how much more there is to get. We must
* lock the socket against other receivers until we have an entire
* rpc request/reply.
*/
+
static int rpcclnt_receive(struct rpctask *rep, struct sockaddr *aname,
struct rpc_reply *reply, struct rpc_call *call)
{
@@ -495,19 +315,17 @@ static int rpcclnt_receive(struct rpctask *rep, struct sockaddr *aname,
#endif
int error, sotype, rcvflg;
- /*
- * Set up arguments for soreceive()
- */
+ /* Set up arguments for soreceive() */
sotype = rep->r_rpcclnt->rc_sotype;
- /*
- * For reliable protocols, lock against other senders/receivers in
+ /* For reliable protocols, lock against other senders/receivers in
* case a reconnect is necessary. For SOCK_STREAM, first get the
* Record Mark to find out how much more there is to get. We must
* lock the socket against other receivers until we have an entire
* rpc request/reply.
*/
+
#ifdef CONFIG_NFS_TCPIP
if (sotype != SOCK_DGRAM)
{
@@ -515,14 +333,13 @@ static int rpcclnt_receive(struct rpctask *rep, struct sockaddr *aname,
if (error != 0)
return (error);
tryagain:
- /*
- * Check for fatal errors and resending request.
- */
- /*
+ /* Check for fatal errors and resending request.
+ *
* Ugh: If a reconnect attempt just happened, rc_so would
* have changed. NULL indicates a failed attempt that has
* essentially shut down this mount point.
*/
+
if (rep->r_flags & TASK_SOFTTERM)
{
rpcclnt_sndunlock(&rep->r_rpcclnt->rc_flag);
@@ -577,11 +394,12 @@ static int rpcclnt_receive(struct rpctask *rep, struct sockaddr *aname,
}
len = ntohl(len) & ~0x80000000;
- /*
- * This is SERIOUS! We are out of sync with the
+
+ /* This is SERIOUS! We are out of sync with the
* sender and forcing a disconnect/reconnect is all I
* can do.
*/
+
if (len > RPC_MAXPACKET)
{
printf("%s (%d) from rpc server %s\n",
@@ -612,13 +430,13 @@ static int rpcclnt_receive(struct rpctask *rep, struct sockaddr *aname,
}
else
{
- /*
- * NB: Since uio_resid is big, MSG_WAITALL is ignored
+ /* NB: Since uio_resid is big, MSG_WAITALL is ignored
* and soreceive() will return when it has either a
* control msg or a data msg. We have no use for
* control msg., but must grab them and then throw
* them away so we know what is going on.
*/
+
do
{
rcvflg = 0;
@@ -681,8 +499,7 @@ static int rpcclnt_receive(struct rpctask *rep, struct sockaddr *aname,
RPC_RETURN(error);
}
-/*
- * Implement receipt of reply on a socket. We must search through the list of
+/* Implement receipt of reply on a socket. We must search through the list of
* received datagrams matching them with outstanding requests using the xid,
* until ours is found.
*/
@@ -699,17 +516,16 @@ rpcclnt_reply(struct rpctask *myrep, struct rpc_call *call,
uint32_t rxid;
int error;
- /*
- * Loop around until we get our own reply
- */
+ /* Loop around until we get our own reply */
+
for (;;)
{
- /*
- * Lock against other receivers so that I don't get stuck in
+ /* Lock against other receivers so that I don't get stuck in
* sbwait() after someone else has received my reply for me.
* Also necessary for connection based protocols to avoid
* race conditions during a reconnect.
*/
+
#ifdef CONFIG_NFS_TCPIP
error = rpcclnt_rcvlock(myrep);
if (error)
@@ -726,10 +542,10 @@ rpcclnt_reply(struct rpctask *myrep, struct rpc_call *call,
if (error != 0)
{
- /*
- * Ignore routing errors on connectionless
+ /* Ignore routing errors on connectionless
* protocols??
*/
+
if (RPCIGNORE_SOERROR(rpc->rc_soflags, error))
{
if (myrep->r_flags & TASK_GETONEREP)
@@ -740,9 +556,8 @@ rpcclnt_reply(struct rpctask *myrep, struct rpc_call *call,
RPC_RETURN(error);
}
- /*
- * Get the xid and check that it is an rpc reply
- */
+ /* Get the xid and check that it is an rpc reply */
+
rxid = reply->rp_xid;
if (reply->rp_direction != rpc_reply)
{
@@ -751,19 +566,20 @@ rpcclnt_reply(struct rpctask *myrep, struct rpc_call *call,
RPC_RETURN(0);
continue;
}
- /*
- * Loop through the request list to match up the reply Iff no
+
+ /* Loop through the request list to match up the reply Iff no
* match, just drop the datagram
*/
+
for (rep = (struct rpctask *)rpctask_q->head; rep;
rep = (struct rpctask *)rep->r_chain.flink)
{
if (rxid == rep->r_xid)
{
- /*
- * Update congestion window. Do the additive
+ /* Update congestion window. Do the additive
* increase of one rpc/rtt.
*/
+
if (rpc->rc_cwnd <= rpc->rc_sent)
{
rpc->rc_cwnd +=
@@ -776,20 +592,20 @@ rpcclnt_reply(struct rpctask *myrep, struct rpc_call *call,
rep->r_flags &= ~TASK_SENT;
rpc->rc_sent -= RPC_CWNDSCALE;
- /*
- * Update rtt using a gain of 0.125 on the
+ /* Update rtt using a gain of 0.125 on the
* mean and a gain of 0.25 on the deviation.
*/
+
if (rep->r_flags & TASK_TIMING)
{
- /*
- * Since the timer resolution of
+ /* Since the timer resolution of
* NFS_HZ is so course, it can often
* result in r_rtt == 0. Since r_rtt
* == N means that the actual rtt is
* between N+dt and N+2-dt ticks, add
* 1.
*/
+
t1 = rep->r_rtt + 1;
t1 -= (RPC_SRTT(rpc, rep) >> 3);
RPC_SRTT(rpc, rep) += t1;
@@ -802,10 +618,11 @@ rpcclnt_reply(struct rpctask *myrep, struct rpc_call *call,
break;
}
}
- /*
- * If not matched to a request, drop it. If it's mine, get
+
+ /* If not matched to a request, drop it. If it's mine, get
* out.
*/
+
if (rep == 0)
{
rpcstats.rpcunexpected++;
@@ -820,10 +637,377 @@ rpcclnt_reply(struct rpctask *myrep, struct rpc_call *call,
}
}
-/* XXX: ignores tryagain! */
+#ifdef CONFIG_NFS_TCPIP
+static int
+rpcclnt_sigintr( struct rpcclnt *rpc, struct rpctask *task, cthread_t *td)
+{
+ struct proc *p;
+ sigset_t tmpset;
+
+ if (rpc == NULL)
+ return EFAULT;
+
+ if (ISSET(rpc->rc_flag, RPCCLNT_REDIRECT)) /* Should signal? */
+ return (0);
+
+ /* XXX deal with forced unmounts */
+
+ if (task && ISSET(task->r_flags, TASK_SOFTTERM))
+ RPC_RETURN(EINTR);
+
+ if (!ISSET(rpc->rc_flag, RPCCLNT_INT))
+ RPC_RETURN(0);
+
+ if (td == NULL)
+ return (0);
+
+ p = cthread_proc(td);
+
+ PROC_LOCK(p);
+ tmpset = p->p_siglist;
+ SIGSETNAND(tmpset, td->td_sigmask);
+ mtx_lock(&p->p_sigacts->ps_mtx);
+ SIGSETNAND(tmpset, p->p_sigacts->ps_sigignore);
+ mtx_unlock(&p->p_sigacts->ps_mtx);
+ if (SIGNOTEMPTY(p->p_siglist) && RPCCLNTINT_SIGMASK(tmpset))
+ {
+ PROC_UNLOCK(p);
+ RPC_RETURN(EINTR);
+ }
+ PROC_UNLOCK(p);
+ RPC_RETURN(0);
+}
+
+/* Lock a socket against others. Necessary for STREAM sockets to ensure you
+ * get an entire rpc request/reply and also to avoid race conditions between
+ * the processes with nfs requests in progress when a reconnect is necessary.
+ */
+
+static int rpcclnt_sndlock(int *flagp, struct rpctask *task)
+{
+ int slpflag = 0, slptimeo = 0;
+
+ if (task)
+ {
+ if (task->r_rpcclnt->rc_flag & RPCCLNT_INT)
+ slpflag = PCATCH;
+ }
+
+ while (*flagp & RPCCLNT_SNDLOCK)
+ {
+ if (rpcclnt_sigintr(task->r_rpcclnt, task, p))
+ return (EINTR);
+ *flagp |= RPCCLNT_WANTSND;
+ if (slpflag == PCATCH)
+ {
+ slpflag = 0;
+ slptimeo = 2 * CLOCKS_PER_SEC;
+ }
+ }
+
+ *flagp |= RPCCLNT_SNDLOCK;
+ return (0);
+}
+
+/* Unlock the stream socket for others. */
+
+static void rpcclnt_sndunlock(int *flagp)
+{
+ if ((*flagp & RPCCLNT_SNDLOCK) == 0)
+ {
+ panic("rpc sndunlock");
+ }
+
+ *flagp &= ~RPCCLNT_SNDLOCK;
+ if (*flagp & RPCCLNT_WANTSND)
+ {
+ *flagp &= ~RPCCLNT_WANTSND;
+ }
+}
+
+static int rpcclnt_rcvlock(struct rpctask *task)
+{
+ int *flagp = &task->r_rpcclnt->rc_flag;
+ int slpflag, slptimeo = 0;
+
+ if (*flagp & RPCCLNT_INT)
+ slpflag = PCATCH;
+ else
+ slpflag = 0;
+
+ while (*flagp & RPCCLNT_RCVLOCK)
+ {
+ if (rpcclnt_sigintr(task->r_rpcclnt, task, task->r_td))
+ return (EINTR);
+ *flagp |= RPCCLNT_WANTRCV;
+ tsleep((caddr_t) flagp, slpflag | (PZERO - 1), "rpcrcvlk", slptimeo);
+ if (slpflag == PCATCH)
+ {
+ slpflag = 0;
+ slptimeo = 2 * CLOCKS_PER_SEC;
+ }
+ }
+
+ *flagp |= RPCCLNT_RCVLOCK;
+ return (0);
+}
+
+/* Unlock the stream socket for others. */
+
+static void rpcclnt_rcvunlock(int *flagp)
+{
+ if ((*flagp & RPCCLNT_RCVLOCK) == 0)
+ {
+ panic("nfs rcvunlock");
+ }
+
+ *flagp &= ~RPCCLNT_RCVLOCK;
+ if (*flagp & RPCCLNT_WANTRCV)
+ {
+ *flagp &= ~RPCCLNT_WANTRCV;
+ wakeup((caddr_t) flagp);
+ }
+}
+#endif
+
+static uint32_t rpcclnt_proct(struct rpcclnt *rpc, uint32_t procid)
+{
+ if (rpc->rc_proctlen != 0 && rpc->rc_proct != NULL &&
+ procid < rpc->rc_proctlen)
+ return (rpc->rc_proct[procid]);
+
+ return (0);
+}
+
+static void rpcclnt_softterm(struct rpctask *task)
+{
+ task->r_flags |= TASK_SOFTTERM;
+ if (task->r_flags & TASK_SENT)
+ {
+ task->r_rpcclnt->rc_sent -= RPC_CWNDSCALE;
+ task->r_flags &= ~TASK_SENT;
+ }
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+void rpcclnt_init(void)
+{
+ rpcclnt_ticks = (CLOCKS_PER_SEC * RPC_TICKINTVL + 500) / 1000;
+ if (rpcclnt_ticks < 1)
+ rpcclnt_ticks = 1;
+ rpcstats.rpcretries = 0;
+ rpcstats.rpcrequests = 0;
+ rpcstats.rpctimeouts = 0;
+ rpcstats.rpcunexpected = 0;
+ rpcstats.rpcinvalid = 0;
+
+ /* RPC constants how about actually using more than one of these! */
+
+ rpc_reply = txdr_unsigned(RPC_REPLY);
+ rpc_vers = txdr_unsigned(RPC_VER2);
+ rpc_call = txdr_unsigned(RPC_CALL);
+ rpc_msgdenied = txdr_unsigned(RPC_MSGDENIED);
+ rpc_msgaccepted = txdr_unsigned(RPC_MSGACCEPTED);
+ rpc_mismatch = txdr_unsigned(RPC_MISMATCH);
+ rpc_autherr = txdr_unsigned(RPC_AUTHERR);
+ rpc_auth_unix = txdr_unsigned(RPCAUTH_UNIX);
+ rpc_auth_null = txdr_unsigned(RPCAUTH_NULL);
+
+ /* Initialize rpctask queue */
+
+ dq_init(rpctask_q);
+
+ rpcclnt_timer(NULL, callmgs);
+
+ printf("rpc initialed");
+ return;
+}
/*
- * code from nfs_request - goes something like this - fill in task struct -
+void
+rpcclnt_uninit(void)
+{
+ printf("uninit");
+ untimeout(rpcclnt_timer, (void *)NULL, rpcclnt_timer_handle);
+
+}
+*/
+
+/* Initialize sockets and congestion for a new RPC connection. We do not free
+ * the sockaddr if error.
+ */
+
+int rpcclnt_connect(struct rpcclnt *rpc)
+{
+ struct socket *so;
+ int error;
+ struct sockaddr *saddr;
+ struct sockaddr_in *sin;
+ struct timeval *tv;
+ uint16_t tport;
+
+ /* create the socket */
+ rpc->rc_so = NULL;
+ saddr = rpc->rc_name;
+ rpc->rc_sotype = SOCK_DGRAM;
+
+ error =
+ psock_socket(saddr->sa_family, rpc->rc_sotype, rpc->rc_soproto, rpc->rc_so);
+
+ if (error != 0)
+ {
+ printf("error %d in psock_socket()", error);
+ RPC_RETURN(error);
+ }
+
+ so = rpc->rc_so;
+ rpc->rc_soflags = so->s_flags;
+
+ /* Some servers require that the client port be a reserved port
+ * number. We always allocate a reserved port, as this prevents
+ * filehandle disclosure through UDP port capture.
+ */
+
+ sin->sin_family = AF_INET;
+ sin->sin_addr.s_addr = INADDR_ANY;
+ tport = 1024;
+
+ do
+ {
+ tport--;
+ sin->sin_port = htons(tport);
+ error = psock_bind(so, (struct sockaddr *)sin, sizeof(*sin));
+ }
+ while (error == EADDRINUSE && tport > 1024 / 2);
+
+ if (error)
+ {
+ printf("bind failed\n");
+ goto bad;
+ }
+
+ /* Protocols that do not require connections may be optionally left
+ * unconnected for servers that reply from a port other than
+ * NFS_PORT.
+ */
+
+#ifdef CONFIG_NFS_TCPIP
+ if (rpc->rc_soflags == PR_CONNREQUIRED)
+ {
+ error = ENOTCONN;
+ goto bad;
+
+ }
+ else
+ {
+#endif
+ error = psock_connect(so, saddr, sizeof(*saddr));
+
+ if (error)
+ {
+ dbg("psock_connect returns %d", error);
+ goto bad;
+
+ }
+#ifdef CONFIG_NFS_TCPIP
+ }
+#endif
+
+ /* Always set receive timeout to detect server crash and reconnect.
+ * Otherwise, we can get stuck in psock_receive forever.
+ */
+
+ tv->tv_sec = 1;
+ tv->tv_usec = 0;
+
+ if ((error =
+ psock_setsockopt(so, SOL_SOCKET, SO_RCVTIMEO, (const void *)tv,
+ sizeof(*tv))))
+ {
+ goto bad;
+ }
+
+ /* Initialize other non-zero congestion variables */
+
+ rpc->rc_srtt[0] = rpc->rc_srtt[1] = rpc->rc_srtt[2] = rpc->rc_srtt[3] =
+ rpc->rc_srtt[4] = (RPC_TIMEO << 3);
+ rpc->rc_sdrtt[0] = rpc->rc_sdrtt[1] = rpc->rc_sdrtt[2] = rpc->rc_sdrtt[3] =
+ rpc->rc_sdrtt[4] = 0;
+ rpc->rc_cwnd = RPC_MAXCWND / 2; /* Initial send window */
+ rpc->rc_sent = 0;
+ rpc->rc_timeouts = 0;
+
+ RPC_RETURN(0);
+
+bad:
+ rpcclnt_disconnect(rpc);
+ RPC_RETURN(error);
+}
+
+/* Reconnect routine: Called when a connection is broken on a reliable
+ * protocol. - clean up the old socket - nfs_connect() again - set
+ * TASK_MUSTRESEND for all outstanding requests on mount point If this
+ * fails the mount point is DEAD! nb: Must be called with the
+ * nfs_sndlock() set on the mount point.
+ */
+
+int rpcclnt_reconnect(struct rpctask *rep)
+{
+ struct rpctask *rp;
+ struct rpcclnt *rpc = rep->r_rpcclnt;
+ int error;
+
+ rpcclnt_disconnect(rpc);
+ while ((error = rpcclnt_connect(rpc)) != 0)
+ {
+ if (error == EINTR || error == ERESTART)
+ return (EINTR);
+ }
+
+ /* Loop through outstanding request list and fix up all
+ * requests on old socket.
+ */
+
+ for (rp = (struct rpctask *)rpctask_q->head; rp != NULL;
+ rp = (struct rpctask *)rp->r_chain.blink)
+ {
+ if (rp->r_rpcclnt == rpc)
+ rp->r_flags |= TASK_MUSTRESEND;
+ }
+ return (0);
+}
+
+void rpcclnt_disconnect(struct rpcclnt *rpc)
+{
+ struct socket *so;
+
+ if (rpc->rc_so != NULL)
+ {
+ so = rpc->rc_so;
+ rpc->rc_so = NULL;
+ (void)psock_close(so);
+ }
+}
+
+#ifdef CONFIG_NFS_TCPIP
+void rpcclnt_safedisconnect(struct rpcclnt *rpc)
+{
+ struct rpctask dummytask;
+
+ memset((void *)dummytask, 0, sizeof(*call));
+ dummytask.r_rpcclnt = rpc;
+ rpcclnt_rcvlock(&dummytask);
+ rpcclnt_disconnect(rpc);
+ rpcclnt_rcvunlock(&rpc->rc_flag);
+}
+#endif
+
+/* XXX: ignores tryagain! */
+
+/* Code from nfs_request - goes something like this - fill in task struct -
* links task into list - calls nfs_send() for first transmit - calls
* nfs_receive() to get reply - fills in reply (which should be initialized
* prior to calling), which is valid when 0 is returned and is NEVER freed in
@@ -831,13 +1015,12 @@ rpcclnt_reply(struct rpctask *myrep, struct rpc_call *call,
*
* always frees the request header, but NEVER frees 'mrest'
*
- */
-
-/*
+ *
* note that reply->result_* are invalid unless reply->type ==
* RPC_MSGACCEPTED and reply->status == RPC_SUCCESS and that reply->verf_*
* are invalid unless reply->type == RPC_MSGACCEPTED
*/
+
int rpcclnt_request(struct rpcclnt *rpc, int procnum, struct rpc_reply *reply)
{
struct rpc_call *call;
@@ -872,22 +1055,21 @@ int rpcclnt_request(struct rpcclnt *rpc, int procnum, struct rpc_reply *reply)
else
task->r_flags = 0;
- /*
- * Do the client side RPC.
- */
+ /* Do the client side RPC. */
+
rpcstats.rpcrequests++;
- /*
- * Chain request into list of outstanding requests. Be sure to put it
+ /* Chain request into list of outstanding requests. Be sure to put it
* LAST so timer finds oldest requests first.
*/
+
dq_addlast(&task->r_chain, rpctask_q);
- /*
- * If backing off another request or avoiding congestion, don't send
+ /* If backing off another request or avoiding congestion, don't send
* this one now but let timer do it. If not timing a request, do it
* now.
*/
+
if (rpc->rc_so && (rpc->rc_sotype != SOCK_DGRAM ||
(rpc->rc_flag & RPCCLNT_DUMBTIMR) ||
rpc->rc_sent < rpc->rc_cwnd))
@@ -918,20 +1100,17 @@ int rpcclnt_request(struct rpcclnt *rpc, int procnum, struct rpc_reply *reply)
task->r_rtt = -1;
}
- /*
- * Wait for the reply from our send.
- */
+ /* Wait for the reply from our send. */
+
if (error == 0 || error == EPIPE)
error = rpcclnt_reply(task, call, replysvr);
- /*
- * RPC done, unlink the request.
- */
+ /* RPC done, unlink the request. */
+
dq_rem(&task->r_chain, rpctask_q);
- /*
- * Decrement the outstanding request count.
- */
+ /* Decrement the outstanding request count. */
+
if (task->r_flags & TASK_SENT)
{
task->r_flags &= ~TASK_SENT; /* paranoia */
@@ -941,9 +1120,8 @@ int rpcclnt_request(struct rpcclnt *rpc, int procnum, struct rpc_reply *reply)
if (error != 0)
goto rpcmout;
- /*
- * break down the rpc header and check if ok
- */
+ /* Break down the rpc header and check if ok */
+
reply->stat.type = fxdr_unsigned(uint32_t, replysvr->stat.type);
if (reply->stat.type == RPC_MSGDENIED)
{
@@ -1005,11 +1183,11 @@ rpcmout:
RPC_RETURN(error);
}
-/*
- * Nfs timer routine Scan the nfsreq list and retranmit any requests that
+/* Nfs timer routine Scan the nfsreq list and retranmit any requests that
* have timed out To avoid retransmission attempts on STREAM sockets (in the
* future) make sure to set the r_retry field to 0 (implies nm_retry == 0).
*/
+
void rpcclnt_timer(void *arg, struct rpc_call *call)
{
struct rpctask *rep;
@@ -1037,9 +1215,9 @@ void rpcclnt_timer(void *arg, struct rpc_call *call)
if (rpc->rc_timeouts < 8)
rpc->rc_timeouts++;
}
- /*
- * Check for server not responding
- */
+
+ /* Check for server not responding */
+
if ((rep->r_flags & TASK_TPRINTFMSG) == 0 &&
rep->r_rexmit > rpc->rc_deadthresh)
{
@@ -1061,10 +1239,10 @@ void rpcclnt_timer(void *arg, struct rpc_call *call)
if ((so = rpc->rc_so) == NULL)
continue;
- /*
- * If there is enough space and the window allows.. Resend it
+ /* If there is enough space and the window allows.. Resend it
* Set r_rtt to -1 in case we fail to send it now.
*/
+
rep->r_rtt = -1;
if ((rpc->rc_flag & RPCCLNT_DUMBTIMR) || (rep->r_flags & TASK_SENT) ||
rpc->rc_sent < rpc->rc_cwnd)
@@ -1079,11 +1257,11 @@ void rpcclnt_timer(void *arg, struct rpc_call *call)
if (!error)
{
- /*
- * Iff first send, start timing else turn
+ /* Iff first send, start timing else turn
* timing off, backoff timer and divide
* congestion window by 2.
*/
+
if (rep->r_flags & TASK_SENT)
{
rep->r_flags &= ~TASK_TIMING;
@@ -1107,114 +1285,18 @@ void rpcclnt_timer(void *arg, struct rpc_call *call)
// rpcclnt_timer_handle = timeout(rpcclnt_timer, NULL, rpcclnt_ticks);
}
-#ifdef CONFIG_NFS_TCPIP
-
-/*
- * Lock a socket against others. Necessary for STREAM sockets to ensure you
- * get an entire rpc request/reply and also to avoid race conditions between
- * the processes with nfs requests in progress when a reconnect is necessary.
- */
-static int rpcclnt_sndlock(flagp, task)
- int *flagp;
- struct rpctask *task;
-{
- int slpflag = 0, slptimeo = 0;
-
- if (task)
- {
- if (task->r_rpcclnt->rc_flag & RPCCLNT_INT)
- slpflag = PCATCH;
- }
- while (*flagp & RPCCLNT_SNDLOCK)
- {
- if (rpcclnt_sigintr(task->r_rpcclnt, task, p))
- return (EINTR);
- *flagp |= RPCCLNT_WANTSND;
- if (slpflag == PCATCH)
- {
- slpflag = 0;
- slptimeo = 2 * CLOCKS_PER_SEC;
- }
- }
-
- *flagp |= RPCCLNT_SNDLOCK;
- return (0);
-}
-
-/*
- * Unlock the stream socket for others.
- */
-static void rpcclnt_sndunlock(flagp)
- int *flagp;
-{
- if ((*flagp & RPCCLNT_SNDLOCK) == 0)
- panic("rpc sndunlock");
- *flagp &= ~RPCCLNT_SNDLOCK;
- if (*flagp & RPCCLNT_WANTSND)
- {
- *flagp &= ~RPCCLNT_WANTSND;
- }
-}
-
-static int rpcclnt_rcvlock(task)
- struct rpctask *task;
-{
- int *flagp = &task->r_rpcclnt->rc_flag;
- int slpflag, slptimeo = 0;
-
- if (*flagp & RPCCLNT_INT)
- slpflag = PCATCH;
- else
- slpflag = 0;
-
- while (*flagp & RPCCLNT_RCVLOCK)
- {
- if (rpcclnt_sigintr(task->r_rpcclnt, task, task->r_td))
- return (EINTR);
- *flagp |= RPCCLNT_WANTRCV;
- tsleep((caddr_t) flagp, slpflag | (PZERO - 1), "rpcrcvlk", slptimeo);
- if (slpflag == PCATCH)
- {
- slpflag = 0;
- slptimeo = 2 * CLOCKS_PER_SEC;
- }
- }
- *flagp |= RPCCLNT_RCVLOCK;
- return (0);
-}
-
-/*
- * Unlock the stream socket for others.
- */
-static void rpcclnt_rcvunlock(flagp)
- int *flagp;
-{
+/* Build the RPC header and fill in the authorization info. */
- if ((*flagp & RPCCLNT_RCVLOCK) == 0)
- panic("nfs rcvunlock");
- *flagp &= ~RPCCLNT_RCVLOCK;
- if (*flagp & RPCCLNT_WANTRCV)
- {
- *flagp &= ~RPCCLNT_WANTRCV;
- wakeup((caddr_t) flagp);
- }
-}
-#endif
-
-/*
- * Build the RPC header and fill in the authorization info.
- */
int rpcclnt_buildheader(struct rpcclnt *rc, int procid,
int xidp, struct rpc_call *call)
{
struct timeval *tv;
srand(time(NULL));
- /*
- * The RPC header.
- */
+ /* The RPC header.*/
/* Get a new (non-zero) xid */
+
if ((rpcclnt_xid == 0) && (rpcclnt_xid_touched == 0))
{
rpcclnt_xid = rand();
@@ -1258,15 +1340,6 @@ int rpcclnt_buildheader(struct rpcclnt *rc, int procid,
return (0);
}
-static uint32_t rpcclnt_proct(struct rpcclnt *rpc, uint32_t procid)
-{
- if (rpc->rc_proctlen != 0 && rpc->rc_proct != NULL &&
- procid < rpc->rc_proctlen)
- return (rpc->rc_proct[procid]);
-
- return (0);
-}
-
int rpcclnt_cancelreqs(struct rpcclnt *rpc)
{
struct rpctask *task;
@@ -1294,13 +1367,3 @@ int rpcclnt_cancelreqs(struct rpcclnt *rpc)
return (EBUSY);
}
-
-static void rpcclnt_softterm(struct rpctask *task)
-{
- task->r_flags |= TASK_SOFTTERM;
- if (task->r_flags & TASK_SENT)
- {
- task->r_rpcclnt->rc_sent -= RPC_CWNDSCALE;
- task->r_flags &= ~TASK_SENT;
- }
-}
diff --git a/nuttx/fs/nfs/rpc_clnt_private.h b/nuttx/fs/nfs/rpc_clnt_private.h
index 990f12558..204bb2b83 100644
--- a/nuttx/fs/nfs/rpc_clnt_private.h
+++ b/nuttx/fs/nfs/rpc_clnt_private.h
@@ -1,7 +1,15 @@
-/*
- * copyright (c) 2003
- * the regents of the university of michigan
- * all rights reserved
+/****************************************************************************
+ * 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 <jrojas@nx-engineering.com>
+ *
+ * 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
@@ -20,11 +28,9 @@
* 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.
+ *
+ * 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.
@@ -57,10 +63,19 @@
* 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
-#ifndef _RPCCLNT_PRIVATE_H_
-#define _RPCCLNT_PRIVATE_H_
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
#define RPCCLNT_DEBUG 1
@@ -114,6 +129,10 @@
SIGISMEMBER(set, SIGHUP) || SIGISMEMBER(set, SIGKILL) || \
SIGISMEMBER(set, SIGQUIT))
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
/* global rpcstats
* XXX should be per rpcclnt */
@@ -126,4 +145,4 @@ struct rpcstats
int rpcinvalid;
};
-#endif /* _RPCCLNT_PRIVATE_H_ */
+#endif /* __FS_NFS_RPC_CLIENT_PRIVATE_H */
diff --git a/nuttx/fs/nfs/rpc_types.h b/nuttx/fs/nfs/rpc_types.h
index 06924f86b..a4a8ac7a3 100644
--- a/nuttx/fs/nfs/rpc_types.h
+++ b/nuttx/fs/nfs/rpc_types.h
@@ -59,34 +59,6 @@ struct lock
int dummy;
};
-typedef struct { int32_t val[2]; } fsid_t; /* file system id type */
-
-/*
- * File identifier.
- * These are unique per filesystem on a single machine.
- */
-
-#define MAXFIDSZ 16
-
-struct fid
-{
- unsigned short fid_len; /* length of data in bytes */
- unsigned short fid_reserved; /* force longword alignment */
- char fid_data[MAXFIDSZ]; /* data (variable length) */
-};
-
-/*
- * Generic file handle
- */
-
-struct fhandle
-{
- fsid_t fh_fsid; /* File system id of mount point */
- struct fid fh_fid; /* File sys specific id */
-};
-
-typedef struct fhandle fhandle_t;
-
struct componentname
{
/* Arguments to lookup. */