summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-06-12 16:11:31 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-06-12 16:11:31 +0000
commit7f63dd840feea2cce7e55ad8bc4e1e98d23ede87 (patch)
treeeb7dfcf5b90bab0d33944737b9a0e190245469fd
parentc5af86030963729f5b208777284c01bb394a5d39 (diff)
downloadpx4-nuttx-7f63dd840feea2cce7e55ad8bc4e1e98d23ede87.tar.gz
px4-nuttx-7f63dd840feea2cce7e55ad8bc4e1e98d23ede87.tar.bz2
px4-nuttx-7f63dd840feea2cce7e55ad8bc4e1e98d23ede87.zip
Fix PL2303 typo checked in a long time ago; NFS update
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4832 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/ChangeLog2
-rw-r--r--nuttx/drivers/usbdev/pl2303.c2
-rw-r--r--nuttx/fs/nfs/nfs.h17
-rw-r--r--nuttx/fs/nfs/nfs_node.h8
-rw-r--r--nuttx/fs/nfs/nfs_util.c21
-rw-r--r--nuttx/fs/nfs/nfs_vfsops.c242
-rw-r--r--nuttx/fs/nfs/rpc.h2
-rw-r--r--nuttx/fs/nfs/rpc_clnt.c45
8 files changed, 215 insertions, 124 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 7b32ae20f..d7d6f7fc4 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -2900,4 +2900,6 @@
Fix an error when the trapezoid is only 1 line high. In this case, a
divide by zero error would occur. The fix is to draw the 1 line high
trapezoid as a run.
+ * drivers/usbdev/pl2303.c: Fixe a cut'n'paste error that snuck into
+ the PL2303 emulation driver several months back.
diff --git a/nuttx/drivers/usbdev/pl2303.c b/nuttx/drivers/usbdev/pl2303.c
index 8bd94ddd0..69bf87965 100644
--- a/nuttx/drivers/usbdev/pl2303.c
+++ b/nuttx/drivers/usbdev/pl2303.c
@@ -598,7 +598,7 @@ static int usbclass_sndpacket(FAR struct pl2303_dev_s *priv)
/* Get the maximum number of bytes that will fit into one bulk IN request */
#ifdef CONFIG_PL2303_BULKREQLEN
- reqlen = MAX(CONFIG_CDCACM_BULKREQLEN, ep->maxpacket);
+ reqlen = MAX(CONFIG_PL2303_BULKREQLEN, ep->maxpacket);
#else
reqlen = ep->maxpacket;
#endif
diff --git a/nuttx/fs/nfs/nfs.h b/nuttx/fs/nfs/nfs.h
index d18442b97..2518a330d 100644
--- a/nuttx/fs/nfs/nfs.h
+++ b/nuttx/fs/nfs/nfs.h
@@ -360,22 +360,23 @@ extern "C" {
#define EXTERN extern
#endif
-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,
+EXTERN void nfs_semtake(FAR struct nfsmount *nmp);
+EXTERN void nfs_semgive(FAR struct nfsmount *nmp);
+EXTERN int nfs_checkmount(FAR struct nfsmount *nmp);
+EXTERN int nfs_fsinfo(FAR struct nfsmount *nmp);
+EXTERN int nfs_lookup(FAR 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,
+EXTERN int nfs_findnode(FAR struct nfsmount *nmp, FAR const char *relpath,
FAR struct file_handle *fhandle,
FAR struct nfs_fattr *obj_attributes,
FAR struct nfs_fattr *dir_attributes);
-EXTERN int nfs_finddir(struct nfsmount *nmp, FAR const char *relpath,
+EXTERN int nfs_finddir(FAR struct nfsmount *nmp, FAR const char *relpath,
FAR struct file_handle *fhandle,
FAR struct nfs_fattr *attributes, FAR char *filename);
-
+EXTERN void nfs_attrupdate(FAR struct nfsnode *np,
+ FAR struct nfs_fattr *attributes);
#undef EXTERN
#if defined(__cplusplus)
}
diff --git a/nuttx/fs/nfs/nfs_node.h b/nuttx/fs/nfs/nfs_node.h
index 377d2a88f..02e14cbde 100644
--- a/nuttx/fs/nfs/nfs_node.h
+++ b/nuttx/fs/nfs/nfs_node.h
@@ -65,9 +65,6 @@
/* There is a unique nfsnode allocated for each active file. An nfsnode is
* 'named' by its file handle.
- *
- * NOTE: n_size, n_mtime, and n_ctime are duplicted withing n_attr. We could
- * eliminate those fields and save some memory.
*/
struct nfsnode
@@ -77,9 +74,8 @@ struct nfsnode
uint8_t n_fhsize; /* Size in bytes of the file handle */
uint8_t n_flags; /* Node flags */
uint16_t n_buflen; /* Size of I/O buffer */
- struct nfs_fattr n_fattr; /* nfs file attribute cache (network order) */
- struct timespec n_mtime; /* Prev modify time (see NOTE) */
- time_t n_ctime; /* Prev create time (see NOTE) */
+ struct timespec n_mtime; /* File modification time (see NOTE) */
+ time_t n_ctime; /* File creation time (see NOTE) */
nfsfh_t n_fhandle; /* NFS File Handle */
uint64_t n_size; /* Current size of file (see NOTE) */
diff --git a/nuttx/fs/nfs/nfs_util.c b/nuttx/fs/nfs/nfs_util.c
index 8a3a1e579..d489a839c 100644
--- a/nuttx/fs/nfs/nfs_util.c
+++ b/nuttx/fs/nfs/nfs_util.c
@@ -616,3 +616,24 @@ int nfs_finddir(struct nfsmount *nmp, FAR const char *relpath,
}
}
}
+
+/****************************************************************************
+ * Name: nfs_attrupdate
+ *
+ * Desciption:
+ * Update file attributes on write or after the file is modified.
+ *
+ * Return Value:
+ * None.
+ *
+ ****************************************************************************/
+
+void nfs_attrupdate(FAR struct nfsnode *np, FAR struct nfs_fattr *attributes)
+{
+ /* Save a few of the files attribute values in file structur (host order) */
+
+ np->n_type = fxdr_unsigned(uint32_t, attributes->fa_type);
+ np->n_size = fxdr_hyper(&attributes->fa_size);
+ fxdr_nfsv3time(&attributes->fa_mtime, &np->n_mtime)
+ np->n_ctime = fxdr_hyper(&attributes->fa_ctime);
+}
diff --git a/nuttx/fs/nfs/nfs_vfsops.c b/nuttx/fs/nfs/nfs_vfsops.c
index 5bb6f188f..d4392ac0d 100644
--- a/nuttx/fs/nfs/nfs_vfsops.c
+++ b/nuttx/fs/nfs/nfs_vfsops.c
@@ -200,6 +200,7 @@ static int nfs_filecreate(FAR struct nfsmount *nmp, struct nfsnode *np,
FAR const char *relpath, mode_t mode)
{
struct file_handle fhandle;
+ struct nfs_fattr fattr;
char filename[NAME_MAX + 1];
struct CREATE3args request;
struct rpc_reply_create resok;
@@ -211,7 +212,7 @@ static int nfs_filecreate(FAR struct nfsmount *nmp, struct nfsnode *np,
/* Find the NFS node of the directory containing the file to be created */
- error = nfs_finddir(nmp, relpath, &fhandle, &np->n_fattr, filename);
+ error = nfs_finddir(nmp, relpath, &fhandle, &fattr, filename);
if (error != OK)
{
fdbg("ERROR: nfs_finddir returned: %d\n", error);
@@ -329,7 +330,7 @@ static int nfs_filecreate(FAR struct nfsmount *nmp, struct nfsnode *np,
{
/* Parse the returned data */
- ptr = (FAR uint32_t *)&resok;
+ ptr = (FAR uint32_t *)&resok.create;
/* Save the file handle in the file data structure */
@@ -357,15 +358,10 @@ static int nfs_filecreate(FAR struct nfsmount *nmp, struct nfsnode *np,
}
else
{
- memcpy(&np->n_fattr, ptr, sizeof(struct nfs_fattr));
- ptr += uint32_increment(sizeof(struct nfs_fattr));
+ /* Initialize the file attributes */
- /* Put a few of the attribute values in host order */
-
- np->n_type = fxdr_unsigned(uint32_t, np->n_fattr.fa_type);
- np->n_size = fxdr_hyper(&np->n_fattr.fa_size);
- fxdr_nfsv3time(&np->n_fattr.fa_mtime, &np->n_mtime)
- np->n_ctime = fxdr_hyper(&np->n_fattr.fa_ctime);
+ nfs_attrupdate(np, (FAR struct nfs_fattr *)ptr);
+ ptr += uint32_increment(sizeof(struct nfs_fattr));
}
/* Any following dir_wcc data is ignored for now */
@@ -390,12 +386,13 @@ static int nfs_fileopen(FAR struct nfsmount *nmp, struct nfsnode *np,
FAR const char *relpath, int oflags, mode_t mode)
{
struct file_handle fhandle;
+ struct nfs_fattr fattr;
uint32_t tmp;
int error = 0;
/* Find the NFS node associate with the path */
- error = nfs_findnode(nmp, relpath, &fhandle, &np->n_fattr, NULL);
+ error = nfs_findnode(nmp, relpath, &fhandle, &fattr, NULL);
if (error != OK)
{
fdbg("ERROR: nfs_findnode returned: %d\n", error);
@@ -404,7 +401,7 @@ static int nfs_fileopen(FAR struct nfsmount *nmp, struct nfsnode *np,
/* Check if the object is a directory */
- tmp = fxdr_unsigned(uint32_t, np->n_fattr.fa_type);
+ tmp = fxdr_unsigned(uint32_t, fattr.fa_type);
if (tmp == NFDIR)
{
/* Exit with EISDIR if we attempt to open a directory */
@@ -422,7 +419,7 @@ static int nfs_fileopen(FAR struct nfsmount *nmp, struct nfsnode *np,
* able to write).
*/
- tmp = fxdr_unsigned(uint32_t, np->n_fattr.fa_mode);
+ tmp = fxdr_unsigned(uint32_t, fattr.fa_mode);
if ((tmp & (NFSMODE_IWOTH|NFSMODE_IWGRP|NFSMODE_IWUSR)) == 0)
{
fdbg("ERROR: File is read-only: %08x\n", tmp);
@@ -463,15 +460,9 @@ static int nfs_fileopen(FAR struct nfsmount *nmp, struct nfsnode *np,
np->n_fhsize = (uint8_t)fhandle.length;
memcpy(&np->n_fhandle, &fhandle.handle, fhandle.length);
- /* Get a convenience versions of file type, size, and modification time
- * in host byte order.
- */
-
- np->n_type = fxdr_unsigned(uint32_t, np->n_fattr.fa_type);
- np->n_size = fxdr_hyper(&np->n_fattr.fa_size);
- fxdr_nfsv3time(&np->n_fattr.fa_mtime, &np->n_mtime)
- np->n_ctime = fxdr_hyper(&np->n_fattr.fa_ctime);
+ /* Save the file attributes */
+ nfs_attrupdate(np, &fattr);
return OK;
}
@@ -753,7 +744,7 @@ static ssize_t nfs_read(FAR struct file *filep, char *buffer, size_t buflen)
ptr = (FAR uint32_t*)&request;
reqlen = 0;
- /* Copy the variable length, directory file handle */
+ /* Copy the variable length, file handle */
*ptr++ = txdr_unsigned((uint32_t)np->n_fhsize);
reqlen += sizeof(uint32_t);
@@ -858,19 +849,20 @@ errout_with_semaphore:
static ssize_t nfs_write(FAR struct file *filep, const char *buffer,
size_t buflen)
{
- struct inode *inode;
struct nfsmount *nmp;
struct nfsnode *np;
- unsigned int writesize;
struct rpc_reply_write resok;
- uint64_t offset;
- uint8_t *userbuffer = (uint8_t*)buffer;
+ ssize_t writesize;
+ ssize_t bufsize;
+ ssize_t byteswritten;
size_t reqlen;
- uint32_t *ptr;
- int len;
+ FAR uint32_t *ptr;
+ uint32_t tmp;
int commit = 0;
int committed = NFSV3WRITE_FILESYNC;
- int error = 0;
+ int error;
+
+ fvdbg("Write %d bytes to offset %d\n", buflen, filep->f_pos);
/* Sanity checks */
@@ -878,10 +870,8 @@ static ssize_t nfs_write(FAR struct file *filep, const char *buffer,
/* Recover our private data from the struct file instance */
- np = (struct nfsnode *)filep->f_priv;
- inode = filep->f_inode;
- nmp = (struct nfsmount *)inode->i_private;
- offset = 0;
+ nmp = (struct nfsmount*)filep->f_inode->i_private;
+ np = (struct nfsnode*)filep->f_priv;
DEBUGASSERT(nmp != NULL);
@@ -891,7 +881,7 @@ static ssize_t nfs_write(FAR struct file *filep, const char *buffer,
error = nfs_checkmount(nmp);
if (error != OK)
{
- fdbg("ERROR: nfs_checkmount failed: %d\n", error);
+ fdbg("nfs_checkmount failed: %d\n", error);
goto errout_with_semaphore;
}
@@ -903,86 +893,143 @@ static ssize_t nfs_write(FAR struct file *filep, const char *buffer,
goto errout_with_semaphore;
}
- len = nmp->nm_wsize;
- if (len < buflen)
+ /* Now loop until we send the entire user buffer */
+
+ for (byteswritten = 0; byteswritten < buflen; )
{
- error = EFBIG;
- goto errout_with_semaphore;
- }
+ /* Make sure that the attempted write size does not exceed the RPC maximum */
+
+ writesize = buflen;
+ if (writesize > nmp->nm_wsize)
+ {
+ writesize = nmp->nm_wsize;
+ }
- writesize = 0;
+ /* Make sure that the attempted read size does not exceed the IO buffer size */
- /* Initialize the request */
+ bufsize = SIZEOF_rpc_call_write(writesize);
+ if (bufsize > np->n_buflen)
+ {
+ writesize -= (bufsize - np->n_buflen);
+ }
- ptr = (FAR uint32_t*)&np->n_iobuffer;
- reqlen = 0;
+ /* Initialize the request. Here we need an offset pointer to the write
+ * arguments, skipping over the RPC header. Write is unique among the
+ * RPC calls in that the entry RPC calls messasge lies in the I/O buffer
+ */
- /* Copy the variable length, directory file handle */
+ ptr = (FAR uint32_t *)&((FAR struct rpc_call_write *)np->n_iobuffer)->write;
+ reqlen = 0;
- *ptr++ = txdr_unsigned((uint32_t)np->n_fhsize);
- reqlen += sizeof(uint32_t);
+ /* Copy the variable length, file handle */
- memcpy(ptr, &np->n_fhandle, np->n_fhsize);
- reqlen += (int)np->n_fhsize;
- ptr += uint32_increment((int)np->n_fhsize);
+ *ptr++ = txdr_unsigned((uint32_t)np->n_fhsize);
+ reqlen += sizeof(uint32_t);
- /* Copy the file offset */
+ memcpy(ptr, &np->n_fhandle, np->n_fhsize);
+ reqlen += (int)np->n_fhsize;
+ ptr += uint32_increment((int)np->n_fhsize);
- txdr_hyper((uint64_t)filep->f_pos, ptr);
- ptr += 2;
- reqlen += 2*sizeof(uint32_t);
+ /* Copy the file offset */
- /* Copy the count and stable values */
+ txdr_hyper((uint64_t)filep->f_pos, ptr);
+ ptr += 2;
+ reqlen += 2*sizeof(uint32_t);
- *ptr++ = txdr_unsigned(buflen);
- *ptr++ = txdr_unsigned(committed);
- reqlen += 2*sizeof(uint32_t);
+ /* Copy the count and stable values */
- memcpy(ptr, userbuffer, buflen);
- reqlen += buflen;
+ *ptr++ = txdr_unsigned(buflen);
+ *ptr++ = txdr_unsigned(committed);
+ reqlen += 2*sizeof(uint32_t);
- nfsstats.rpccnt[NFSPROC_WRITE]++;
- error = nfs_request(nmp, NFSPROC_WRITE,
- (FAR const void *)np->n_iobuffer, reqlen,
- (FAR void *)&resok, sizeof(struct rpc_reply_write));
- if (error)
- {
- goto errout_with_semaphore;
- }
+ /* Copy a chunk of the user data into the I/O buffer */
- writesize = resok.write.count;
- if (writesize == 0)
- {
- error = EIO;
- goto errout_with_semaphore;
- }
+ *ptr++ = txdr_unsigned(buflen);
+ reqlen += sizeof(uint32_t);
+ memcpy(ptr, buffer, writesize);
+ reqlen += writesize;
- commit = resok.write.committed;
- memcpy(&np->n_fattr, &resok.write.file_wcc.after, sizeof(struct nfs_fattr));
+ /* Perform the write */
- /* Return the lowest committment level obtained by any of the RPCs. */
+ nfsstats.rpccnt[NFSPROC_WRITE]++;
+ error = nfs_request(nmp, NFSPROC_WRITE,
+ (FAR const void *)np->n_iobuffer, reqlen,
+ (FAR void *)&resok, sizeof(struct rpc_reply_write));
+ if (error)
+ {
+ fdbg("ERROR: nfs_request failed: %d\n", error);
+ goto errout_with_semaphore;
+ }
- if (committed == NFSV3WRITE_FILESYNC)
- {
- committed = commit;
- }
- else if (committed == NFSV3WRITE_DATASYNC &&
- commit == NFSV3WRITE_UNSTABLE)
- {
- committed = commit;
- }
+ /* Get a pointer to the WRITE reply data */
- if ((nmp->nm_flag & NFSMNT_HASWRITEVERF) == 0)
- {
- memcpy((void*) nmp->nm_verf, (void*) resok.write.verf, NFSX_V3WRITEVERF);
- nmp->nm_flag |= NFSMNT_HASWRITEVERF;
- }
- else if (strncmp((char*) resok.write.verf, (char*) nmp->nm_verf, NFSX_V3WRITEVERF))
- {
- memcpy((void*) nmp->nm_verf, (void*) resok.write.verf, NFSX_V3WRITEVERF);
- }
+ ptr = (FAR uint32_t *)&resok.write;
+
+ /* Parse file_wcc. First, check if WCC attributes follow. */
+
+ tmp = *ptr++;
+ if (tmp != 0)
+ {
+ /* Yes.. WCC attributes follow. But we just skip over them. */
+
+ ptr += uint32_increment(sizeof(struct wcc_attr));
+ }
+
+ /* Check if normal file attributes follow */
+
+ tmp = *ptr++;
+ if (tmp != 0)
+ {
+ /* Yes.. Update the cached file status in the file structure. */
+
+ nfs_attrupdate(np, (FAR struct nfs_fattr *)ptr);
+ ptr += uint32_increment(sizeof(struct nfs_fattr));
+ }
+
+ /* Get the count of bytes actually written */
+
+ tmp = fxdr_unsigned(uint32_t, *ptr);
+ ptr++;
+
+ if (tmp < 1 || tmp > writesize)
+ {
+ error = EIO;
+ goto errout_with_semaphore;
+ }
+
+ writesize = tmp;
+
+ /* Determine the lowest committment level obtained by any of the RPCs. */
+
+ commit = *ptr++;
+ if (committed == NFSV3WRITE_FILESYNC)
+ {
+ committed = commit;
+ }
+ else if (committed == NFSV3WRITE_DATASYNC &&
+ commit == NFSV3WRITE_UNSTABLE)
+ {
+ committed = commit;
+ }
+
+ /* Save the verifier if needed or if it has change*/
+
+ if ((nmp->nm_flag & NFSMNT_HASWRITEVERF) == 0)
+ {
+ memcpy(nmp->nm_verf, ptr, NFSX_V3WRITEVERF);
+ nmp->nm_flag |= NFSMNT_HASWRITEVERF;
+ }
+ else if (memcmp(ptr, nmp->nm_verf, NFSX_V3WRITEVERF) != 0)
+ {
+ memcpy(nmp->nm_verf, ptr, NFSX_V3WRITEVERF);
+ }
- fxdr_nfsv3time(&np->n_fattr.fa_mtime, &np->n_mtime)
+ /* Update the read state data */
+
+ filep->f_pos += writesize;
+ byteswritten += writesize;
+ buffer += writesize;
+ }
nfs_semgive(nmp);
return writesize;
@@ -1664,8 +1711,8 @@ int mountnfs(struct nfs_args *argp, void **handle)
/* Save the file attributes */
- memcpy(&np->n_fattr, &resok.attr, sizeof(struct nfs_fattr));
memcpy(&nmp->nm_fattr, &resok.attr, sizeof(struct nfs_fattr));
+ nfs_attrupdate(np, &resok.attr);
/* Mounted! */
@@ -1852,7 +1899,6 @@ static int nfs_statfs(struct inode *mountpt, struct statfs *sbp)
goto errout_with_semaphore;
}
- nmp->nm_head->n_fattr = sfp.fsstat.obj_attributes;
sbp->f_bsize = NFS_FABLKSIZE;
tquad = fxdr_hyper(&sfp.fsstat.sf_tbytes);
sbp->f_blocks = tquad / (uint64_t) NFS_FABLKSIZE;
@@ -2275,7 +2321,7 @@ static int nfs_rename(struct inode *mountpt, const char *oldrelpath,
return error;
}
- /* Format the RENAME RPC arguements */
+ /* Format the RENAME RPC arguments */
ptr = (FAR uint32_t *)&request;
reqlen = 0;
diff --git a/nuttx/fs/nfs/rpc.h b/nuttx/fs/nfs/rpc.h
index 2aa01a69a..336e78798 100644
--- a/nuttx/fs/nfs/rpc.h
+++ b/nuttx/fs/nfs/rpc.h
@@ -434,7 +434,7 @@ struct rpc_reply_write
{
struct rpc_reply_header rh;
uint32_t status;
- struct WRITE3resok write;
+ struct WRITE3resok write; /* Variable length */
};
struct rpc_reply_read
diff --git a/nuttx/fs/nfs/rpc_clnt.c b/nuttx/fs/nfs/rpc_clnt.c
index 34d5ccc13..aafd63feb 100644
--- a/nuttx/fs/nfs/rpc_clnt.c
+++ b/nuttx/fs/nfs/rpc_clnt.c
@@ -1143,12 +1143,12 @@ static int rpcclnt_buildheader(struct rpcclnt *rpc, int procid, int prog, int ve
case NFSPROC_WRITE:
{
- /* Copy the variable length, caller-provided data into the call
- * message structure.
+ /* The WRITE message is a unique case: The write data is already
+ * provided in an I/O buffer at the correct offset. Here we
+ * merely have to inititlized the RPC header fields.
*/
- struct rpc_call_write *callmsg = (struct rpc_call_write *)msgbuf;
- memcpy(&callmsg->write, request, *reqlen);
+ struct rpc_call_write *callmsg = (struct rpc_call_write *)request;
/* Return the full size of the message (the size of variable data
* plus the size of the messages header).
@@ -1790,7 +1790,11 @@ int rpcclnt_request(FAR struct rpcclnt *rpc, int procnum, int prog,
struct xidr value;
int error = 0;
- /* Set aside memory on the stack to hold the largest call message */
+ /* Set aside memory on the stack to hold the largest call message. NOTE
+ * that the write call message does not appear in this list. It is a
+ * special case because the full write call message will be provided in
+ * user-provided I/O vuffer.
+ */
union
{
@@ -1798,7 +1802,6 @@ int rpcclnt_request(FAR struct rpcclnt *rpc, int procnum, int prog,
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;
struct rpc_call_rename renamef;
@@ -1807,10 +1810,32 @@ int rpcclnt_request(FAR struct rpcclnt *rpc, int procnum, int prog,
struct rpc_call_readdir readdir;
struct rpc_call_fs fs;
} u;
+ FAR void *callmsg;
- /* Clear the call message memory */
+ /* Handle a nasty special case... the NFS WRITE call message will reside
+ * in a use provided I/O buffer, not in our local call message buffer.
+ */
+
+ if (prog == NFS_PROG && procnum == NFSPROC_WRITE)
+ {
+ /* User the caller provided I/O buffer. The data to be written has
+ * already been copied into the correct offset by the calling.
+ * rpcclnt_buildheader will need only to initialize the header and
+ * update the call messsage size.
+ */
- memset(&u, 0, sizeof(u));
+ callmsg = request;
+ }
+ else
+ {
+ /* Clear the local call message memory. rpcclnt_buildheader will
+ * need to initialie the header and copy the user RPC arguments into
+ * this buffer.
+ */
+
+ memset(&u, 0, sizeof(u));
+ callmsg = (FAR void *)&u;
+ }
/* Create an instance of the task state structure */
@@ -1822,7 +1847,7 @@ int rpcclnt_request(FAR struct rpcclnt *rpc, int procnum, int prog,
}
error = rpcclnt_buildheader(rpc, procnum, prog, version, &value,
- request, &reqlen, (FAR void*)&u);
+ request, &reqlen, callmsg);
if (error)
{
fdbg("ERROR: Building call header error\n");
@@ -1881,7 +1906,7 @@ int rpcclnt_request(FAR struct rpcclnt *rpc, int procnum, int prog,
if (error == 0)
{
error = rpcclnt_send(rpc->rc_so, rpc->rc_name, procnum, prog,
- (FAR void*)&u, reqlen, task);
+ callmsg, reqlen, task);
#ifdef CONFIG_NFS_TCPIP
if (rpc->rc_soflags & PR_CONNREQUIRED)