summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/ChangeLog4
-rw-r--r--nuttx/arch/mips/src/pic32mx/pic32mx-ethernet.c4
-rw-r--r--nuttx/configs/pic32mx7mmb/nsh/defconfig12
-rw-r--r--nuttx/fs/nfs/nfs_mount.h1
-rw-r--r--nuttx/fs/nfs/nfs_node.h20
-rw-r--r--nuttx/fs/nfs/nfs_vfsops.c47
6 files changed, 72 insertions, 16 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 79845d19d..60e3ff539 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -2866,5 +2866,9 @@
of the Mikroelektronika PIC32MX7 MMB. That board now works!
* configs/pic32mx7mmb/nsh: Added and verify a NuttShell configuration
for the Mikroelektronika PIC32MX7 MMB board.
+ * arch/mips/pic32/pic32mx-ethernet.c: Fix logic that guesses PHY address;
+ the search loop missed the PHY address needed by the Mikroelektronika
+ PIC32MX7 MMB board.
+ * configs/pic32mx7mmb/nsh: Configuration now supports a network by default.
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-ethernet.c b/nuttx/arch/mips/src/pic32mx/pic32mx-ethernet.c
index 40db51f80..30860edfa 100644
--- a/nuttx/arch/mips/src/pic32mx/pic32mx-ethernet.c
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-ethernet.c
@@ -2676,7 +2676,7 @@ static inline int pic32mx_phyinit(struct pic32mx_driver_s *priv)
* latches different at different addresses.
*/
- for (phyaddr = 1; phyaddr < 32; phyaddr++)
+ for (phyaddr = 0; phyaddr < 32; phyaddr++)
{
/* Clear any ongoing PHY command bits */
@@ -2687,7 +2687,7 @@ static inline int pic32mx_phyinit(struct pic32mx_driver_s *priv)
ret = pic32mx_phyreset(phyaddr);
if (ret < 0)
{
- ndbg("Failed to reset PHY at address %d\n");
+ ndbg("Failed to reset PHY at address %d\n", phyaddr);
continue;
}
diff --git a/nuttx/configs/pic32mx7mmb/nsh/defconfig b/nuttx/configs/pic32mx7mmb/nsh/defconfig
index 75e8f8c5a..35bcbd89d 100644
--- a/nuttx/configs/pic32mx7mmb/nsh/defconfig
+++ b/nuttx/configs/pic32mx7mmb/nsh/defconfig
@@ -165,7 +165,7 @@ CONFIG_PIC32MX_USBDEV=n
CONFIG_PIC32MX_USBHOST=n
CONFIG_PIC32MX_CAN1=n
CONFIG_PIC32MX_CAN2=n
-CONFIG_PIC32MX_ETHERNET=n
+CONFIG_PIC32MX_ETHERNET=y
CONFIG_PIC32MX_IOPORTA=y
CONFIG_PIC32MX_IOPORTB=y
CONFIG_PIC32MX_IOPORTC=y
@@ -440,8 +440,10 @@ CONFIG_DEBUG=n
CONFIG_DEBUG_VERBOSE=n
CONFIG_DEBUG_SYMBOLS=n
CONFIG_DEBUG_SCHED=n
+CONFIG_DEBUG_USB=n
CONFIG_DEBUG_NET=n
CONFIG_DEBUG_LCD=n
+CONFIG_DEBUG_GRAPHICS=n
CONFIG_DEBUG_INPUT=n
CONFIG_HAVE_CXX=n
@@ -690,9 +692,9 @@ CONFIG_FB_HWCURSORIMAGE=n
# option will enable a limited form of memory mapping that is
# implemented by copying whole files into memory.
#
-CONFIG_FS_FAT=n
-CONFIG_FAT_LCNAMES=n
-CONFIG_FAT_LFN=n
+CONFIG_FS_FAT=y
+CONFIG_FAT_LCNAMES=y
+CONFIG_FAT_LFN=y
CONFIG_FAT_MAXFNAME=32
CONFIG_FS_NXFFS=n
CONFIG_FS_ROMFS=n
@@ -779,7 +781,7 @@ CONFIG_MMCSD_HAVECARDDETECT=n
# CONFIG_NET_FWCACHE_SIZE - number of packets to remember when
# looking for duplicates
#
-CONFIG_NET=n
+CONFIG_NET=y
CONFIG_NET_NOINTS=n
CONFIG_NET_MULTIBUFFER=y
CONFIG_NET_IPv6=n
diff --git a/nuttx/fs/nfs/nfs_mount.h b/nuttx/fs/nfs/nfs_mount.h
index d7012991d..63f193696 100644
--- a/nuttx/fs/nfs/nfs_mount.h
+++ b/nuttx/fs/nfs/nfs_mount.h
@@ -78,6 +78,7 @@ struct nfsmount
nfsfh_t nm_fh; /* File handle of root dir */
char nm_path[90]; /* server's path of the directory being mount */
int nm_fhsize; /* Size of root file handle */
+ struct nfs_fattr nm_fattr; /* nfs file attribute cache */
struct rpcclnt *nm_rpcclnt; /* rpc state */
struct socket *nm_so; /* Rpc socket */
uint8_t nm_sotype; /* Type of socket */
diff --git a/nuttx/fs/nfs/nfs_node.h b/nuttx/fs/nfs/nfs_node.h
index 9a8799558..a07c8473a 100644
--- a/nuttx/fs/nfs/nfs_node.h
+++ b/nuttx/fs/nfs/nfs_node.h
@@ -123,7 +123,7 @@ struct nfsnode
bool n_open; /* true: The file is (still) open */
uint64_t n_size; /* Current size of file */
struct nfs_fattr n_fattr; /* nfs file attribute cache */
- uint32_t nfsv3_type; /* File type */
+ uint8_t nfsv3_type; /* File type */
time_t n_attrstamp; /* Attr. cache timestamp */
struct timespec n_mtime; /* Prev modify time. */
time_t n_ctime; /* Prev create time. */
@@ -156,4 +156,22 @@ struct nfsnode
//int n_commitflags;
};
+/* This structure is used internally for describing the result of
+ * walking a path
+ */
+
+struct nfs_dirinfo_s
+{
+ /* These values describe the directory containing the terminal
+ * path component (of the terminal component itself if it is
+ * a directory.
+ */
+
+ struct nfsdir_s n_dir; /* Describes directory. */
+
+ /* Values from the NFS file entry */
+
+ struct nfsnode attribute;
+};
+
#endif /* __FS_NFS_NFS_NODE_H */
diff --git a/nuttx/fs/nfs/nfs_vfsops.c b/nuttx/fs/nfs/nfs_vfsops.c
index a56aa9f3b..d69effbb3 100644
--- a/nuttx/fs/nfs/nfs_vfsops.c
+++ b/nuttx/fs/nfs/nfs_vfsops.c
@@ -223,8 +223,8 @@ again:
//vap = nmp->nm_head->n_fattr;
sp.sa_modetrue = true;
sp.sa_mode = txdr_unsigned(mode);
- sp.sa_uidfalse = 0;
- sp.sa_gidfalse = 0;
+ sp.sa_uidfalse = nfs_xdrneg1;
+ sp.sa_gidfalse = nfs_xdrneg1;
sp.sa_sizefalse = 0;
sp.sa_atimetype = txdr_unsigned(NFSV3SATTRTIME_DONTCHANGE);
sp.sa_mtimetype = txdr_unsigned(NFSV3SATTRTIME_DONTCHANGE);
@@ -257,8 +257,22 @@ again:
* non-zero elements)
*/
- np->n_open = true;
np->nfsv3_type = fxdr_unsigned(uint32_t, resok.attributes.fa_type);
+
+ /* The full path exists -- but is the final component a file
+ * or a directory?
+ */
+
+ if (np->nfsv3_type == NFDIR)
+ {
+ /* It is a directory */
+
+ error = EISDIR;
+ fdbg("'%s' is a directory\n", relpath);
+ goto errout_with_semaphore;
+ }
+
+ np->n_open = true;
np->n_fhp = resok.fshandle.handle;
np->n_size = fxdr_hyper(&resok.attributes.fa3_size);
np->n_fattr = resok.attributes;
@@ -291,7 +305,7 @@ again:
}
else
{
- if (np->nfsv3_type != NFREG && np->nfsv3_type != NFDIR)
+ if (np->nfsv3_type != NFREG)
{
ndbg("open eacces typ=%d\n", np->nfsv3_type);
return EACCES;
@@ -590,7 +604,9 @@ static int nfs_opendir(struct inode *mountpt, const char *relpath,
{
struct nfsmount *nmp;
struct nfsnode *np;
-//struct romfs_dirinfo_s dirinfo;
+ struct nfsv3_fsinfo fsp;
+ struct FS3args attributes;
+//struct nfs_dirinfo_s dirinfo;
int ret;
fvdbg("relpath: '%s'\n", relpath);
@@ -633,13 +649,25 @@ static int nfs_opendir(struct inode *mountpt, const char *relpath,
dir->u.nfs.cookie[1] = 0;
}
}
+
+ attributes.fsroot.length = txdr_unsigned(nmp->nm_fhsize);
+ attributes.fsroot.handle = nmp->nm_fh;
+
+ ret = nfs_request(nmp, NFSPROC_FSINFO, (FAR const void *)&attributes,
+ (FAR void *)&fsp);
+ if (ret)
+ {
+ goto errout_with_semaphore;
+ }
+
+ nmp->nm_fattr = fsp.obj_attributes;
nfs_semgive(nmp);
return OK;
errout_with_semaphore:
nfs_semgive(nmp);
- return ERROR;
+ return ret;
}
/****************************************************************************
@@ -784,6 +812,8 @@ static int nfs_readdir(struct inode *mountpt, struct fs_dirent_s *dir)
goto errout_with_semaphore;
}
+ dir->fd_dir.d_name[0] = '\0';
+
if (np->nfsv3_type != NFDIR)
{
error = EPERM;
@@ -791,6 +821,7 @@ static int nfs_readdir(struct inode *mountpt, struct fs_dirent_s *dir)
}
dir->u.nfs.nd_direoffset = np->n_direofoffset;
+ dir->fd_dir.d_type = np->nfsv3_type;
/* First, check for hit on the EOF offset */
@@ -1606,7 +1637,7 @@ errout_with_semaphore:
/****************************************************************************
* Name: nfs_fsinfo
*
- * Description: Return information about a file or directory
+ * Description: Return information about root directory
*
****************************************************************************/
@@ -1647,7 +1678,7 @@ static int nfs_fsinfo(struct inode *mountpt, const char *relpath, struct stat *b
goto errout_with_semaphore;
}
- nmp->nm_head->n_fattr = fsp.obj_attributes;
+ nmp->nm_fattr = fsp.obj_attributes;
pref = fxdr_unsigned(uint32_t, fsp.fs_wtpref);
if (pref < nmp->nm_wsize)
{