summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-06-10 00:13:59 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-06-10 00:13:59 +0000
commite56f40210903c13eb07168de2acdf61c8babd2ae (patch)
tree94685ece210f7fd49cb823ae1762db64c57a163d
parent59f64eb3c5ade626a3366355ae49344765d1a4c1 (diff)
downloadpx4-nuttx-e56f40210903c13eb07168de2acdf61c8babd2ae.tar.gz
px4-nuttx-e56f40210903c13eb07168de2acdf61c8babd2ae.tar.bz2
px4-nuttx-e56f40210903c13eb07168de2acdf61c8babd2ae.zip
NFS update
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4822 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/fs/nfs/nfs.h10
-rw-r--r--nuttx/fs/nfs/nfs_proto.h12
-rw-r--r--nuttx/fs/nfs/nfs_socket.c13
-rw-r--r--nuttx/fs/nfs/nfs_socket.h13
-rw-r--r--nuttx/fs/nfs/nfs_util.c92
-rw-r--r--nuttx/fs/nfs/nfs_vfsops.c129
-rw-r--r--nuttx/fs/nfs/rpc.h27
-rw-r--r--nuttx/fs/nfs/rpc_clnt.c1196
8 files changed, 683 insertions, 809 deletions
diff --git a/nuttx/fs/nfs/nfs.h b/nuttx/fs/nfs/nfs.h
index 34cf01b12..63efbdaa4 100644
--- a/nuttx/fs/nfs/nfs.h
+++ b/nuttx/fs/nfs/nfs.h
@@ -363,10 +363,14 @@ EXTERN void nfs_semtake(struct nfsmount *nmp);
EXTERN void nfs_semgive(struct nfsmount *nmp);
EXTERN int nfs_checkmount(struct nfsmount *nmp);
EXTERN int nfs_fsinfo(struct nfsmount *nmp);
+EXTERN int nfs_lookup(struct nfsmount *nmp, FAR const char *filename,
+ FAR struct file_handle *fhandle,
+ FAR struct nfs_fattr *obj_attributes,
+ FAR struct nfs_fattr *dir_attributes);
EXTERN int nfs_findnode(struct nfsmount *nmp, FAR const char *relpath,
- FAR struct file_handle *fhandle,
- FAR struct nfs_fattr *obj_attributes,
- FAR struct nfs_fattr *dir_attributes);
+ FAR struct file_handle *fhandle,
+ FAR struct nfs_fattr *obj_attributes,
+ FAR struct nfs_fattr *dir_attributes);
#undef EXTERN
#if defined(__cplusplus)
diff --git a/nuttx/fs/nfs/nfs_proto.h b/nuttx/fs/nfs/nfs_proto.h
index 20e80d833..1aeba0a6a 100644
--- a/nuttx/fs/nfs/nfs_proto.h
+++ b/nuttx/fs/nfs/nfs_proto.h
@@ -316,10 +316,10 @@ typedef enum
NFREG = 1, /* Regular file */
NFDIR = 2, /* Directory */
NFBLK = 3, /* Block special device file */
- NFCHR = 4, /* Characgter special device file */
+ NFCHR = 4, /* Character special device file */
NFLNK = 5, /* Symbolic link */
NFSOCK = 6, /* Socket */
- NFFIFO = 7
+ NFFIFO = 7 /* Named FIFO */
} nfstype;
typedef struct
@@ -588,10 +588,12 @@ struct LOOKUP3args
{
struct file_handle dirhandle;
uint32_t namelen;
- uint32_t name[1]; /* Actual size determined by namelen */
+ uint32_t name[(NAME_MAX+3) >> 2]; /* Actual size determined by namelen */
};
-#define SIZEOF_LOOKUP3args(n) \
- (sizeof(struct LOOKUP3args) + ((((n)+3) >> 2) - 1)*sizeof(uint32_t))
+
+/* Actual size of LOOKUP3args */
+
+#define SIZEOF_LOOKUP3args(n) (sizeof(struct file_handle) + sizeof(namelen) + (((n)+3) & ~3))
struct LOOKUP3resok
{
diff --git a/nuttx/fs/nfs/nfs_socket.c b/nuttx/fs/nfs/nfs_socket.c
index 141196b01..133121b29 100644
--- a/nuttx/fs/nfs/nfs_socket.c
+++ b/nuttx/fs/nfs/nfs_socket.c
@@ -125,7 +125,7 @@ int nfs_connect(struct nfsmount *nmp)
if (!rpc)
{
fdbg("ERROR: Failed to allocate rpc structure\n");
- return -ENOMEM;
+ return ENOMEM;
}
rpc->rc_prog = &nfs3_program;
@@ -180,8 +180,9 @@ void nfs_safedisconnect(struct nfsmount *nmp)
}
#endif
-int nfs_request(struct nfsmount *nmp, int procnum, FAR const void *datain,
- FAR void *dataout, size_t len)
+int nfs_request(struct nfsmount *nmp, int procnum,
+ FAR const void *request, size_t reqlen,
+ FAR void *response, size_t resplen)
{
struct rpcclnt *clnt= nmp->nm_rpcclnt;
struct rpc_reply_header replyh;
@@ -193,15 +194,15 @@ tryagain:
memset(&replyh, 0, sizeof(struct rpc_reply_header));
error = rpcclnt_request(clnt, procnum, nmp->nm_rpcclnt->rc_prog->prog_id,
- nmp->nm_rpcclnt->rc_prog->prog_version, dataout,
- datain, len);
+ nmp->nm_rpcclnt->rc_prog->prog_version, request, reqlen,
+ response, resplen);
if (error != 0)
{
fdbg("ERROR: rpcclnt_request failed: %d\n", error);
goto out;
}
- memcpy(&replyh, dataout, sizeof(struct rpc_reply_header));
+ memcpy(&replyh, response, sizeof(struct rpc_reply_header));
if (replyh.rpc_verfi.authtype != 0)
{
diff --git a/nuttx/fs/nfs/nfs_socket.h b/nuttx/fs/nfs/nfs_socket.h
index 7b67414fb..075015f21 100644
--- a/nuttx/fs/nfs/nfs_socket.h
+++ b/nuttx/fs/nfs/nfs_socket.h
@@ -55,16 +55,17 @@ extern "C" {
#endif
EXTERN void nfs_init(void);
-EXTERN int nfs_connect(struct nfsmount *);
-EXTERN void nfs_disconnect(struct nfsmount *);
+EXTERN int nfs_connect(struct nfsmount *nmp);
+EXTERN void nfs_disconnect(struct nfsmount *nmp);
#ifdef CONFIG_NFS_TCPIP
-EXTERN int nfs_sigintr(struct nfsmount *, struct nfsreq *, cthread_t *);
-EXTERN void nfs_safedisconnect(struct nfsmount *);
+EXTERN void nfs_safedisconnect(struct nfsmount *nmp);
#endif
-EXTERN int nfs_request(struct nfsmount *, int, FAR const void *, FAR void *, size_t);
+EXTERN int nfs_request(struct nfsmount *nmp, int procnum,
+ FAR const void *request, size_t reqlen,
+ FAR void *response, size_t resplen);
#undef COMP
#ifdef COMP
-EXTERN int nfs_nmcancelreqs(struct nfsmount *);
+EXTERN int nfs_nmcancelreqs(struct nfsmount *nmp);
#endif
#undef EXTERN
#if defined(__cplusplus)
diff --git a/nuttx/fs/nfs/nfs_util.c b/nuttx/fs/nfs/nfs_util.c
index 63070b76f..c07c6e519 100644
--- a/nuttx/fs/nfs/nfs_util.c
+++ b/nuttx/fs/nfs/nfs_util.c
@@ -226,7 +226,8 @@ int nfs_fsinfo(FAR struct nfsmount *nmp)
/* Request FSINFO from the server */
- error = nfs_request(nmp, NFSPROC_FSINFO, (FAR const void *)&fsinfo,
+ error = nfs_request(nmp, NFSPROC_FSINFO,
+ (FAR const void *)&fsinfo, sizeof(struct FS3args),
(FAR void *)&fsp, sizeof(struct rpc_reply_fsinfo));
if (error)
{
@@ -291,6 +292,86 @@ int nfs_fsinfo(FAR struct nfsmount *nmp)
}
/****************************************************************************
+ * Name: nfs_lookup
+ *
+ * Desciption:
+ * Given a directory file handle, and the path to file in the directory,
+ * return the file handle of the path and attributes of both the file and
+ * the directory containing the file.
+ *
+ * NOTE: The LOOKUP call differs from other RPC messages in that the
+ * call message is variable length, depending upon the size of the path
+ * name.
+ *
+ ****************************************************************************/
+
+int nfs_lookup(struct nfsmount *nmp, FAR const char *filename,
+ FAR struct file_handle *fhandle,
+ FAR struct nfs_fattr *obj_attributes,
+ FAR struct nfs_fattr *dir_attributes)
+{
+ struct LOOKUP3args request;
+ struct rpc_reply_lookup response;
+ int namelen;
+ int error = 0;
+
+ DEBUGASSERT(nmp && filename && fhandle && obj_attributes && dir_attributes);
+
+ /* Set all of the buffers to a known state */
+
+ memset(&request, 0, sizeof(struct LOOKUP3args));
+ memset(&response, 0, sizeof(struct rpc_reply_lookup));
+ memset(&obj_attributes, 0, sizeof(struct nfs_fattr));
+ memset(&dir_attributes, 0, sizeof(struct nfs_fattr));
+
+ /* Get the length of the string to be sent */
+
+ namelen = strlen(filename);
+ if (namelen > NAME_MAX)
+ {
+ fdbg("Length of \"%s\%too big: %d\n", namelen);
+ return E2BIG;
+ }
+
+ /* Initialize the request */
+
+ nfsstats.rpccnt[NFSPROC_LOOKUP]++;
+
+ memcpy(&request.dirhandle, fhandle, sizeof(struct file_handle));
+ request.namelen = txdr_unsigned(namelen);
+ memcpy(request.name, filename, namelen);
+
+ /* Request LOOKUP from the server */
+
+ error = nfs_request(nmp, NFSPROC_LOOKUP,
+ (FAR const void *)&request, SIZEOF_LOOKUP3args(namelen),
+ (FAR void *)&response, sizeof(struct rpc_reply_lookup));
+ if (error)
+ {
+ fdbg("nfs_request failed: %d\n", error);
+ return error;
+ }
+
+ /* Return the data to the caller's buffers */
+
+ memcpy(fhandle, &response.lookup.fshandle, sizeof(struct file_handle));
+
+ if (response.lookup.obj_attributes_follow != 0)
+ {
+ memcpy(obj_attributes, &response.lookup.obj_attributes,
+ sizeof(struct nfs_fattr));
+ }
+
+ if (response.lookup.dir_attributes_follow != 0)
+ {
+ memcpy(dir_attributes, &response.lookup.dir_attributes,
+ sizeof(struct nfs_fattr));
+ }
+
+ return OK;
+}
+
+/****************************************************************************
* Name: nfs_findnode
*
* Desciption:
@@ -315,8 +396,6 @@ int nfs_findnode(struct nfsmount *nmp, FAR const char *relpath,
fhandle->length = nmp->nm_fhsize;
memcpy(&fhandle->handle, &nmp->nm_fh, sizeof(nfsfh_t));
-
-#warning "Where do we get the attributes of the root file system?"
memset(obj_attributes, 0, sizeof(struct nfs_fattr));
memset(dir_attributes, 0, sizeof(struct nfs_fattr));
@@ -326,6 +405,7 @@ int nfs_findnode(struct nfsmount *nmp, FAR const char *relpath,
if (*path == '\0' || strlen(path) == 0)
{
+#warning "Where do we get the attributes of the root file system?"
return OK;
}
@@ -349,12 +429,10 @@ int nfs_findnode(struct nfsmount *nmp, FAR const char *relpath,
/* Look-up this path segment */
- nfsstats.rpccnt[NFSPROC_LOOKUP]++;
- error = rpcclnt_lookup(nmp->nm_rpcclnt, buffer, fhandle,
- obj_attributes, dir_attributes);
+ error = nfs_lookup(nmp, buffer, fhandle, obj_attributes, dir_attributes);
if (error != 0)
{
- fdbg("rpcclnt_lookup of \"%s\" failed at \"%s\": %d\n",
+ fdbg("nfs_lookup of \"%s\" failed at \"%s\": %d\n",
relpath, buffer, error);
return error;
}
diff --git a/nuttx/fs/nfs/nfs_vfsops.c b/nuttx/fs/nfs/nfs_vfsops.c
index 6de219586..c3268efbf 100644
--- a/nuttx/fs/nfs/nfs_vfsops.c
+++ b/nuttx/fs/nfs/nfs_vfsops.c
@@ -53,7 +53,6 @@
#include <stdint.h>
#include <stdbool.h>
-#include <stdio.h>
#include <stdlib.h>
#include <queue.h>
#include <string.h>
@@ -210,8 +209,9 @@ static int nfs_create(FAR struct nfsmount *nmp, struct nfsnode *np,
create.where.length = txdr_unsigned(64);
strncpy(create.where.name, relpath, 64);
- error = nfs_request(nmp, NFSPROC_CREATE, (FAR const void *)&create,
- (void *)&resok, sizeof(struct rpc_reply_create));
+ error = nfs_request(nmp, NFSPROC_CREATE,
+ (FAR const void *)&create, sizeof(struct CREATE3args),
+ (FAR void *)&resok, sizeof(struct rpc_reply_create));
}
while (error == EOPNOTSUPP);
@@ -552,8 +552,9 @@ again:
read.count = txdr_unsigned(buflen);
read.offset = txdr_unsigned(offset);
- error = nfs_request(nmp, NFSPROC_READ, (FAR const void *)&read,
- (void *)&resok, sizeof(struct rpc_reply_read));
+ error = nfs_request(nmp, NFSPROC_READ,
+ (FAR const void *)&read, sizeof(struct READ3args),
+ (FAR void *)&resok, sizeof(struct rpc_reply_read));
if (error)
{
goto errout_with_semaphore;
@@ -587,8 +588,8 @@ errout_with_semaphore:
*
****************************************************************************/
-static ssize_t
-nfs_write(FAR struct file *filep, const char *buffer, size_t buflen)
+static ssize_t nfs_write(FAR struct file *filep, const char *buffer,
+ size_t buflen)
{
struct inode *inode;
struct nfsmount *nmp;
@@ -651,7 +652,8 @@ nfs_write(FAR struct file *filep, const char *buffer, size_t buflen)
write.stable = txdr_unsigned(committed);
memcpy((void *)write.data, userbuffer, buflen);
- error = nfs_request(nmp, NFSPROC_WRITE, (FAR const void *)&write,
+ error = nfs_request(nmp, NFSPROC_WRITE,
+ (FAR const void *)&write, sizeof(struct WRITE3args),
(FAR void *)&resok, sizeof(struct rpc_reply_write));
if (error)
{
@@ -779,7 +781,7 @@ errout_with_semaphore:
* Name: nfs_readdirrpc
*
* Description:
- * The function below stuff the cookies in after the name.
+ * Perform the READIR RPC call.
*
* Returned Value:
* 0 on success; a positive errno value on failure.
@@ -793,6 +795,9 @@ int nfs_readdirrpc(struct nfsmount *nmp, struct nfsnode *np,
uint32_t buffer[64];
struct READDIR3args rddir;
struct rpc_reply_readdir *resok;
+ struct file_handle fhandle;
+ struct nfs_fattr obj_attributes;
+ struct nfs_fattr dir_attributes;
uint32_t tmp;
uint32_t *ptr; /* This goes in fs_dirent_s */
uint8_t *name;
@@ -818,7 +823,7 @@ int nfs_readdirrpc(struct nfsmount *nmp, struct nfsnode *np,
while (!more && !eod)
{
- /* Request a block directory enries */
+ /* Request a block directory entries */
nfsstats.rpccnt[NFSPROC_READDIR]++;
memset(&rddir, 0, sizeof(struct READDIR3args));
@@ -839,7 +844,8 @@ int nfs_readdirrpc(struct nfsmount *nmp, struct nfsnode *np,
memcpy(&rddir.cookieverf, &np->n_cookieverf, NFSX_V3COOKIEVERF);
}
- error = nfs_request(nmp, NFSPROC_READDIR, (FAR const void *)&rddir,
+ error = nfs_request(nmp, NFSPROC_READDIR,
+ (FAR const void *)&rddir, sizeof(struct READDIR3args),
(FAR void *)buffer, sizeof(buffer));
if (error)
{
@@ -939,13 +945,6 @@ int nfs_readdirrpc(struct nfsmount *nmp, struct nfsnode *np,
ptr++; /* Just skip over the nextentry for now */
- /* Return the directory entry to the caller. On subsequent calls to
- * readdir(), we will return the next entry. And so on until all of
- * the entries have been returned. Then read the next next block
- * of entries until EOF is reported.
- */
-#warning "Not implemented"
-
/* Return the name of the node to the caller */
if (length > NAME_MAX)
@@ -959,50 +958,46 @@ int nfs_readdirrpc(struct nfsmount *nmp, struct nfsnode *np,
/* Get the file attributes associated with this name and return
* the file type.
*/
-#if 0 /* There is no point in enabling until nfs_getfsinfo handles the relative path */
- if ((nmp->nm_flag & (NFSMNT_NFSV3 | NFSMNT_GOTFSINFO)) == NFSMNT_NFSV3)
+
+ fhandle.length = txdr_unsigned(np->n_fhsize);
+ memcpy(&fhandle.handle, &np->n_fhp, sizeof(nfsfh_t));
+
+ error = nfs_lookup(nmp, dir->fd_dir.d_name, &fhandle,
+ &obj_attributes, &dir_attributes);
+ if (error != 0)
{
- struct stat buf;
- char *path;
+ fdbg("nfs_lookup failed: %d\n", error);
+ return error;
+ }
- /* Construct the full path to the file */
+ /* Set the dirent file type */
- asprintf(&path, "%s/%s", relpath, dir->fd_dir.d_name);
- if (path)
- {
- /* Then stat the file */
-
- int ret = nfs_getstat(nmp, path, &buf);
- if (ret == OK)
- {
- if (S_ISREG(buf.st_mode))
- {
- dir->fd_dir.d_type = DTYPE_FILE;
- }
- else if (S_ISDIR(buf.st_mode))
- {
- dir->fd_dir.d_type = DTYPE_FILE;
- }
- else if (S_ISCHR(buf.st_mode) || S_ISFIFO(buf.st_mode))
- {
- dir->fd_dir.d_type = DTYPE_FILE;
- }
- else if (S_ISBLK(buf.st_mode))
- {
- dir->fd_dir.d_type = DTYPE_FILE;
- }
- else
- {
-#warning "Other types should be ignored ... go to the next entry"
- }
- }
-
- /* Free the allocated string */
-
- kfree(path);
- }
+ switch (obj_attributes.fa_type)
+ {
+ default:
+ case NFNON: /* Unknown type */
+ case NFSOCK: /* Socket */
+ case NFLNK: /* Symbolic link */
+ break;
+
+ case NFREG: /* Regular file */
+ dir->fd_dir.d_type = DTYPE_FILE;
+ break;
+
+ case NFDIR: /* Directory */
+ dir->fd_dir.d_type = DTYPE_DIRECTORY;
+ break;
+
+ case NFBLK: /* Block special device file */
+ dir->fd_dir.d_type = DTYPE_BLK;
+ break;
+
+ case NFFIFO: /* Named FIFO */
+ case NFCHR: /* Character special device file */
+ dir->fd_dir.d_type = DTYPE_CHR;
+ break;
}
-#endif
+
error = 0;
}
@@ -1445,7 +1440,8 @@ int mountnfs(struct nfs_args *argp, void **handle)
getattr.fsroot.length = txdr_unsigned(nmp->nm_fhsize);
memcpy(&getattr.fsroot.handle, &nmp->nm_fh, sizeof(nfsfh_t));
- error = nfs_request(nmp, NFSPROC_GETATTR, (FAR const void *)&getattr,
+ error = nfs_request(nmp, NFSPROC_GETATTR,
+ (FAR const void *)&getattr, sizeof(struct FS3args),
(FAR void*)&resok, sizeof(struct rpc_reply_getattr));
if (error)
{
@@ -1635,7 +1631,8 @@ static int nfs_statfs(struct inode *mountpt, struct statfs *sbp)
fsstat.fsroot.length = txdr_unsigned(nmp->nm_fhsize);
fsstat.fsroot.handle = nmp->nm_fh;
- error = nfs_request(nmp, NFSPROC_FSSTAT, (FAR const void *)&fsstat,
+ error = nfs_request(nmp, NFSPROC_FSSTAT,
+ (FAR const void *)&fsstat, sizeof(struct FS3args),
(FAR void *) &sfp, sizeof(struct rpc_reply_fsstat));
if (error)
{
@@ -1718,7 +1715,8 @@ static int nfs_remove(struct inode *mountpt, const char *relpath)
remove.object.length = txdr_unsigned(64);
strncpy(remove.object.name, relpath, 64);
- error = nfs_request(nmp, NFSPROC_REMOVE, (FAR const void *)&remove,
+ error = nfs_request(nmp, NFSPROC_REMOVE,
+ (FAR const void *)&remove, sizeof(struct REMOVE3args),
(FAR void*)&resok, sizeof(struct rpc_reply_remove));
/* Kludge City: If the first reply to the remove rpc is lost..
@@ -1807,7 +1805,8 @@ static int nfs_mkdir(struct inode *mountpt, const char *relpath, mode_t mode)
memcpy(&mkir.attributes, &sp, sizeof(struct nfsv3_sattr));
- error = nfs_request(nmp, NFSPROC_MKDIR, (FAR const void *)&mkir,
+ error = nfs_request(nmp, NFSPROC_MKDIR,
+ (FAR const void *)&mkir, sizeof(struct MKDIR3args),
(FAR void *)&resok, sizeof(struct rpc_reply_mkdir));
if (error)
{
@@ -1882,7 +1881,8 @@ static int nfs_rmdir(struct inode *mountpt, const char *relpath)
rmdir.object.length = txdr_unsigned(64);
strncpy(rmdir.object.name, relpath, 64);
- error = nfs_request(nmp, NFSPROC_RMDIR, (FAR const void *)&rmdir,
+ error = nfs_request(nmp, NFSPROC_RMDIR,
+ (FAR const void *)&rmdir, sizeof(struct RMDIR3args),
(FAR void *)&resok, sizeof(struct rpc_reply_rmdir));
if (error == ENOENT)
{
@@ -1962,7 +1962,8 @@ static int nfs_rename(struct inode *mountpt, const char *oldrelpath,
rename.to.length = txdr_unsigned(64);
strncpy(rename.to.name, newrelpath, 64);
- error = nfs_request(nmp, NFSPROC_RENAME, (FAR const void *)&rename,
+ error = nfs_request(nmp, NFSPROC_RENAME,
+ (FAR const void *)&rename, sizeof(struct RENAME3args),
(FAR void *)&resok, sizeof(struct rpc_reply_rename));
/* ENOENT => 0 assuming that it is a reply to a retry. */
diff --git a/nuttx/fs/nfs/rpc.h b/nuttx/fs/nfs/rpc.h
index 4199797a1..b03d73546 100644
--- a/nuttx/fs/nfs/rpc.h
+++ b/nuttx/fs/nfs/rpc.h
@@ -331,6 +331,7 @@ struct rpc_call_lookup
struct rpc_call_header ch;
struct LOOKUP3args lookup;
};
+#define SIZEOF_rpc_call_lookup(n) (sizeof(struct rpc_call_header) + SIZEOF_LOOKUP3args(n))
struct rpc_call_read
{
@@ -410,6 +411,13 @@ struct rpc_reply_create
struct CREATE3resok create;
};
+struct rpc_reply_lookup
+{
+ struct rpc_reply_header rh;
+ uint32_t status;
+ struct LOOKUP3resok lookup;
+};
+
struct rpc_reply_write
{
struct rpc_reply_header rh;
@@ -555,17 +563,14 @@ struct rpcclnt
****************************************************************************/
void rpcclnt_init(void);
-int rpcclnt_connect(struct rpcclnt *);
-int rpcclnt_reconnect(struct rpctask *);
-void rpcclnt_disconnect(struct rpcclnt *);
-int rpcclnt_umount(struct rpcclnt *);
-void rpcclnt_safedisconnect(struct rpcclnt *);
-int rpcclnt_request(FAR struct rpcclnt *, int, int, int, void *,
- FAR const void *, size_t);
-int rpcclnt_lookup(FAR struct rpcclnt *rpc, FAR const char *relpath,
- FAR struct file_handle *fhandle,
- FAR struct nfs_fattr *obj_attributes,
- FAR struct nfs_fattr *dir_attributes);
+int rpcclnt_connect(struct rpcclnt *rpc);
+int rpcclnt_reconnect(struct rpctask *rep);
+void rpcclnt_disconnect(struct rpcclnt *rpc);
+int rpcclnt_umount(struct rpcclnt *rpc);
+void rpcclnt_safedisconnect(struct rpcclnt *rpc);
+int rpcclnt_request(FAR struct rpcclnt *rpc, int procnum, int prog, int version,
+ FAR const void *request, size_t reqlen,
+ FAR void *response, size_t resplen);
#undef COMP
#ifdef COMP
diff --git a/nuttx/fs/nfs/rpc_clnt.c b/nuttx/fs/nfs/rpc_clnt.c
index dba71a411..cdf16f56c 100644
--- a/nuttx/fs/nfs/rpc_clnt.c
+++ b/nuttx/fs/nfs/rpc_clnt.c
@@ -200,25 +200,33 @@ static dq_queue_t rpctask_q;
* Private Function Prototypes
****************************************************************************/
-static int rpcclnt_send(struct socket *, struct sockaddr *, int, int, void *,
- struct rpctask *);
-static int rpcclnt_receive(struct rpctask *, struct sockaddr *, int, int,
- void *, size_t);//, struct rpc_call *);
-static int rpcclnt_reply(struct rpctask *, int, int, void *, size_t);
+static int rpcclnt_send(struct socket *so, struct sockaddr *nam,
+ int procid, int prog, void *call, int reqlen,
+ struct rpctask *rep);
+static int rpcclnt_receive(struct rpctask *rep, struct sockaddr *aname,
+ int proc, int program, void *reply, size_t resplen);
+ //, struct rpc_call *);
+static int rpcclnt_reply(struct rpctask *myrep, int procid, int prog,
+ void *reply, size_t resplen);
#ifdef CONFIG_NFS_TCPIP
-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 *);
+static int rpcclnt_sndlock(int *flagp, struct rpctask *task);
+static void rpcclnt_sndunlock(int *flagp);
+static int rpcclnt_rcvlock(struct rpctask *task);
+static void rpcclnt_rcvunlock(int *flagp);
+static int rpcclnt_sigintr(struct rpcclnt *rpc, struct rpctask *task,
+ cthread_t *td);
#endif
#ifdef COMP
static void rpcclnt_softterm(struct rpctask *task);
-static void rpcclnt_timer(void *, struct rpc_call *);
+void rpcclnt_timer(void *arg, struct rpc_call *call);
#endif
-static uint32_t rpcclnt_proct(struct rpcclnt *, uint32_t);
-static int rpcclnt_buildheader(struct rpcclnt *, int, int, int, struct xidr *, FAR const void *,
- void *);
+static uint32_t rpcclnt_proct(struct rpcclnt *rpc, uint32_t procid);
+static uint32_t rpcclnt_newxid(void);
+static void rpcclnt_fmtheader(FAR struct rpc_call_header *ch,
+ uint32_t xid, int procid, int prog, int vers);
+static int rpcclnt_buildheader(struct rpcclnt *rpc, int procid, int prog, int vers,
+ struct xidr *value, FAR const void *request,
+ size_t *reqlen, FAR void *msgbuf);
/****************************************************************************
* Private Functions
@@ -234,18 +242,17 @@ static int rpcclnt_buildheader(struct rpcclnt *, int, int, int, struct xidr *, F
* (TCP...) - do any cleanup required by recoverable socket errors (???)
*/
-static int
-rpcclnt_send(struct socket *so, struct sockaddr *nam, int procid, int prog,
- void *call, struct rpctask *rep)
+static int rpcclnt_send(struct socket *so, struct sockaddr *nam,
+ int procid, int prog, void *call, int reqlen,
+ struct rpctask *rep)
{
struct sockaddr *sendnam;
ssize_t nbytes;
- int error = ESRCH;
#ifdef CONFIG_NFS_TCPIP
int soflags;
#endif
- int length;
int flags;
+ int error = OK;
if (rep != NULL)
{
@@ -257,7 +264,7 @@ rpcclnt_send(struct socket *so, struct sockaddr *nam, int procid, int prog,
if ((so = rep->r_rpcclnt->rc_so) == NULL)
{
rep->r_flags |= TASK_MUSTRESEND;
- return 0;
+ return OK;
}
rep->r_flags &= ~TASK_MUSTRESEND;
@@ -290,123 +297,37 @@ rpcclnt_send(struct socket *so, struct sockaddr *nam, int procid, int prog,
flags = 0;
}
- /* Get the length of the call messsage */
-
- error = 0;
- if (prog == PMAPPROG)
- {
- if (procid == PMAPPROC_GETPORT || procid == PMAPPROC_UNSET)
- {
- length = sizeof(struct rpc_call_pmap);
- }
- else
- {
- error = EINVAL;
- }
- }
- else if (prog == RPCPROG_MNT)
- {
- if (procid == RPCMNT_UMOUNT || procid == RPCMNT_MOUNT)
- {
- length = sizeof(struct rpc_call_mount);
- }
- else
- {
- error = EINVAL;
- }
- }
- else if (prog == NFS_PROG)
- {
- switch (procid)
- {
- case NFSPROC_CREATE:
- length = sizeof(struct rpc_call_create);
- break;
-
- case NFSPROC_READ:
- length = sizeof(struct rpc_call_read);
- break;
-
- case NFSPROC_WRITE:
- length = sizeof(struct rpc_call_write);
- break;
-
- case NFSPROC_READDIR:
- length = sizeof(struct rpc_call_readdir);
- break;
-
- case NFSPROC_FSSTAT:
- length = sizeof(struct rpc_call_fs);
- break;
-
- case NFSPROC_GETATTR:
- length = sizeof(struct rpc_call_fs);
- break;
-
- case NFSPROC_REMOVE:
- length = sizeof(struct rpc_call_remove);
- break;
-
- case NFSPROC_MKDIR:
- length = sizeof(struct rpc_call_mkdir);
- break;
-
- case NFSPROC_RMDIR:
- length = sizeof(struct rpc_call_rmdir);
- break;
-
- case NFSPROC_RENAME:
- length = sizeof(struct rpc_call_rename);
- break;
-
- case NFSPROC_FSINFO:
- length = sizeof(struct rpc_call_fs);
- break;
-
- default:
- error = EINVAL;
- break;
- }
- }
- else
- {
- error = EINVAL;
- }
-
/* Send the call message */
- if (error == 0)
+ /* On success, psock_sendto returns the number of bytes sent;
+ * On failure, it returns -1 with the specific error in errno.
+ */
+
+ nbytes = psock_sendto(so, call, reqlen, flags,
+ sendnam, sizeof(struct sockaddr));
+ if (nbytes < 0)
{
- /* On success, psock_sendto returns the number of bytes sent;
- * On failure, it returns -1 with the specific error in errno.
+ /* psock_sendto failed, Sample the error value (subsequent
+ * calls can change the errno value!
*/
- nbytes = psock_sendto(so, call, length, flags,
- sendnam, sizeof(struct sockaddr));
- if (nbytes < 0)
+ error = errno;
+ fdbg("ERROR: psock_sendto failed: %d\n", error);
+
+ if (rep != NULL)
{
- /* psock_sendto failed, Sample the error value (subsequent
- * calls can change the errno value!
- */
+ fdbg("rpc send error %d for service %s\n", error,
+ rep->r_rpcclnt->rc_prog->prog_name);
- error = errno;
- fdbg("ERROR: psock_sendto failed: %d\n", error);
+ /* Deal with errors for the client side. */
- if (rep != NULL)
+ if (rep->r_flags & TASK_SOFTTERM)
{
- fdbg("rpc send error %d for service %s\n", error,
- rep->r_rpcclnt->rc_prog->prog_name);
-
- /* Deal with errors for the client side. */
-
- if (rep->r_flags & TASK_SOFTTERM)
- {
- error = EINTR;
- }
- else
- {
- rep->r_flags |= TASK_MUSTRESEND;
- }
+ error = EINTR;
+ }
+ else
+ {
+ rep->r_flags |= TASK_MUSTRESEND;
}
}
}
@@ -422,13 +343,13 @@ rpcclnt_send(struct socket *so, struct sockaddr *nam, int procid, int prog,
*/
static int rpcclnt_receive(struct rpctask *rep, struct sockaddr *aname,
- int proc, int program, void *reply, size_t len)
+ int proc, int program, void *reply, size_t resplen)
//, struct rpc_call *call)
{
struct socket *so;
ssize_t nbytes;
#ifdef CONFIG_NFS_TCPIP
- uint32_t len;
+ uint32_t resplen;
int sotype;
#endif
int error = 0;
@@ -485,7 +406,7 @@ static int rpcclnt_receive(struct rpctask *rep, struct sockaddr *aname,
while (rep->r_flags & TASK_MUSTRESEND)
{
rpcstats.rpcretries++;
- error = rpcclnt_send(so, rep->r_rpcclnt->rc_name, call, rep);
+ error = rpcclnt_send(so, rep->r_rpcclnt->rc_name, call, reqlen, rep);
if (error)
{
if (error == EINTR || error == ERESTART ||
@@ -506,7 +427,7 @@ static int rpcclnt_receive(struct rpctask *rep, struct sockaddr *aname,
do
{
socklen_t fromlen = sizeof(*rep->r_rpcclnt->rc_name)
- nbytes = psock_recvfrom(so, reply, len,
+ nbytes = psock_recvfrom(so, reply, resplen,
MSG_WAITALL, rep->r_rpcclnt->rc_name,
&fromlen);
if (nbytes < 0)
@@ -527,12 +448,12 @@ static int rpcclnt_receive(struct rpctask *rep, struct sockaddr *aname,
{
error = errval;
}
- else if (nbytes < len)
+ else if (nbytes < resplen)
{
fdbg("ERROR: Short receive from rpc server %s\n",
rep->r_rpcclnt->rc_prog->prog_name);
fvdbg(" Expected %d bytes, received %d bytes\n",
- len, nbytes);
+ resplen, nbytes);
error = EPIPE;
}
else
@@ -540,19 +461,19 @@ static int rpcclnt_receive(struct rpctask *rep, struct sockaddr *aname,
error = 0;
}
-#warning "What is len? This logic is not right!"
- len = ntohl(len) & ~0x80000000;
+#warning "What is resplen? This logic is not right!"
+ resplen = ntohl(resplen) & ~0x80000000;
/* This is SERIOUS! We are out of sync with the
* sender and forcing a disconnect/reconnect is all I
* can do.
*/
- else if (len > RPC_MAXPACKET)
+ else if (resplen > RPC_MAXPACKET)
{
fdbg("ERROR %s (%d) from rpc server %s\n",
"impossible packet length",
- len, rep->r_rpcclnt->rc_prog->prog_name);
+ resplen, rep->r_rpcclnt->rc_prog->prog_name);
error = EFBIG;
goto errout;
}
@@ -577,12 +498,12 @@ static int rpcclnt_receive(struct rpctask *rep, struct sockaddr *aname,
error = errval;
goto errout;
}
- else if (nbytes < len)
+ else if (nbytes < resplen)
{
fdbg("ERROR: Short receive from rpc server %s\n",
rep->r_rpcclnt->rc_prog->prog_name);
fvdbg(" Expected %d bytes, received %d bytes\n",
- len, nbytes);
+ resplen, nbytes);
error = EPIPE;
}
else
@@ -626,12 +547,12 @@ static int rpcclnt_receive(struct rpctask *rep, struct sockaddr *aname,
error = errval;
goto errout;
}
- else if (nbytes < len)
+ else if (nbytes < resplen)
{
fdbg("ERROR: Short receive from rpc server %s\n",
rep->r_rpcclnt->rc_prog->prog_name);
fvdbg(" Expected %d bytes, received %d bytes\n",
- len, nbytes);
+ resplen, nbytes);
error = EPIPE;
}
else
@@ -671,7 +592,7 @@ static int rpcclnt_receive(struct rpctask *rep, struct sockaddr *aname,
}
socklen_t fromlen = sizeof(struct sockaddr);
- nbytes = psock_recvfrom(so, reply, len, 0, aname, &fromlen);
+ nbytes = psock_recvfrom(so, reply, resplen, 0, aname, &fromlen);
if (nbytes < 0)
{
errval = errno;
@@ -690,7 +611,7 @@ static int rpcclnt_receive(struct rpctask *rep, struct sockaddr *aname,
*/
static int rpcclnt_reply(struct rpctask *myrep, int procid, int prog,
- void *reply, size_t len)
+ void *reply, size_t resplen)
{
struct rpctask *rep;
struct rpc_reply_header replyheader;
@@ -719,7 +640,7 @@ static int rpcclnt_reply(struct rpctask *myrep, int procid, int prog,
#endif
/* Get the next Rpc reply off the socket */
- error = rpcclnt_receive(myrep, rpc->rc_name, procid, prog, reply, len);
+ error = rpcclnt_receive(myrep, rpc->rc_name, procid, prog, reply, resplen);
#ifdef CONFIG_NFS_TCPIP
rpcclnt_rcvunlock(&rpc->rc_flag);
#endif
@@ -842,8 +763,8 @@ static int rpcclnt_reply(struct rpctask *myrep, int procid, int prog,
}
#ifdef CONFIG_NFS_TCPIP
-static int
-rpcclnt_sigintr( struct rpcclnt *rpc, struct rpctask *task, cthread_t *td)
+static int rpcclnt_sigintr(struct rpcclnt *rpc, struct rpctask *task,
+ cthread_t *td)
{
struct proc *p;
sigset_t tmpset;
@@ -1017,6 +938,403 @@ static void rpcclnt_softterm(struct rpctask *task)
}
#endif
+/* Get a new (non-zero) xid */
+
+static uint32_t rpcclnt_newxid(void)
+{
+ static uint32_t rpcclnt_xid = 0;
+ static uint32_t rpcclnt_xid_touched = 0;
+ int xidp = 0;
+
+ srand(time(NULL));
+ if ((rpcclnt_xid == 0) && (rpcclnt_xid_touched == 0))
+ {
+ rpcclnt_xid = rand();
+ rpcclnt_xid_touched = 1;
+ }
+ else
+ {
+ do
+ {
+ xidp = rand();
+ }
+ while ((xidp % 256) == 0);
+
+ rpcclnt_xid += xidp;
+ }
+
+ return rpcclnt_xid;
+}
+
+/* Format the common part of the call header */
+
+static void rpcclnt_fmtheader(FAR struct rpc_call_header *ch,
+ uint32_t xid, int prog, int vers, int procid)
+{
+ /* Format the call header */
+
+ ch->rp_xid = txdr_unsigned(xid);
+ ch->rp_direction = rpc_call;
+ ch->rp_rpcvers = rpc_vers;
+ ch->rp_prog = txdr_unsigned(prog);
+ ch->rp_vers = txdr_unsigned(vers);
+ ch->rp_proc = txdr_unsigned(procid);
+
+ /* rpc_auth part (auth_unix as root) */
+
+ ch->rpc_auth.authtype = rpc_auth_null;
+//call->rpc_auth.authlen = 0;
+#ifdef CONFIG_NFS_UNIX_AUTH
+ ch->rpc_unix.stamp = txdr_unsigned(1);
+ ch->rpc_unix.hostname = 0;
+ ch->rpc_unix.uid = setuid;
+ ch->rpc_unix.gid = setgid;
+ ch->rpc_unix.gidlist = 0;
+#endif
+ /* rpc_verf part (auth_null) */
+
+ ch->rpc_verf.authtype = rpc_auth_null;
+//call->rpc_verf.authlen = 0;
+}
+
+/* Build the RPC header and fill in the authorization info. */
+
+static int rpcclnt_buildheader(struct rpcclnt *rpc, int procid, int prog, int vers,
+ struct xidr *value, FAR const void *request,
+ size_t *reqlen, FAR void *msgbuf)
+{
+ uint32_t xid;
+
+ /* The RPC header.*/
+
+ /* Get a new (non-zero) xid */
+
+ xid = rpcclnt_newxid();
+
+ /* Perform the binding depending on the protocol type */
+
+ if (prog == PMAPPROG)
+ {
+ if (procid == PMAPPROC_GETPORT)
+ {
+ /* Copy the variable, caller-provided data into the call message structure */
+
+ struct rpc_call_pmap *callmsg = (struct rpc_call_pmap *)msgbuf;
+ memcpy(&callmsg->pmap, request, *reqlen);
+
+ /* Return the full size of the message (including messages headers) */
+
+ DEBUGASSERT(*reqlen == sizeof(struct call_args_pmap));
+ *reqlen = sizeof(struct rpc_call_pmap);
+
+ /* Format the message header */
+
+ rpcclnt_fmtheader(&callmsg->ch, xid, prog, vers, procid);
+ value->xid = callmsg->ch.rp_xid;
+ return 0;
+ }
+ else if (procid == PMAPPROC_UNSET)
+ {
+ /* Copy the variable, caller-provided data into the call message structure */
+
+ struct rpc_call_pmap *callmsg = (struct rpc_call_pmap *)msgbuf;;
+ memcpy(&callmsg->pmap, request, *reqlen);
+
+ /* Return the full size of the message (including messages headers) */
+
+ DEBUGASSERT(*reqlen == sizeof(struct call_args_pmap));
+ *reqlen = sizeof(struct rpc_call_pmap);
+
+ /* Format the message header */
+
+ rpcclnt_fmtheader(&callmsg->ch, xid, prog, vers, procid);
+ value->xid = callmsg->ch.rp_xid;
+ return 0;
+ }
+ }
+ else if (prog == RPCPROG_MNT)
+ {
+ if (procid == RPCMNT_UMOUNT)
+ {
+ /* Copy the variable, caller-provided data into the call message structure */
+
+ struct rpc_call_mount *callmsg = (struct rpc_call_mount *)msgbuf;
+ memcpy(&callmsg->mount, request, *reqlen);
+
+ /* Return the full size of the message (including messages headers) */
+
+ DEBUGASSERT(*reqlen == sizeof(struct call_args_mount));
+ *reqlen = sizeof(struct rpc_call_mount);
+
+ /* Format the message header */
+
+ rpcclnt_fmtheader(&callmsg->ch, xid, prog, vers, procid);
+ value->xid = callmsg->ch.rp_xid;
+ return 0;
+ }
+ else if (procid == RPCMNT_MOUNT)
+ {
+ /* Copy the variable, caller-provided data into the call message structure */
+
+ struct rpc_call_mount *callmsg = (struct rpc_call_mount *)msgbuf;
+ memcpy(&callmsg->mount, request, *reqlen);
+
+ /* Return the full size of the message (including messages headers) */
+
+ DEBUGASSERT(*reqlen == sizeof(struct call_args_mount));
+ *reqlen = sizeof(struct rpc_call_mount);
+
+ /* Format the message header */
+
+ rpcclnt_fmtheader(&callmsg->ch, xid, prog, vers, procid);
+ value->xid = callmsg->ch.rp_xid;
+ return 0;
+ }
+ }
+ else if (prog == NFS_PROG)
+ {
+ switch (procid)
+ {
+ case NFSPROC_CREATE:
+ {
+ /* Copy the variable, caller-provided data into the call message structure */
+
+ struct rpc_call_create *callmsg = (struct rpc_call_create *)msgbuf;
+ memcpy(&callmsg->create, request, *reqlen);
+
+ /* Return the full size of the message (including messages headers) */
+
+ DEBUGASSERT(*reqlen == sizeof(struct CREATE3args));
+ *reqlen = sizeof(struct rpc_call_create);
+
+ /* Format the message header */
+
+ rpcclnt_fmtheader(&callmsg->ch, xid, prog, vers, procid);
+ value->xid = callmsg->ch.rp_xid;
+ return 0;
+ }
+
+ case NFSPROC_LOOKUP:
+ {
+ struct rpc_call_lookup *callmsg = (struct rpc_call_lookup *)msgbuf;
+ uint32_t namelen;
+
+ /* Copy the variable, caller-provided data into the call message structure */
+
+ memcpy(&callmsg->lookup, request, *reqlen);
+
+ /* Return the full size of the message (including messages headers) */
+
+ namelen = fxdr_unsigned(uint32_t, ((FAR struct LOOKUP3args*)request)->namelen);
+ DEBUGASSERT(*reqlen <= SIZEOF_LOOKUP3args(namelen));
+ *reqlen = SIZEOF_rpc_call_lookup(namelen);
+
+ /* Format the message header */
+
+ rpcclnt_fmtheader(&callmsg->ch, xid, prog, vers, procid);
+ value->xid = callmsg->ch.rp_xid;
+ return 0;
+ }
+
+ case NFSPROC_READ:
+ {
+ /* Copy the variable, caller-provided data into the call message structure */
+
+ struct rpc_call_read *callmsg = (struct rpc_call_read *)msgbuf;
+ memcpy(&callmsg->read, request, *reqlen);
+
+ /* Return the full size of the message (including messages headers) */
+
+ DEBUGASSERT(*reqlen == sizeof(struct READ3args));
+ *reqlen = sizeof(struct rpc_call_read);
+
+ /* Format the message header */
+
+ rpcclnt_fmtheader(&callmsg->ch, xid, prog, vers, procid);
+ value->xid = callmsg->ch.rp_xid;
+ return 0;
+ }
+
+ case NFSPROC_WRITE:
+ {
+ /* Copy the variable, caller-provided data into the call message structure */
+
+ struct rpc_call_write *callmsg = (struct rpc_call_write *)msgbuf;
+ memcpy(&callmsg->write, request, *reqlen);
+
+ /* Return the full size of the message (including messages headers) */
+
+ DEBUGASSERT(*reqlen == sizeof(struct WRITE3args));
+ *reqlen = sizeof(struct rpc_call_write);
+
+ /* Format the message header */
+
+ rpcclnt_fmtheader(&callmsg->ch, xid, prog, vers, procid);
+ value->xid = callmsg->ch.rp_xid;
+ return 0;
+ }
+
+ case NFSPROC_READDIR:
+ {
+ /* Copy the variable, caller-provided data into the call message structure */
+
+ struct rpc_call_readdir *callmsg = (struct rpc_call_readdir *)msgbuf;
+ memcpy(&callmsg->readdir, request, *reqlen);
+
+ /* Return the full size of the message (including messages headers) */
+
+ DEBUGASSERT(*reqlen == sizeof(struct READDIR3args));
+ *reqlen = sizeof(struct rpc_call_readdir);
+
+ /* Format the message header */
+
+ rpcclnt_fmtheader(&callmsg->ch, xid, prog, vers, procid);
+ value->xid = callmsg->ch.rp_xid;
+ return 0;
+ }
+
+ case NFSPROC_FSSTAT:
+ {
+ /* Copy the variable, caller-provided data into the call message structure */
+
+ struct rpc_call_fs *callmsg = (struct rpc_call_fs *)msgbuf;
+ memcpy(&callmsg->fs, request, *reqlen);
+
+ /* Return the full size of the message (including messages headers) */
+
+ DEBUGASSERT(*reqlen == sizeof(struct FS3args));
+ *reqlen = sizeof(struct rpc_call_fs);
+
+ /* Format the message header */
+
+ rpcclnt_fmtheader(&callmsg->ch, xid, prog, vers, procid);
+ value->xid = callmsg->ch.rp_xid;
+ return 0;
+ }
+
+ case NFSPROC_REMOVE:
+ {
+ /* Copy the variable, caller-provided data into the call message structure */
+
+ struct rpc_call_remove *callmsg = (struct rpc_call_remove *)msgbuf;
+ memcpy(&callmsg->remove, request, *reqlen);
+
+ /* Return the full size of the message (including messages headers) */
+
+ DEBUGASSERT(*reqlen == sizeof(struct REMOVE3args));
+ *reqlen = sizeof(struct rpc_call_remove);
+
+ /* Format the message header */
+
+ rpcclnt_fmtheader(&callmsg->ch, xid, prog, vers, procid);
+ value->xid = callmsg->ch.rp_xid;
+ return 0;
+ }
+
+ case NFSPROC_GETATTR:
+ {
+ /* Copy the variable, caller-provided data into the call message structure */
+
+ struct rpc_call_fs *callmsg = (struct rpc_call_fs *)msgbuf;
+ memcpy(&callmsg->fs, request, *reqlen);
+
+ /* Return the full size of the message (including messages headers) */
+
+ DEBUGASSERT(*reqlen == sizeof(struct FS3args));
+ *reqlen = sizeof(struct rpc_call_fs);
+
+ /* Format the message header */
+
+ rpcclnt_fmtheader(&callmsg->ch, xid, prog, vers, procid);
+ value->xid = callmsg->ch.rp_xid;
+ return 0;
+ }
+
+ case NFSPROC_MKDIR:
+ {
+ /* Copy the variable, caller-provided data into the call message structure */
+
+ struct rpc_call_mkdir *callmsg = (struct rpc_call_mkdir *)msgbuf;
+ memcpy(&callmsg->mkdir, request, *reqlen);
+
+ /* Return the full size of the message (including messages headers) */
+
+ DEBUGASSERT(*reqlen == sizeof(struct MKDIR3args));
+ *reqlen = sizeof(struct rpc_call_mkdir);
+
+ /* Format the message header */
+
+ rpcclnt_fmtheader(&callmsg->ch, xid, prog, vers, procid);
+ value->xid = callmsg->ch.rp_xid;
+ return 0;
+ }
+
+ case NFSPROC_RMDIR:
+ {
+ /* Copy the variable, caller-provided data into the call message structure */
+
+ struct rpc_call_rmdir *callmsg = (struct rpc_call_rmdir *)msgbuf;
+ memcpy(&callmsg->rmdir, request, *reqlen);
+
+ /* Return the full size of the message (including messages headers) */
+
+ DEBUGASSERT(*reqlen == sizeof(struct RMDIR3args));
+ *reqlen = sizeof(struct rpc_call_rmdir);
+
+ /* Format the message header */
+
+ rpcclnt_fmtheader(&callmsg->ch, xid, prog, vers, procid);
+ value->xid = callmsg->ch.rp_xid;
+ return 0;
+ }
+
+ case NFSPROC_RENAME:
+ {
+ /* Copy the variable, caller-provided data into the call message structure */
+
+ struct rpc_call_rename *callmsg = (struct rpc_call_rename *)msgbuf;
+ memcpy(&callmsg->rename, request, *reqlen);
+
+ /* Return the full size of the message (including messages headers) */
+
+ DEBUGASSERT(*reqlen == sizeof(struct RENAME3args));
+ *reqlen = sizeof(struct rpc_call_rename);
+
+ /* Format the message header */
+
+ rpcclnt_fmtheader(&callmsg->ch, xid, prog, vers, procid);
+ value->xid = callmsg->ch.rp_xid;
+ return 0;
+ }
+
+ case NFSPROC_FSINFO:
+ {
+ /* Copy the variable, caller-provided data into the call message structure */
+
+ struct rpc_call_fs *callmsg = (struct rpc_call_fs *)msgbuf;
+ memcpy(&callmsg->fs, request, *reqlen);
+
+ /* Return the full size of the message (including messages headers) */
+
+ DEBUGASSERT(*reqlen == sizeof(struct FS3args));
+ *reqlen = sizeof(struct rpc_call_fs);
+
+ /* Format the message header */
+
+ rpcclnt_fmtheader(&callmsg->ch, xid, prog, vers, procid);
+ value->xid = callmsg->ch.rp_xid;
+ return 0;
+ }
+
+ default:
+ fdbg("No support for procid %d\n", procid);
+ break;
+ }
+ }
+
+ return ESRCH;
+}
+
/****************************************************************************
* Public Functions
****************************************************************************/
@@ -1097,7 +1415,7 @@ int rpcclnt_connect(struct rpcclnt *rpc)
if (!so)
{
fdbg("ERROR: Failed to allocate socket structure\n");
- return -ENOMEM;
+ return ENOMEM;
}
error = psock_socket(saddr->sa_family, rpc->rc_sotype, rpc->rc_soproto, so);
@@ -1205,8 +1523,8 @@ int rpcclnt_connect(struct rpcclnt *rpc)
sdata.port = 0;
error = rpcclnt_request(rpc, PMAPPROC_GETPORT, PMAPPROG, PMAPVERS,
- (FAR void *)&rdata, (FAR const void *)&sdata,
- sizeof(struct rpc_reply_pmap));
+ (FAR const void *)&sdata, sizeof(struct call_args_pmap),
+ (FAR void *)&rdata, sizeof(struct rpc_reply_pmap));
if (error != 0)
{
fdbg("ERROR: rpcclnt_request failed: %d\n", error);
@@ -1232,8 +1550,8 @@ int rpcclnt_connect(struct rpcclnt *rpc)
mountd.len = txdr_unsigned(sizeof(mountd.rpath));
error = rpcclnt_request(rpc, RPCMNT_MOUNT, RPCPROG_MNT, RPCMNT_VER1,
- (FAR void *)&mdata, (FAR const void *)&mountd,
- sizeof(struct rpc_reply_mount));
+ (FAR const void *)&mountd, sizeof(struct call_args_mount),
+ (FAR void *)&mdata, sizeof(struct rpc_reply_mount));
if (error != 0)
{
fdbg("ERROR: rpcclnt_request failed: %d\n", error);
@@ -1271,8 +1589,8 @@ int rpcclnt_connect(struct rpcclnt *rpc)
sdata.port = 0;
error = rpcclnt_request(rpc, PMAPPROC_GETPORT, PMAPPROG, PMAPVERS,
- (FAR void *)&rdata, (FAR const void *)&sdata,
- sizeof(struct rpc_reply_pmap));
+ (FAR const void *)&sdata, sizeof(struct call_args_pmap),
+ (FAR void *)&rdata, sizeof(struct rpc_reply_pmap));
if (error != 0)
{
fdbg("ERROR: rpcclnt_request failed: %d\n", error);
@@ -1388,10 +1706,11 @@ int rpcclnt_umount(struct rpcclnt *rpc)
sdata.port = 0;
error = rpcclnt_request(rpc, PMAPPROC_GETPORT, PMAPPROG, PMAPVERS,
- (void *)&rdata, (FAR const void *)&sdata,
- sizeof(struct rpc_reply_pmap));
+ (FAR const void *)&sdata, sizeof(struct call_args_pmap),
+ (FAR void *)&rdata, sizeof(struct rpc_reply_pmap));
if (error != 0)
{
+ fdbg("ERROR: rpcclnt_request failed: %d\n", error);
goto bad;
}
@@ -1413,10 +1732,11 @@ int rpcclnt_umount(struct rpcclnt *rpc)
mountd.len = txdr_unsigned(sizeof(mountd.rpath));
error = rpcclnt_request(rpc, RPCMNT_UMOUNT, RPCPROG_MNT, RPCMNT_VER1,
- (void *)&mdata, (FAR const void *)&mountd,
- sizeof(struct rpc_reply_mount));
+ (FAR const void *)&mountd, sizeof(struct call_args_mount),
+ (FAR void *)&mdata, sizeof(struct rpc_reply_mount));
if (error != 0)
{
+ fdbg("ERROR: rpcclnt_request failed: %d\n", error);
goto bad;
}
@@ -1451,13 +1771,15 @@ void rpcclnt_safedisconnect(struct rpcclnt *rpc)
* nfs_receive() to get reply - fills in reply (which should be initialized
* prior to calling), which is valid when 0.
*
- * note that reply->result_* are invalid unless reply->type ==
+ * 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, int prog, int version,
- void *dataout, FAR const void *datain, size_t len)
+int rpcclnt_request(FAR struct rpcclnt *rpc, int procnum, int prog,
+ int version,
+ FAR const void *request, size_t reqlen,
+ FAR void *response, size_t resplen)
{
struct rpc_reply_header replymgs;
struct rpc_reply_header replyheader;
@@ -1472,6 +1794,7 @@ int rpcclnt_request(struct rpcclnt *rpc, int procnum, int prog, int version,
struct rpc_call_pmap pmap;
struct rpc_call_mount mountd;
struct rpc_call_create create;
+ struct rpc_call_lookup lookup;
struct rpc_call_write write;
struct rpc_call_read read;
struct rpc_call_remove removef;
@@ -1495,7 +1818,8 @@ int rpcclnt_request(struct rpcclnt *rpc, int procnum, int prog, int version,
return -ENOMEM;
}
- error = rpcclnt_buildheader(rpc, procnum, prog, version, &value, datain, (FAR void*)&u);
+ error = rpcclnt_buildheader(rpc, procnum, prog, version, &value,
+ request, &reqlen, (FAR void*)&u);
if (error)
{
fdbg("ERROR: Building call header error\n");
@@ -1554,7 +1878,7 @@ int rpcclnt_request(struct rpcclnt *rpc, int procnum, int prog, int version,
if (error == 0)
{
error = rpcclnt_send(rpc->rc_so, rpc->rc_name, procnum, prog,
- (FAR void*)&u, task);
+ (FAR void*)&u, reqlen, task);
#ifdef CONFIG_NFS_TCPIP
if (rpc->rc_soflags & PR_CONNREQUIRED)
@@ -1579,7 +1903,7 @@ int rpcclnt_request(struct rpcclnt *rpc, int procnum, int prog, int version,
if (error == 0 || error == EPIPE)
{
- error = rpcclnt_reply(task, procnum, prog, dataout, len);
+ error = rpcclnt_reply(task, procnum, prog, response, resplen);
fvdbg("rpcclnt_reply returned: %d\n", error);
}
@@ -1603,7 +1927,7 @@ int rpcclnt_request(struct rpcclnt *rpc, int procnum, int prog, int version,
/* Break down the rpc header and check if ok */
memset(&replymgs, 0, sizeof(replymgs));
- memcpy(&replyheader, dataout, sizeof(struct rpc_reply_header));
+ memcpy(&replyheader, response, sizeof(struct rpc_reply_header));
replymgs.type = fxdr_unsigned(uint32_t, replyheader.type);
if (replymgs.type == RPC_MSGDENIED)
{
@@ -1807,548 +2131,6 @@ void rpcclnt_timer(void *arg, struct rpc_call *call)
}
#endif
-/* Get a new (non-zero) xid */
-
-uint32_t rpcclnt_newxid(void)
-{
- static uint32_t rpcclnt_xid = 0;
- static uint32_t rpcclnt_xid_touched = 0;
- int xidp = 0;
-
- srand(time(NULL));
- if ((rpcclnt_xid == 0) && (rpcclnt_xid_touched == 0))
- {
- rpcclnt_xid = rand();
- rpcclnt_xid_touched = 1;
- }
- else
- {
- do
- {
- xidp = rand();
- }
- while ((xidp % 256) == 0);
-
- rpcclnt_xid += xidp;
- }
-
- return rpcclnt_xid;
-}
-
-/* Build the RPC header and fill in the authorization info. */
-
-int rpcclnt_buildheader(struct rpcclnt *rpc, int procid, int prog, int vers,
- struct xidr *value, FAR const void *datain,
- void *dataout)
-{
- uint32_t xid;
-
- /* The RPC header.*/
-
- /* Get a new (non-zero) xid */
-
- xid = rpcclnt_newxid();
-
- /* Perform the binding depending on the protocol type */
-
- if (prog == PMAPPROG)
- {
- if (procid == PMAPPROC_GETPORT)
- {
- struct rpc_call_pmap *callmsg = (struct rpc_call_pmap *)dataout;
- memcpy(&callmsg->pmap, datain, sizeof(struct call_args_pmap));
-
- callmsg->ch.rp_xid = txdr_unsigned(xid);
- value->xid = callmsg->ch.rp_xid;
- callmsg->ch.rp_direction = rpc_call;
- callmsg->ch.rp_rpcvers = rpc_vers;
- callmsg->ch.rp_prog = txdr_unsigned(prog);
- callmsg->ch.rp_vers = txdr_unsigned(vers);
- callmsg->ch.rp_proc = txdr_unsigned(procid);
-
- /* rpc_auth part (auth_unix as root) */
-
- callmsg->ch.rpc_auth.authtype = rpc_auth_null;
- //call->rpc_auth.authlen = 0;
-#ifdef CONFIG_NFS_UNIX_AUTH
- callmsg->ch.rpc_unix.stamp = txdr_unsigned(1);
- callmsg->ch.rpc_unix.hostname = 0;
- callmsg->ch.rpc_unix.uid = setuid;
- callmsg->ch.rpc_unix.gid = setgid;
- callmsg->ch.rpc_unix.gidlist = 0;
-#endif
- /* rpc_verf part (auth_null) */
-
- callmsg->ch.rpc_verf.authtype = rpc_auth_null;
- //call->rpc_verf.authlen = 0;
- return 0;
- }
- else if (procid == PMAPPROC_UNSET)
- {
- struct rpc_call_pmap *callmsg = (struct rpc_call_pmap *)dataout;;
- memcpy(&callmsg->pmap, datain, sizeof(struct call_args_pmap));
- callmsg->ch.rp_xid = txdr_unsigned(xid);
- value->xid = callmsg->ch.rp_xid;
- callmsg->ch.rp_direction = rpc_call;
- callmsg->ch.rp_rpcvers = rpc_vers;
- callmsg->ch.rp_prog = txdr_unsigned(prog);
- callmsg->ch.rp_vers = txdr_unsigned(vers);
- callmsg->ch.rp_proc = txdr_unsigned(procid);
-
- /* rpc_auth part (auth_unix as root) */
-
- callmsg->ch.rpc_auth.authtype = rpc_auth_null;
- //call->rpc_auth.authlen = 0;
-#ifdef CONFIG_NFS_UNIX_AUTH
- callmsg->ch.rpc_unix.stamp = txdr_unsigned(1);
- callmsg->ch.rpc_unix.hostname = 0;
- callmsg->ch.rpc_unix.uid = setuid;
- callmsg->ch.rpc_unix.gid = setgid;
- callmsg->ch.rpc_unix.gidlist = 0;
-#endif
- /* rpc_verf part (auth_null) */
-
- callmsg->ch.rpc_verf.authtype = rpc_auth_null;
- //call->rpc_verf.authlen = 0;
- return 0;
- }
- }
- else if (prog == RPCPROG_MNT)
- {
- if (procid == RPCMNT_UMOUNT)
- {
- struct rpc_call_mount *callmsg = (struct rpc_call_mount *)dataout;
- memcpy(&callmsg->mount, datain, sizeof(struct call_args_mount));
- callmsg->ch.rp_xid = txdr_unsigned(xid);
- value->xid = callmsg->ch.rp_xid;
- callmsg->ch.rp_direction = rpc_call;
- callmsg->ch.rp_rpcvers = rpc_vers;
- callmsg->ch.rp_prog = txdr_unsigned(prog);
- callmsg->ch.rp_vers = txdr_unsigned(vers);
- callmsg->ch.rp_proc = txdr_unsigned(procid);
-
- /* rpc_auth part (auth_unix as root) */
-
- callmsg->ch.rpc_auth.authtype = rpc_auth_null;
- //call->rpc_auth.authlen = 0;
-#ifdef CONFIG_NFS_UNIX_AUTH
- callmsg->ch.rpc_unix.stamp = txdr_unsigned(1);
- callmsg->ch.rpc_unix.hostname = 0;
- callmsg->ch.rpc_unix.uid = setuid;
- callmsg->ch.rpc_unix.gid = setgid;
- callmsg->ch.rpc_unix.gidlist = 0;
-#endif
- /* rpc_verf part (auth_null) */
-
- callmsg->ch.rpc_verf.authtype = rpc_auth_null;
- //call->rpc_verf.authlen = 0;
- return 0;
- }
- else if (procid == RPCMNT_MOUNT)
- {
- struct rpc_call_mount *callmsg = (struct rpc_call_mount *)dataout;
- memcpy(&callmsg->mount, datain, sizeof(struct call_args_mount));
- callmsg->ch.rp_xid = txdr_unsigned(xid);
- value->xid = callmsg->ch.rp_xid;
- callmsg->ch.rp_direction = rpc_call;
- callmsg->ch.rp_rpcvers = rpc_vers;
- callmsg->ch.rp_prog = txdr_unsigned(prog);
- callmsg->ch.rp_vers = txdr_unsigned(vers);
- callmsg->ch.rp_proc = txdr_unsigned(procid);
-
- /* rpc_auth part (auth_unix as root) */
-
- callmsg->ch.rpc_auth.authtype = rpc_auth_null;
- //call->rpc_auth.authlen = 0;
-#ifdef CONFIG_NFS_UNIX_AUTH
- callmsg->ch.rpc_unix.stamp = txdr_unsigned(1);
- callmsg->ch.rpc_unix.hostname = 0;
- callmsg->ch.rpc_unix.uid = setuid;
- callmsg->ch.rpc_unix.gid = setgid;
- callmsg->ch.rpc_unix.gidlist = 0;
-#endif
- /* rpc_verf part (auth_null) */
-
- callmsg->ch.rpc_verf.authtype = rpc_auth_null;
- //call->rpc_verf.authlen = 0;
- return 0;
- }
- }
- else if (prog == NFS_PROG)
- {
- switch (procid)
- {
- case NFSPROC_CREATE:
- {
- struct rpc_call_create *callmsg = (struct rpc_call_create *)dataout;
- memcpy(&callmsg->create, datain, sizeof(struct CREATE3args));
- callmsg->ch.rp_xid = txdr_unsigned(xid);
- value->xid = callmsg->ch.rp_xid;
- callmsg->ch.rp_direction = rpc_call;
- callmsg->ch.rp_rpcvers = rpc_vers;
- callmsg->ch.rp_prog = txdr_unsigned(prog);
- callmsg->ch.rp_vers = txdr_unsigned(vers);
- callmsg->ch.rp_proc = txdr_unsigned(procid);
-
- /* rpc_auth part (auth_unix as root) */
-
- callmsg->ch.rpc_auth.authtype = rpc_auth_null;
- //call->rpc_auth.authlen = 0;
-#ifdef CONFIG_NFS_UNIX_AUTH
- callmsg->ch.rpc_unix.stamp = txdr_unsigned(1);
- callmsg->ch.rpc_unix.hostname = 0;
- callmsg->ch.rpc_unix.uid = setuid;
- callmsg->ch.rpc_unix.gid = setgid;
- callmsg->ch.rpc_unix.gidlist = 0;
-#endif
- /* rpc_verf part (auth_null) */
-
- callmsg->ch.rpc_verf.authtype = rpc_auth_null;
- //call->rpc_verf.authlen = 0;
- return 0;
- }
-
- case NFSPROC_READ:
- {
- struct rpc_call_read *callmsg = (struct rpc_call_read *)dataout;
- memcpy(&callmsg->read, datain, sizeof(struct READ3args));
- callmsg->ch.rp_xid = txdr_unsigned(xid);
- value->xid = callmsg->ch.rp_xid;
- callmsg->ch.rp_direction = rpc_call;
- callmsg->ch.rp_rpcvers = rpc_vers;
- callmsg->ch.rp_prog = txdr_unsigned(prog);
- callmsg->ch.rp_vers = txdr_unsigned(vers);
- callmsg->ch.rp_proc = txdr_unsigned(procid);
-
- /* rpc_auth part (auth_unix as root) */
-
- callmsg->ch.rpc_auth.authtype = rpc_auth_null;
- //call->rpc_auth.authlen = 0;
-
-#ifdef CONFIG_NFS_UNIX_AUTH
- callmsg->ch.rpc_unix.stamp = txdr_unsigned(1);
- callmsg->ch.rpc_unix.hostname = 0;
- callmsg->ch.rpc_unix.uid = setuid;
- callmsg->ch.rpc_unix.gid = setgid;
- callmsg->ch.rpc_unix.gidlist = 0;
-#endif
- /* rpc_verf part (auth_null) */
-
- callmsg->ch.rpc_verf.authtype = rpc_auth_null;
- //call->rpc_verf.authlen = 0;
- return 0;
- }
-
- case NFSPROC_WRITE:
- {
- struct rpc_call_write *callmsg = (struct rpc_call_write *)dataout;
- memcpy(&callmsg->write, datain, sizeof(struct WRITE3args));
- callmsg->ch.rp_xid = txdr_unsigned(xid);
- value->xid = callmsg->ch.rp_xid;
- callmsg->ch.rp_direction = rpc_call;
- callmsg->ch.rp_rpcvers = rpc_vers;
- callmsg->ch.rp_prog = txdr_unsigned(prog);
- callmsg->ch.rp_vers = txdr_unsigned(vers);
- callmsg->ch.rp_proc = txdr_unsigned(procid);
-
- /* rpc_auth part (auth_unix as root) */
-
- callmsg->ch.rpc_auth.authtype = rpc_auth_null;
- //call->rpc_auth.authlen = 0;
-
-#ifdef CONFIG_NFS_UNIX_AUTH
- callmsg->ch.rpc_unix.stamp = txdr_unsigned(1);
- callmsg->ch.rpc_unix.hostname = 0;
- callmsg->ch.rpc_unix.uid = setuid;
- callmsg->ch.rpc_unix.gid = setgid;
- callmsg->ch.rpc_unix.gidlist = 0;
-#endif
- /* rpc_verf part (auth_null) */
-
- callmsg->ch.rpc_verf.authtype = rpc_auth_null;
- //call->rpc_verf.authlen = 0;
- return 0;
- }
-
- case NFSPROC_READDIR:
- {
- struct rpc_call_readdir *callmsg = (struct rpc_call_readdir *)dataout;
- memcpy(&callmsg->readdir, datain, sizeof(struct READDIR3args));
- callmsg->ch.rp_xid = txdr_unsigned(xid);
- value->xid = callmsg->ch.rp_xid;
- callmsg->ch.rp_direction = rpc_call;
- callmsg->ch.rp_rpcvers = rpc_vers;
- callmsg->ch.rp_prog = txdr_unsigned(prog);
- callmsg->ch.rp_vers = txdr_unsigned(vers);
- callmsg->ch.rp_proc = txdr_unsigned(procid);
-
- /* rpc_auth part (auth_unix as root) */
-
- callmsg->ch.rpc_auth.authtype = rpc_auth_null;
- //call->rpc_auth.authlen = 0;
-
-#ifdef CONFIG_NFS_UNIX_AUTH
- callmsg->ch.rpc_unix.stamp = txdr_unsigned(1);
- callmsg->ch.rpc_unix.hostname = 0;
- callmsg->ch.rpc_unix.uid = setuid;
- callmsg->ch.rpc_unix.gid = setgid;
- callmsg->ch.rpc_unix.gidlist = 0;
-#endif
- /* rpc_verf part (auth_null) */
-
- callmsg->ch.rpc_verf.authtype = rpc_auth_null;
- //call->rpc_verf.authlen = 0;
- return 0;
- }
-
- case NFSPROC_FSSTAT:
- {
- struct rpc_call_fs *callmsg = (struct rpc_call_fs *)dataout;
- memcpy(&callmsg->fs, datain, sizeof(struct FS3args));
- callmsg->ch.rp_xid = txdr_unsigned(xid);
- value->xid = callmsg->ch.rp_xid;
- callmsg->ch.rp_direction = rpc_call;
- callmsg->ch.rp_rpcvers = rpc_vers;
- callmsg->ch.rp_prog = txdr_unsigned(prog);
- callmsg->ch.rp_vers = txdr_unsigned(vers);
- callmsg->ch.rp_proc = txdr_unsigned(procid);
-
- /* rpc_auth part (auth_unix as root) */
-
- callmsg->ch.rpc_auth.authtype = rpc_auth_null;
- //call->rpc_auth.authlen = 0;
-
-#ifdef CONFIG_NFS_UNIX_AUTH
- callmsg->ch.rpc_unix.stamp = txdr_unsigned(1);
- callmsg->ch.rpc_unix.hostname = 0;
- callmsg->ch.rpc_unix.uid = setuid;
- callmsg->ch.rpc_unix.gid = setgid;
- callmsg->ch.rpc_unix.gidlist = 0;
-#endif
- /* rpc_verf part (auth_null) */
-
- callmsg->ch.rpc_verf.authtype = rpc_auth_null;
- //call->rpc_verf.authlen = 0;
- return 0;
- }
-
- case NFSPROC_REMOVE:
- {
- struct rpc_call_remove *callmsg = (struct rpc_call_remove *)dataout;
- memcpy(&callmsg->remove, datain, sizeof(struct REMOVE3args));
- callmsg->ch.rp_xid = txdr_unsigned(xid);
- value->xid = callmsg->ch.rp_xid;
- callmsg->ch.rp_direction = rpc_call;
- callmsg->ch.rp_rpcvers = rpc_vers;
- callmsg->ch.rp_prog = txdr_unsigned(prog);
- callmsg->ch.rp_vers = txdr_unsigned(vers);
- callmsg->ch.rp_proc = txdr_unsigned(procid);
-
- /* rpc_auth part (auth_unix as root) */
-
- callmsg->ch.rpc_auth.authtype = rpc_auth_null;
- //call->rpc_auth.authlen = 0;
-
-#ifdef CONFIG_NFS_UNIX_AUTH
- callmsg->ch.rpc_unix.stamp = txdr_unsigned(1);
- callmsg->ch.rpc_unix.hostname = 0;
- callmsg->ch.rpc_unix.uid = setuid;
- callmsg->ch.rpc_unix.gid = setgid;
- callmsg->ch.rpc_unix.gidlist = 0;
-#endif
- /* rpc_verf part (auth_null) */
-
- callmsg->ch.rpc_verf.authtype = rpc_auth_null;
- //call->rpc_verf.authlen = 0;
- return 0;
- }
-
- case NFSPROC_GETATTR:
- {
- struct rpc_call_fs *callmsg = (struct rpc_call_fs *)dataout;
- memcpy(&callmsg->fs, datain, sizeof(struct FS3args));
- callmsg->ch.rp_xid = txdr_unsigned(xid);
- value->xid = callmsg->ch.rp_xid;
- callmsg->ch.rp_direction = rpc_call;
- callmsg->ch.rp_rpcvers = rpc_vers;
- callmsg->ch.rp_prog = txdr_unsigned(prog);
- callmsg->ch.rp_vers = txdr_unsigned(vers);
- callmsg->ch.rp_proc = txdr_unsigned(procid);
-
- /* rpc_auth part (auth_unix as root) */
-
- callmsg->ch.rpc_auth.authtype = rpc_auth_null;
- //call->rpc_auth.authlen = 0;
-
-#ifdef CONFIG_NFS_UNIX_AUTH
- callmsg->ch.rpc_unix.stamp = txdr_unsigned(1);
- callmsg->ch.rpc_unix.hostname = 0;
- callmsg->ch.rpc_unix.uid = setuid;
- callmsg->ch.rpc_unix.gid = setgid;
- callmsg->ch.rpc_unix.gidlist = 0;
-#endif
- /* rpc_verf part (auth_null) */
-
- callmsg->ch.rpc_verf.authtype = rpc_auth_null;
- //call->rpc_verf.authlen = 0;
- return 0;
- }
-
- case NFSPROC_MKDIR:
- {
- struct rpc_call_mkdir *callmsg = (struct rpc_call_mkdir *)dataout;
- memcpy(&callmsg->mkdir, datain, sizeof(struct MKDIR3args));
- callmsg->ch.rp_xid = txdr_unsigned(xid);
- value->xid = callmsg->ch.rp_xid;
- callmsg->ch.rp_direction = rpc_call;
- callmsg->ch.rp_rpcvers = rpc_vers;
- callmsg->ch.rp_prog = txdr_unsigned(prog);
- callmsg->ch.rp_vers = txdr_unsigned(vers);
- callmsg->ch.rp_proc = txdr_unsigned(procid);
-
- /* rpc_auth part (auth_unix as root) */
-
- callmsg->ch.rpc_auth.authtype = rpc_auth_null;
- //call->rpc_auth.authlen = 0;
-
-#ifdef CONFIG_NFS_UNIX_AUTH
- callmsg->ch.rpc_unix.stamp = txdr_unsigned(1);
- callmsg->ch.rpc_unix.hostname = 0;
- callmsg->ch.rpc_unix.uid = setuid;
- callmsg->ch.rpc_unix.gid = setgid;
- callmsg->ch.rpc_unix.gidlist = 0;
-#endif
- /* rpc_verf part (auth_null) */
-
- callmsg->ch.rpc_verf.authtype = rpc_auth_null;
- //call->rpc_verf.authlen = 0;
- return 0;
- }
-
- case NFSPROC_RMDIR:
- {
- struct rpc_call_rmdir *callmsg = (struct rpc_call_rmdir *)dataout;
- memcpy(&callmsg->rmdir, datain, sizeof(struct RMDIR3args));
- callmsg->ch.rp_xid = txdr_unsigned(xid);
- value->xid = callmsg->ch.rp_xid;
- callmsg->ch.rp_direction = rpc_call;
- callmsg->ch.rp_rpcvers = rpc_vers;
- callmsg->ch.rp_prog = txdr_unsigned(prog);
- callmsg->ch.rp_vers = txdr_unsigned(vers);
- callmsg->ch.rp_proc = txdr_unsigned(procid);
-
- /* rpc_auth part (auth_unix as root) */
-
- callmsg->ch.rpc_auth.authtype = rpc_auth_null;
- //call->rpc_auth.authlen = 0;
-
-#ifdef CONFIG_NFS_UNIX_AUTH
- callmsg->ch.rpc_unix.stamp = txdr_unsigned(1);
- callmsg->ch.rpc_unix.hostname = 0;
- callmsg->ch.rpc_unix.uid = setuid;
- callmsg->ch.rpc_unix.gid = setgid;
- callmsg->ch.rpc_unix.gidlist = 0;
-#endif
- /* rpc_verf part (auth_null) */
-
- callmsg->ch.rpc_verf.authtype = rpc_auth_null;
- //call->rpc_verf.authlen = 0;
- return 0;
- }
-
- case NFSPROC_RENAME:
- {
- struct rpc_call_rename *callmsg = (struct rpc_call_rename *)dataout;
- memcpy(&callmsg->rename, datain, sizeof(struct RENAME3args));
- callmsg->ch.rp_xid = txdr_unsigned(xid);
- value->xid = callmsg->ch.rp_xid;
- callmsg->ch.rp_direction = rpc_call;
- callmsg->ch.rp_rpcvers = rpc_vers;
- callmsg->ch.rp_prog = txdr_unsigned(prog);
- callmsg->ch.rp_vers = txdr_unsigned(vers);
- callmsg->ch.rp_proc = txdr_unsigned(procid);
-
- /* rpc_auth part (auth_unix as root) */
-
- callmsg->ch.rpc_auth.authtype = rpc_auth_null;
- //call->rpc_auth.authlen = 0;
-
-#ifdef CONFIG_NFS_UNIX_AUTH
- callmsg->ch.rpc_unix.stamp = txdr_unsigned(1);
- callmsg->ch.rpc_unix.hostname = 0;
- callmsg->ch.rpc_unix.uid = setuid;
- callmsg->ch.rpc_unix.gid = setgid;
- callmsg->ch.rpc_unix.gidlist = 0;
-#endif
- /* rpc_verf part (auth_null) */
-
- callmsg->ch.rpc_verf.authtype = rpc_auth_null;
- //call->rpc_verf.authlen = 0;
- return 0;
- }
-
- case NFSPROC_FSINFO:
- {
- struct rpc_call_fs *callmsg = (struct rpc_call_fs *)dataout;
- memcpy(&callmsg->fs, datain, sizeof(struct FS3args));
- callmsg->ch.rp_xid = txdr_unsigned(xid);
- value->xid = callmsg->ch.rp_xid;
- callmsg->ch.rp_direction = rpc_call;
- callmsg->ch.rp_rpcvers = rpc_vers;
- callmsg->ch.rp_prog = txdr_unsigned(prog);
- callmsg->ch.rp_vers = txdr_unsigned(vers);
- callmsg->ch.rp_proc = txdr_unsigned(procid);
-
- /* rpc_auth part (auth_unix as root) */
-
- callmsg->ch.rpc_auth.authtype = rpc_auth_null;
- //call->rpc_auth.authlen = 0;
-
-#ifdef CONFIG_NFS_UNIX_AUTH
- callmsg->ch.rpc_unix.stamp = txdr_unsigned(1);
- callmsg->ch.rpc_unix.hostname = 0;
- callmsg->ch.rpc_unix.uid = setuid;
- callmsg->ch.rpc_unix.gid = setgid;
- callmsg->ch.rpc_unix.gidlist = 0;
-#endif
- /* rpc_verf part (auth_null) */
-
- callmsg->ch.rpc_verf.authtype = rpc_auth_null;
- //call->rpc_verf.authlen = 0;
- return 0;
- }
-
- default:
- break;
- }
- }
-
- return ESRCH;
-}
-
-/****************************************************************************
- * Name: rpcclnt_lookup
- *
- * Desciption:
- * Given a directory file handle, and the path to file in the directory,
- * return the file handle of the path and attributes of both the file and
- * the directory containing the file.
- *
- * NOTE: The LOOKUP call differs from other RPC messages in that the
- * call message is variable length, depending upon the size of the path
- * name.
- *
- ****************************************************************************/
-
-int rpcclnt_lookup(FAR struct rpcclnt *rpc, FAR const char *relpath,
- FAR struct file_handle *fhandle,
- FAR struct nfs_fattr *obj_attributes,
- FAR struct nfs_fattr *dir_attributes)
-{
-#warning "Missing logic"
- return ENOSYS;
-}
-
#ifdef COMP
int rpcclnt_cancelreqs(struct rpcclnt *rpc)
{