From 7f70746d22efea1cec36e172debaaf4031230e96 Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 2 Mar 2012 02:11:31 +0000 Subject: Add the beginnings of NFS client support git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4443 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/fs/Makefile | 5 +- nuttx/fs/nfs/Make.defs | 50 ++++ nuttx/fs/nfs/rpc.h | 82 ++++++ nuttx/fs/nfs/rpc_idgen.h | 69 +++++ nuttx/fs/nfs/rpc_mbuf.h | 516 ++++++++++++++++++++++++++++++++ nuttx/fs/nfs/rpc_subr.c | 748 +++++++++++++++++++++++++++++++++++++++++++++++ nuttx/fs/nfs/rpc_types.h | 111 +++++++ nuttx/fs/nfs/rpc_v2.h | 117 ++++++++ nuttx/fs/nfs/xdr_subs.h | 103 +++++++ 9 files changed, 1799 insertions(+), 2 deletions(-) create mode 100644 nuttx/fs/nfs/Make.defs create mode 100644 nuttx/fs/nfs/rpc.h create mode 100644 nuttx/fs/nfs/rpc_idgen.h create mode 100644 nuttx/fs/nfs/rpc_mbuf.h create mode 100644 nuttx/fs/nfs/rpc_subr.c create mode 100644 nuttx/fs/nfs/rpc_types.h create mode 100644 nuttx/fs/nfs/rpc_v2.h create mode 100644 nuttx/fs/nfs/xdr_subs.h diff --git a/nuttx/fs/Makefile b/nuttx/fs/Makefile index f42ebcaaf..57a01c9c4 100644 --- a/nuttx/fs/Makefile +++ b/nuttx/fs/Makefile @@ -87,6 +87,7 @@ CSRCS += fs_mount.c fs_umount.c fs_fsync.c fs_unlink.c fs_rename.c \ include fat/Make.defs include romfs/Make.defs include nxffs/Make.defs +include nfs/Make.defs endif endif @@ -97,8 +98,8 @@ OBJS = $(AOBJS) $(COBJS) BIN = libfs$(LIBEXT) -SUBDIRS = mmap fat romfs nxffs -VPATH = mmap:fat:romfs:nxffs +SUBDIRS = mmap fat romfs nxffs:nfs +VPATH = mmap:fat:romfs:nxffs:nfs all: $(BIN) diff --git a/nuttx/fs/nfs/Make.defs b/nuttx/fs/nfs/Make.defs new file mode 100644 index 000000000..c0a19e8b2 --- /dev/null +++ b/nuttx/fs/nfs/Make.defs @@ -0,0 +1,50 @@ +############################################################################ +# Make.defs +# +# Copyright (C) 2012 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# 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 Nuttx 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 COPYRIGHT HOLDERS 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 +# COPYRIGHT OWNER 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. +# +############################################################################ + +ifeq ($(CONFIG_NFS),y) +# Files required for NFS file system support + +ASRCS += +CSRCS += + +# Files required for NFS RPC + +ASRCS += +CSRCS += rpc_subr.c + +# Argument for dependency checking + +NFSDEPPATH = --dep-path rpc +endif diff --git a/nuttx/fs/nfs/rpc.h b/nuttx/fs/nfs/rpc.h new file mode 100644 index 000000000..5fdd21b9f --- /dev/null +++ b/nuttx/fs/nfs/rpc.h @@ -0,0 +1,82 @@ +/**************************************************************************** + * 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 + * + * Leveraged from OpenBSD: + * + * Copyright (c) 1982, 1986, 1988, 1993 + * The Regents of the University of California. All rights reserved. + * + * 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_RPC_H +#define __FS_NFS_RPC_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* RPC definitions for the portmapper. */ + +#define PMAPPORT 111 +#define PMAPPROG 100000 +#define PMAPVERS 2 +#define PMAPPROC_NULL 0 +#define PMAPPROC_SET 1 +#define PMAPPROC_UNSET 2 +#define PMAPPROC_GETPORT 3 +#define PMAPPROC_DUMP 4 +#define PMAPPROC_CALLIT 5 + +/* RPC definitions for bootparamd. */ + +#define BOOTPARAM_PROG 100026 +#define BOOTPARAM_VERS 1 +#define BOOTPARAM_WHOAMI 1 +#define BOOTPARAM_GETFILE 2 + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +int krpc_call(struct sockaddr_in *, unsigned int, unsigned int, unsigned int, + struct mbuf **, struct mbuf **, int); +int krpc_portmap(struct sockaddr_in *, unsigned int, unsigned int, uint16_t *); + +struct mbuf *xdr_string_encode(char *, int); +struct mbuf *xdr_string_decode(struct mbuf *, char *, int *); +struct mbuf *xdr_inaddr_encode(struct in_addr *); +struct mbuf *xdr_inaddr_decode(struct mbuf *, struct in_addr *); + +#endif /* __FS_NFS_RPC_H */ diff --git a/nuttx/fs/nfs/rpc_idgen.h b/nuttx/fs/nfs/rpc_idgen.h new file mode 100644 index 000000000..42babc4d7 --- /dev/null +++ b/nuttx/fs/nfs/rpc_idgen.h @@ -0,0 +1,69 @@ + +/* $OpenBSD: idgen.h,v 1.2 2008/06/25 00:55:53 djm Exp $ */ + +/* + */ + +/**************************************************************************** + * fs/nfs/rpc_idgen.h + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2012 Jose Pablo Rojas Vargas. All rights reserved. + * Author: Jose Pablo Rojas Vargas + * + * Leveraged from OpenBSD: + * + * Copyright (c) 2008 Damien Miller + * + * Permission to use, copy, modify, and distribute this software for any + * purpose with or without fee is hereby granted, provided that the above + * copyright notice and this permission notice appear in all copies. + * + * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES + * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR + * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES + * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN + * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF + * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + * + ****************************************************************************/ + +#ifndef __FS_NFS_RPC_IDGEN_H +#define __FS_NFS_RPC_IDGEN_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define IDGEN32_ROUNDS 31 +#define IDGEN32_KEYLEN 32 +#define IDGEN32_REKEY_LIMIT 0x60000000 +#define IDGEN32_REKEY_TIME 600 + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +struct idgen32_ctx +{ + uint32_t id_counter; + uint32_t id_offset; + uint32_t id_hibit; + uint8_t id_key[IDGEN32_KEYLEN]; + time_t id_rekey_time; +}; + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +void idgen32_init(struct idgen32_ctx *); +uint32_t idgen32(struct idgen32_ctx *); + +#endif /* __FS_NFS_RPC_IDGEN_H */ + diff --git a/nuttx/fs/nfs/rpc_mbuf.h b/nuttx/fs/nfs/rpc_mbuf.h new file mode 100644 index 000000000..2077f1dbe --- /dev/null +++ b/nuttx/fs/nfs/rpc_mbuf.h @@ -0,0 +1,516 @@ +/**************************************************************************** + * fs/nfs/rpc_mbuf.h + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2012 Jose Pablo Rojas Vargas. All rights reserved. + * Author: Jose Pablo Rojas Vargas + * + * Leveraged from OpenBSD: + * + * Copyright (c) 1982, 1986, 1988, 1993 + * The Regents of the University of California. All rights reserved. + * + * 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_RPC_MBUF_H +#define __FS_NFS_RPC_MBUF_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ +/* Mbufs are of a single size, MSIZE (sys/param.h), which + * includes overhead. An mbuf may add a single "mbuf cluster" of size + * MCLBYTES (also in sys/param.h), which has no additional overhead + * and is used instead of the internal data area; this is done when + * at least MINCLSIZE of data must be stored. + */ + +#define MSIZE 256 +#define MCLSHIFT 11 /* Convert bytes to m_buf clusters */ + /* 2K cluster can hold Ether frame */ +#define MCLBYTES (1 << MCLSHIFT) /* Size of a m_buf cluster */ +#define MLEN (MSIZE - sizeof(struct m_hdr)) /* Normal data len */ +#define MHLEN (MLEN - sizeof(struct pkthdr)) /* Data len w/pkthdr */ + +/* smallest amount to put in cluster */ + +#define MINCLSIZE (MHLEN + MLEN + 1) +#define M_MAXCOMPRESS (MHLEN / 2) /* Max amount to copy for compression */ + +/* Macros for type conversion + * mtod(m,t) - convert mbuf pointer to data pointer of correct type + */ + +#define mtod(m,t) ((t)((m)->m_data)) + +/* pkthdr_pf.flags */ + +#define PF_TAG_GENERATED 0x01 +#define PF_TAG_TRANSLATE_LOCALHOST 0x04 +#define PF_TAG_DIVERTED 0x08 +#define PF_TAG_DIVERTED_PACKET 0x10 +#define PF_TAG_REROUTE 0x20 +#define PF_TAG_REFRAGMENTED 0x40 /* refragmented ipv6 packet */ + +/* mbuf flags */ + +#define M_EXT 0x0001 /* has associated external storage */ +#define M_PKTHDR 0x0002 /* start of record */ +#define M_EOR 0x0004 /* end of record */ +#define M_CLUSTER 0x0008 /* external storage is a cluster */ +#define M_PROTO1 0x0010 /* protocol-specific */ + +/* mbuf pkthdr flags, also in m_flags */ + +#define M_VLANTAG 0x0020 /* ether_vtag is valid */ +#define M_LOOP 0x0040 /* for Mbuf statistics */ +#define M_FILDROP 0x0080 /* dropped by bpf filter */ +#define M_BCAST 0x0100 /* send/received as link-level broadcast */ +#define M_MCAST 0x0200 /* send/received as link-level multicast */ +#define M_CONF 0x0400 /* payload was encrypted (ESP-transport) */ +#define M_AUTH 0x0800 /* payload was authenticated (AH or ESP auth) */ +#define M_TUNNEL 0x1000 /* IP-in-IP added by tunnel mode IPsec */ +#define M_AUTH_AH 0x2000 /* header was authenticated (AH) */ +#define M_COMP 0x4000 /* header was decompressed */ +#define M_LINK0 0x8000 /* link layer specific flag */ + +/* Flags copied when copying m_pkthdr */ + +#define M_COPYFLAGS (M_PKTHDR|M_EOR|M_PROTO1|M_BCAST|M_MCAST|M_CONF|M_COMP|\ + M_AUTH|M_LOOP|M_TUNNEL|M_LINK0|M_VLANTAG|M_FILDROP) + +/* Checksumming flags */ + +#define M_IPV4_CSUM_OUT 0x0001 /* IPv4 checksum needed */ +#define M_TCP_CSUM_OUT 0x0002 /* TCP checksum needed */ +#define M_UDP_CSUM_OUT 0x0004 /* UDP checksum needed */ +#define M_IPV4_CSUM_IN_OK 0x0008 /* IPv4 checksum verified */ +#define M_IPV4_CSUM_IN_BAD 0x0010 /* IPv4 checksum bad */ +#define M_TCP_CSUM_IN_OK 0x0020 /* TCP/IPv4 checksum verified */ +#define M_TCP_CSUM_IN_BAD 0x0040 /* TCP/IPv4 checksum bad */ +#define M_UDP_CSUM_IN_OK 0x0080 /* UDP/IPv4 checksum verified */ +#define M_UDP_CSUM_IN_BAD 0x0100 /* UDP/IPv4 checksum bad */ +#define M_ICMP_CSUM_OUT 0x0200 /* ICMP checksum needed */ +#define M_ICMP_CSUM_IN_OK 0x0400 /* ICMP checksum verified */ +#define M_ICMP_CSUM_IN_BAD 0x0800 /* ICMP checksum bad */ + +/* mbuf types */ + +#define MT_FREE 0 /* should be on free list */ +#define MT_DATA 1 /* dynamic (data) allocation */ +#define MT_HEADER 2 /* packet header */ +#define MT_SONAME 3 /* socket name */ +#define MT_SOOPTS 4 /* socket options */ +#define MT_FTABLE 5 /* fragment reassembly header */ +#define MT_CONTROL 6 /* extra-data protocol message */ +#define MT_OOBDATA 7 /* expedited data */ + +/* Flags to m_get/MGET */ + +#define M_DONTWAIT 0x0000 +#define M_WAIT 0x0001 + +/* mbuf allocation/deallocation macros: + * + * MGET(struct mbuf *m, int how, int type) + * allocates an mbuf and initializes it to contain internal data. + * + * MGETHDR(struct mbuf *m, int how, int type) + * allocates an mbuf and initializes it to contain a packet header + * and internal data. + */ + +#define MGET(m, how, type) m = m_get((how), (type)) +#define MGETHDR(m, how, type) m = m_gethdr((how), (type)) + +/* Macros for tracking external storage associated with an mbuf. + * + * Note: add and delete reference must be called at splnet(). + */ + +#ifdef CONFIG_DEBUG +# define MCLREFDEBUGN(m, file, line) do { \ + (m)->m_ext.ext_nfile = (file); \ + (m)->m_ext.ext_nline = (line); \ + } while (/* CONSTCOND */ 0) +# define MCLREFDEBUGO(m, file, line) do { \ + (m)->m_ext.ext_ofile = (file); \ + (m)->m_ext.ext_oline = (line); \ + } while (/* CONSTCOND */ 0) +#else +# define MCLREFDEBUGN(m, file, line) +# define MCLREFDEBUGO(m, file, line) +#endif + +#define MCLISREFERENCED(m) ((m)->m_ext.ext_nextref != (m)) + +#define MCLADDREFERENCE(o, n) do { \ + int ms = splnet(); \ + (n)->m_flags |= ((o)->m_flags & (M_EXT|M_CLUSTER)); \ + (n)->m_ext.ext_nextref = (o)->m_ext.ext_nextref; \ + (n)->m_ext.ext_prevref = (o); \ + (o)->m_ext.ext_nextref = (n); \ + (n)->m_ext.ext_nextref->m_ext.ext_prevref = (n); \ + splx(ms); \ + MCLREFDEBUGN((n), __FILE__, __LINE__); \ + } while (/* CONSTCOND */ 0) + +#define MCLINITREFERENCE(m) do { \ + (m)->m_ext.ext_prevref = (m); \ + (m)->m_ext.ext_nextref = (m); \ + MCLREFDEBUGO((m), __FILE__, __LINE__); \ + MCLREFDEBUGN((m), NULL, 0); \ + } while (/* CONSTCOND */ 0) + +/* Macros for mbuf external storage. + * + * MEXTADD adds pre-allocated external storage to + * a normal mbuf; the flag M_EXT is set. + * + * MCLGET allocates and adds an mbuf cluster to a normal mbuf; + * the flag M_EXT is set upon success. + */ + +#define MEXTADD(m, buf, size, type, free, arg) do { \ + (m)->m_data = (m)->m_ext.ext_buf = (caddr_t)(buf); \ + (m)->m_flags |= M_EXT; \ + (m)->m_flags &= ~M_CLUSTER; \ + (m)->m_ext.ext_size = (size); \ + (m)->m_ext.ext_free = (free); \ + (m)->m_ext.ext_arg = (arg); \ + (m)->m_ext.ext_type = (type); \ + MCLINITREFERENCE(m); \ +} while (/* CONSTCOND */ 0) + +#define MCLGET(m, how) (void) m_clget((m), (how), NULL, MCLBYTES) +#define MCLGETI(m, how, ifp, l) m_clget((m), (how), (ifp), (l)) + +/* MFREE(struct mbuf *m, struct mbuf *n) + * Free a single mbuf and associated external storage. + * Place the successor, if any, in n. + */ + +#define MFREE(m, n) n = m_free((m)) + +/* Move just m_pkthdr from from to to, + * remove M_PKTHDR and clean flags/tags for from. + */ + +#define M_MOVE_HDR(to, from) do { \ + (to)->m_pkthdr = (from)->m_pkthdr; \ + (from)->m_flags &= ~M_PKTHDR; \ + SLIST_INIT(&(from)->m_pkthdr.tags); \ +} while (/* CONSTCOND */ 0) + +/* MOVE mbuf pkthdr from from to to. + * from must have M_PKTHDR set, and to must be empty. + */ + +#define M_MOVE_PKTHDR(to, from) do { \ + (to)->m_flags = ((to)->m_flags & (M_EXT | M_CLUSTER)); \ + (to)->m_flags |= (from)->m_flags & M_COPYFLAGS; \ + M_MOVE_HDR((to), (from)); \ + if (((to)->m_flags & M_EXT) == 0) \ + (to)->m_data = (to)->m_pktdat; \ +} while (/* CONSTCOND */ 0) + +/* Set the m_data pointer of a newly-allocated mbuf (m_get/MGET) to place + * an object of the specified size at the end of the mbuf, longword aligned. + */ + +#define M_ALIGN(m, len) \ + (m)->m_data += (MLEN - (len)) &~ (sizeof(long) - 1) + +/* As above, for mbufs allocated with m_gethdr/MGETHDR + * or initialized by M_MOVE_PKTHDR. + */ + +#define MH_ALIGN(m, len) \ + (m)->m_data += (MHLEN - (len)) &~ (sizeof(long) - 1) + +/* Determine if an mbuf's data area is read-only. This is true for + * non-cluster external storage and for clusters that are being + * referenced by more than one mbuf. + */ + +#define M_READONLY(m) \ + (((m)->m_flags & M_EXT) != 0 && \ + (((m)->m_flags & M_CLUSTER) == 0 || MCLISREFERENCED(m))) + +/* Compute the amount of space available + * before the current start of data in an mbuf. + */ + +#define M_LEADINGSPACE(m) m_leadingspace(m) + +/* Compute the amount of space available + * after the end of data in an mbuf. + */ + +#define M_TRAILINGSPACE(m) m_trailingspace(m) + +/* Arrange to prepend space of size plen to mbuf m. + * If a new mbuf must be allocated, how specifies whether to wait. + * If how is M_DONTWAIT and allocation fails, the original mbuf chain + * is freed and m is set to NULL. + */ + +#define M_PREPEND(m, plen, how) \ + (m) = m_prepend((m), (plen), (how)) + +/* Length to m_copy to copy all */ + +#define M_COPYALL 1000000000 + +/* Compatibility with 4.3 */ + +#define m_copy(m, o, l) m_copym((m), (o), (l), M_DONTWAIT) + +/* Packet tag types */ + +#define PACKET_TAG_IPSEC_IN_DONE 0x0001 /* IPsec applied, in */ +#define PACKET_TAG_IPSEC_OUT_DONE 0x0002 /* IPsec applied, out */ +#define PACKET_TAG_IPSEC_IN_CRYPTO_DONE 0x0004 + /* NIC IPsec crypto done */ +#define PACKET_TAG_IPSEC_OUT_CRYPTO_NEEDED 0x0008 /* NIC IPsec crypto + * req'ed */ +#define PACKET_TAG_IPSEC_PENDING_TDB 0x0010 /* Reminder to do IPsec */ +#define PACKET_TAG_BRIDGE 0x0020 /* Bridge processing done */ +#define PACKET_TAG_GIF 0x0040 + /* GIF processing done */ +#define PACKET_TAG_GRE 0x0080 + /* GRE processing done */ +#define PACKET_TAG_DLT 0x0100 + /* data link layer type */ +#define PACKET_TAG_PF_DIVERT 0x0200 /* pf(4) diverted packet */ +#define PACKET_TAG_PIPEX 0x0400 /* pipex context XXX */ +#define PACKET_TAG_PF_REASSEMBLED 0x0800 /* pf reassembled ipv6 packet */ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/* Packet tags structure */ + +struct m_tag +{ + SLIST_ENTRY(m_tag) m_tag_link; /* List of packet tags */ + uint16_t m_tag_id; /* Tag ID */ + uint16_t m_tag_len; /* Length of data */ +}; + +/* Header at beginning of each mbuf: */ + +struct m_hdr +{ + struct mbuf *mh_next; /* Next buffer in chain */ + struct mbuf *mh_nextpkt; /* Next chain in queue/record */ + char *mh_data; /* Location of data */ + unsigned int mh_len; /* Amount of data in this mbuf */ + short mh_type; /* Type of data in this mbuf */ + unsigned short mh_flags; /* Flags; see below */ +}; + +/* pf stuff */ + +struct pkthdr_pf +{ + void *hdr; /* saved hdr pos in mbuf, for ECN */ + void *statekey; /* PF stackside statekey */ + uint32_t qid; /* Queue id */ + uint16_t tag; /* Tag id */ + uint8_t flags; + uint8_t routed; + uint8_t prio; + uint8_t pad[3]; +}; + +/* Record/packet header in first mbuf of chain; valid if M_PKTHDR set */ + +struct pkthdr +{ + struct ifnet *rcvif; /* rcv interface */ + SLIST_HEAD(packet_tags, m_tag) tags; /* List of packet tags */ + int len; /* Total packet length */ + uint16_t tagsset; /* mtags attached */ + uint16_t pad; + uint16_t csum_flags; /* Checksum flags */ + uint16_t ether_vtag; /* Ethernet 802.1p+Q vlan tag */ + unsigned int rdomain; /* Routing domain id */ + struct pkthdr_pf pf; +}; + +/* Description of external storage mapped into mbuf, valid if M_EXT set */ + +struct mbuf_ext +{ + char *ext_buf; /* start of buffer */ + /* free routine if not the usual */ + // void (*ext_free)(char*, unsigned int, void *); + // void *ext_arg; /* argument for ext_free */ + // unsigned int ext_size; /* size of buffer, for ext_free */ + int ext_type; + struct ifnet *ext_ifp; + int ext_backend; /* backend pool the storage came from */ + struct mbuf *ext_nextref; + struct mbuf *ext_prevref; +#ifdef CONFIG_DEBUG + const char *ext_ofile; + const char *ext_nfile; + int ext_oline; + int ext_nline; +#endif + }; + +struct mbuf + { + struct m_hdr m_hdr; + union + { + struct + { + struct pkthdr MH_pkthdr; /* M_PKTHDR set */ + union + { + struct mbuf_ext MH_ext; /* M_EXT set */ + char MH_databuf[MHLEN]; + } MH_dat; + } MH; + char M_databuf[MLEN]; /* !M_PKTHDR, !M_EXT */ + } M_dat; + }; + +#define m_next m_hdr.mh_next +#define m_len m_hdr.mh_len +#define m_data m_hdr.mh_data +#define m_type m_hdr.mh_type +#define m_flags m_hdr.mh_flags +#define m_nextpkt m_hdr.mh_nextpkt +#define m_act m_nextpkt +#define m_pkthdr M_dat.MH.MH_pkthdr +#define m_ext M_dat.MH.MH_dat.MH_ext +#define m_pktdat M_dat.MH.MH_dat.MH_databuf +#define m_dat M_dat.M_databuf + +/* Mbuf statistics. + * For statistics related to mbuf and cluster allocations, see also the + * pool headers (mbpool and mclpool). + */ + +struct mbstat +{ + unsigned long _m_spare; /* formerly m_mbufs */ + unsigned long _m_spare1; /* formerly m_clusters */ + unsigned long _m_spare2; /* spare field */ + unsigned long _m_spare3; /* formely m_clfree - free clusters */ + unsigned long m_drops; /* times failed to find space */ + unsigned long m_wait; /* times waited for space */ + unsigned long m_drain; /* times drained protocols for space */ + unsigned short m_mtypes[256]; /* type specific mbuf allocations */ +}; + +struct mclsizes +{ + unsigned int size; + unsigned int hwm; +}; + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +extern struct mbstat mbstat; +extern int nmbclust; /* limit on the # of clusters */ +extern int mblowat; /* mbuf low water mark */ +extern int mcllowat; /* mbuf cluster low water mark */ +extern int max_linkhdr; /* largest link-level header */ +extern int max_protohdr; /* largest protocol header */ +extern int max_hdr; /* largest link+protocol header */ +extern int max_datalen; /* MHLEN - max_hdr */ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +void mbinit(void); +struct mbuf *m_copym2(struct mbuf *, int, int, int); +struct mbuf *m_copym(struct mbuf *, int, int, int); +struct mbuf *m_free(struct mbuf *); +struct mbuf *m_free_unlocked(struct mbuf *); +struct mbuf *m_get(int, int); +struct mbuf *m_getclr(int, int); +struct mbuf *m_gethdr(int, int); +struct mbuf *m_inithdr(struct mbuf *); +int m_defrag(struct mbuf *, int); +struct mbuf *m_prepend(struct mbuf *, int, int); +struct mbuf *m_pulldown(struct mbuf *, int, int, int *); +struct mbuf *m_pullup(struct mbuf *, int); +struct mbuf *m_split(struct mbuf *, int, int); +struct mbuf *m_inject(struct mbuf *, int, int, int); +struct mbuf *m_getptr(struct mbuf *, int, int *); +int m_leadingspace(struct mbuf *); +int m_trailingspace(struct mbuf *); +struct mbuf *m_clget(struct mbuf *, int, struct ifnet *, unsigned int); +void m_clsetwms(struct ifnet *, unsigned int, unsigned int, unsigned int); +int m_cldrop(struct ifnet *, int); +void m_clcount(struct ifnet *, int); +void m_cluncount(struct mbuf *, int); +void m_clinitifp(struct ifnet *); +void m_adj(struct mbuf *, int); +int m_copyback(struct mbuf *, int, int, const void *, int); +void m_freem(struct mbuf *); +void m_reclaim(void *, int); +void m_copydata(struct mbuf *, int, int, caddr_t); +void m_cat(struct mbuf *, struct mbuf *); +struct mbuf *m_devget(char *, int, int, struct ifnet *, + void (*)(const void *, void *, size_t)); +void m_zero(struct mbuf *); +int m_apply(struct mbuf *, int, int, + int (*)(caddr_t, caddr_t, unsigned int), caddr_t); +int m_dup_pkthdr(struct mbuf *, struct mbuf *, int); + +/* Packet tag routines */ + +struct m_tag *m_tag_get(int, int, int); +void m_tag_prepend(struct mbuf *, struct m_tag *); +void m_tag_delete(struct mbuf *, struct m_tag *); +void m_tag_delete_chain(struct mbuf *); +struct m_tag *m_tag_find(struct mbuf *, int, struct m_tag *); +struct m_tag *m_tag_copy(struct m_tag *, int); +int m_tag_copy_chain(struct mbuf *, struct mbuf *, int); +void m_tag_init(struct mbuf *); +struct m_tag *m_tag_first(struct mbuf *); +struct m_tag *m_tag_next(struct mbuf *, struct m_tag *); + +#endif /* __FS_NFS_RPC_MBUF_H */ + diff --git a/nuttx/fs/nfs/rpc_subr.c b/nuttx/fs/nfs/rpc_subr.c new file mode 100644 index 000000000..539a48576 --- /dev/null +++ b/nuttx/fs/nfs/rpc_subr.c @@ -0,0 +1,748 @@ +/**************************************************************************** + * fs/nfs/rpc_subr.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2012 Jose Pablo Rojas Vargas. All rights reserved. + * Author: Jose Pablo Rojas Vargas + * + * Leveraged from OpenBSD: + * + * Copyright (c) 1995 Gordon Ross, Adam Glass + * Copyright (c) 1992 Regents of the University of California. + * All rights reserved. + * + * This software was developed by the Computer Systems Engineering group + * at Lawrence Berkeley Laboratory under DARPA contract BG 91-66 and + * contributed to Berkeley. + * + * 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. All advertising materials mentioning features or use of this software + * must display the following acknowledgement: + * This product includes software developed by the University of + * California, Lawrence Berkeley Laboratory and its contributors. + * 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. + * + * partially based on: + * libnetboot/rpc.c + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include +#include +#include +#include +#include + +#include "rpc_mbuf.h" +#include "rpc_types.h" +#include "rpc_v2.h" +#include "rpc.h" +#include "xdr_subs.h" + +#include "rpc_idgen.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define MIN_REPLY_HDR 16 /* xid, dir, astat, errno */ + +/* What is the longest we will wait before re-sending a request? + * Note this is also the frequency of "RPC timeout" messages. + * The re-send loop count sup linearly to this maximum, so the + * first complaint will happen after (1+2+3+4+5)=15 seconds. + */ + +#define MAX_RESEND_DELAY 5 /* seconds */ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/* Generic RPC headers */ + +struct auth_info +{ + uint32_t authtype; /* auth type */ + uint32_t authlen; /* auth length */ +}; + +struct auth_unix +{ + int32_t ua_time; + int32_t ua_hostname; /* null */ + int32_t ua_uid; + int32_t ua_gid; + int32_t ua_gidlist; /* null */ +}; + +struct rpc_call +{ + uint32_t rp_xid; /* request transaction id */ + int32_t rp_direction; /* call direction (0) */ + uint32_t rp_rpcvers; /* rpc version (2) */ + uint32_t rp_prog; /* program */ + uint32_t rp_vers; /* version */ + uint32_t rp_proc; /* procedure */ + struct auth_info rpc_auth; + struct auth_unix rpc_unix; + struct auth_info rpc_verf; +}; + +struct rpc_reply +{ + uint32_t rp_xid; /* request transaction id */ + int32_t rp_direction; /* call direction (1) */ + int32_t rp_astatus; /* accept status (0: accepted) */ + union + { + uint32_t rpu_errno; + struct + { + struct auth_info rok_auth; + uint32_t rok_status; + } rpu_rok; + } rp_u; +}; + +#define rp_errno rp_u.rpu_errno +#define rp_auth rp_u.rpu_rok.rok_auth +#define rp_status rp_u.rpu_rok.rok_status + +/* String representation for RPC. */ + +struct xdr_string +{ + uint32_t len; /* length without null or padding */ + char data[4]; /* data (longer, of course) */ + /* data is padded to a long-word boundary */ +}; + +/* Inet address in RPC messages (Note, really four ints, NOT chars. Blech.) */ + +struct xdr_inaddr +{ + uint32_t atype; + uint32_t addr[4]; +}; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/* Return an unpredictable XID. */ + +uint32_t krpc_get_xid(void) +{ + static struct idgen32_ctx krpc_xid_ctx; + static int called = 0; + + if (!called) + { + called = 1; + idgen32_init(&krpc_xid_ctx); + } + return idgen32(&krpc_xid_ctx); +} + +/* Call portmap to lookup a port number for a particular rpc program + * Returns non-zero error on failure. + */ + +int krpc_portmap(struct sockaddr_in *sin, unsigned int prog, unsigned int vers, + uint16_t * portp) +{ + struct sdata + { + uint32_t prog; /* call program */ + uint32_t vers; /* call version */ + uint32_t proto; /* call protocol */ + uint32_t port; /* call port (unused) */ + } *sdata; + struct rdata + { + uint16_t pad; + uint16_t port; + } *rdata; + struct mbuf *m; + int error; + + /* The portmapper port is fixed. */ + + if (prog == PMAPPROG) + { + *portp = htons(PMAPPORT); + return 0; + } + + // m = m_get(M_WAIT, MT_DATA); + m = kmalloc(sizeof(*sdata)); + m->m_type = MT_DATA; + m->m_next = (struct mbuf *)NULL; + m->m_nextpkt = (struct mbuf *)NULL; + m->m_data = m->m_dat; + m->m_flags = 0; + + sdata = mtod(m, struct sdata *); + m->m_len = sizeof(*sdata); + + /* Do the RPC to get it. */ + + sdata->prog = txdr_unsigned(prog); + sdata->vers = txdr_unsigned(vers); + sdata->proto = txdr_unsigned(IPPROTO_UDP); + sdata->port = 0; + + sin->sin_port = htons(PMAPPORT); + error = krpc_call(sin, PMAPPROG, PMAPVERS, PMAPPROC_GETPORT, &m, NULL, -1); + if (error) + { + return error; + } + + if (m->m_len < sizeof(*rdata)) + { + m = m_pullup(m, sizeof(*rdata)); + if (m == NULL) + return ENOBUFS; + } + + rdata = mtod(m, struct rdata *); + *portp = rdata->port; + + kfree(m); + return 0; +} + +/* Do a remote procedure call (RPC) and wait for its reply. + * If from_p is non-null, then we are doing broadcast, and + * the address from whence the response came is saved there. + * data: input/output + * from_p: output + */ + +int krpc_call(struct sockaddr_in *sa, unsigned int prog, unsigned int vers, + unsigned int func, struct mbuf **data, struct mbuf **from_p, + int retries) +{ + struct socket *so; + struct sockaddr_in *sin; + struct mbuf *m, *nam, *mhead, *from, *mopt; + struct rpc_call *call; + struct rpc_reply *reply; + struct uio auio; + int error, rcvflg, timo, secs, len; + static uint32_t xid = 0; + int *ip; + struct timeval *tv; + + /* Validate address family. + * Sorry, this is INET specific... + */ + + if (sa->sin_family != AF_INET) + { + return (EAFNOSUPPORT); + } + + /* Free at end if not null. */ + + nam = mhead = NULL; + from = NULL; + + /* Create socket and set its receive timeout. */ + + if ((error = socket(AF_INET, SOCK_DGRAM, 0))) + { + goto out; + } + + // m = m_get(M_WAIT, MT_SOOPTS); + m = kmalloc(sizeof(*tv)); + m->m_type = MT_SOOPTS; + m->m_next = (struct mbuf *)NULL; + m->m_nextpkt = (struct mbuf *)NULL; + m->m_data = m->m_dat; + m->m_flags = 0; + + tv = mtod(m, struct timeval *); + m->m_len = sizeof(*tv); + tv->tv_sec = 1; + tv->tv_usec = 0; + + if ((error = sosetopt(so, SOL_SOCKET, SO_RCVTIMEO, m))) + { + goto out; + } + + /* Enable broadcast if necessary. */ + + if (from_p) + { + int32_t *on; + // m = m_get(M_WAIT, MT_SOOPTS); + m = kmalloc(sizeof(*on)); + m->m_type = MT_SOOPTS; + m->m_next = (struct mbuf *)NULL; + m->m_nextpkt = (struct mbuf *)NULL; + m->m_data = m->m_dat; + m->m_flags = 0; + + on = mtod(m, int32_t *); + m->m_len = sizeof(*on); + *on = 1; + + if ((error = sosetopt(error, SOL_SOCKET, SO_BROADCAST, m))) + { + goto out; + } + } + + /* Bind the local endpoint to a reserved port, + * because some NFS servers refuse requests from + * non-reserved (non-privileged) ports. + */ + + // MGET(mopt, M_WAIT, MT_SOOPTS); + mopt = kmalloc(sizeof(int)); + mopt->m_type = MT_SOOPTS; + mopt->m_next = (struct mbuf *)NULL; + mopt->m_nextpkt = (struct mbuf *)NULL; + mopt->m_data = mopt->m_dat; + mopt->m_flags = 0; + + mopt->m_len = sizeof(int); + ip = mtod(mopt, int *); + *ip = 2; + error = sosetopt(so, IPPROTO_IP, 19, mopt); + if (error) + { + goto out; + } + + // MGET(m, M_WAIT, MT_SONAME); + m = kmalloc(sizeof(struct sockaddr_in)); + m->m_type = MT_SONAME; + m->m_next = (struct mbuf *)NULL; + m->m_nextpkt = (struct mbuf *)NULL; + m->m_data = m->m_dat; + m->m_flags = 0; + + sin = mtod(m, struct sockaddr_in *); + sin->sin_len = m->m_len = sizeof(struct sockaddr_in); + sin->sin_family = AF_INET; + sin->sin_addr.s_addr = INADDR_ANY; + sin->sin_port = htons(0); + error = sobind(so, m, &proc0); + kfree(m); + // m_freem(m); + if (error) + { + printf("bind failed\n"); + goto out; + } + + // MGET(mopt, M_WAIT, MT_SOOPTS); + mopt = kmalloc(sizeof(int)); + mopt->m_type = MT_SOOPTS; + mopt->m_next = (struct mbuf *)NULL; + mopt->m_nextpkt = (struct mbuf *)NULL; + mopt->m_data = mopt->m_dat; + mopt->m_flags = 0; + + mopt->m_len = sizeof(int); + ip = mtod(mopt, int *); + *ip = 0; + error = sosetopt(so, IPPROTO_IP, 19, mopt); + if (error) + { + goto out; + } + + /* Setup socket address for the server. */ + + // nam = m_get(M_WAIT, MT_SONAME); + nam = kmalloc(sizeof(struct sockaddr_in)); + nam->m_type = MT_SONAME; + nam->m_next = (struct mbuf *)NULL; + nam->m_nextpkt = (struct mbuf *)NULL; + nam->m_data = nam->m_dat; + nam->m_flags = 0; + + sin = mtod(nam, struct sockaddr_in *); + bcopy((caddr_t) sa, (caddr_t) sin, (nam->m_len = sa->sin_len)); + + /* Prepend RPC message header. */ + + mhead = m_gethdr(M_WAIT, MT_DATA); + mhead->m_next = *data; + call = mtod(mhead, struct rpc_call *); + mhead->m_len = sizeof(*call); + bzero((caddr_t) call, sizeof(*call)); + + /* rpc_call part */ + + xid = krpc_get_xid(); + call->rp_xid = txdr_unsigned(xid); + + /* call->rp_direction = 0; */ + + call->rp_rpcvers = txdr_unsigned(2); + call->rp_prog = txdr_unsigned(prog); + call->rp_vers = txdr_unsigned(vers); + call->rp_proc = txdr_unsigned(func); + + /* rpc_auth part (auth_unix as root) */ + + call->rpc_auth.authtype = txdr_unsigned(RPCAUTH_UNIX); + call->rpc_auth.authlen = txdr_unsigned(sizeof(struct auth_unix)); + + /* rpc_verf part (auth_null) */ + + call->rpc_verf.authtype = 0; + call->rpc_verf.authlen = 0; + + /* Setup packet header */ + + len = 0; + m = mhead; + while (m) + { + len += m->m_len; + m = m->m_next; + } + + mhead->m_pkthdr.len = len; + mhead->m_pkthdr.rcvif = NULL; + + /* Send it, repeatedly, until a reply is received, + * but delay each re-send by an increasing amount. + * If the delay hits the maximum, start complaining. + */ + + for (timo = 0; retries; retries--) + { + /* Send RPC request (or re-send). */ + + m = m_copym(mhead, 0, M_COPYALL, M_WAIT); + if (m == NULL) + { + error = ENOBUFS; + goto out; + } + + error = sosend(so, nam, NULL, m, NULL, 0); + if (error) + { + printf("krpc_call: sosend: %d\n", error); + goto out; + } + + m = NULL; + + /* Determine new timeout. */ + + if (timo < MAX_RESEND_DELAY) + { + timo++; + } + else + { + printf("RPC timeout for server %s (0x%x) prog %u\n", + inet_ntoa(sin->sin_addr), ntohl(sin->sin_addr.s_addr), prog); + } + + /* Wait for up to timo seconds for a reply. + * The socket receive timeout was set to 1 second. + */ + + secs = timo; + while (secs > 0) + { + if (from) + { + m_freem(from); + from = NULL; + } + + if (m) + { + m_freem(m); + m = NULL; + } + + auio.uio_resid = len = 1 << 16; + auio.uio_procp = NULL; + rcvflg = 0; + + error = soreceive(so, &from, &auio, &m, NULL, &rcvflg, 0); + if (error == EWOULDBLOCK) + { + secs--; + continue; + } + + if (error) + { + goto out; + } + + len -= auio.uio_resid; + + /* Does the reply contain at least a header? */ + + if (len < MIN_REPLY_HDR) + { + continue; + } + + if (m->m_len < MIN_REPLY_HDR) + { + continue; + } + + reply = mtod(m, struct rpc_reply *); + + /* Is it the right reply? */ + + if (reply->rp_direction != txdr_unsigned(RPC_REPLY)) + { + continue; + } + + if (reply->rp_xid != txdr_unsigned(xid)) + { + continue; + } + + /* Was RPC accepted? (authorization OK) */ + + if (reply->rp_astatus != 0) + { + error = fxdr_unsigned(uint32_t, reply->rp_errno); + printf("rpc denied, error=%d\n", error); + continue; + } + + /* Did the call succeed? */ + + if (reply->rp_status != 0) + { + error = fxdr_unsigned(uint32_t, reply->rp_status); + printf("rpc denied, status=%d\n", error); + continue; + } + + goto gotreply; /* break two levels */ + } + } + + error = ETIMEDOUT; + goto out; + +gotreply: + + /* Get RPC reply header into first mbuf, + * get its length, then strip it off. + */ + + len = sizeof(*reply); + if (m->m_len < len) + { + m = m_pullup(m, len); + if (m == NULL) + { + error = ENOBUFS; + goto out; + } + } + + reply = mtod(m, struct rpc_reply *); + if (reply->rp_auth.authtype != 0) + { + len += fxdr_unsigned(uint32_t, reply->rp_auth.authlen); + len = (len + 3) & ~3; /* XXX? */ + } + + m_adj(m, len); + + /* result */ + + *data = m; + if (from_p && error == 0) + { + *from_p = from; + from = NULL; + } + +out: + if (nam) + { + m_freem(nam); + } + + if (mhead) + { + m_freem(mhead); + } + + if (from) + { + m_freem(from); + } + + soclose(so); + return error; +} + +/* eXternal Data Representation routines. (but with non-standard args...) */ + +struct mbuf *xdr_string_encode(char *str, int len) +{ + struct mbuf *m; + struct xdr_string *xs; + int dlen; /* padded string length */ + int mlen; /* message length */ + + dlen = (len + 3) & ~3; + mlen = dlen + 4; + + if (mlen > MCLBYTES) /* If too big, we just can't do it. */ + { + return (NULL); + } + + m = m_get(M_WAIT, MT_DATA); + if (mlen > MLEN) + { + MCLGET(m, M_WAIT); + if ((m->m_flags & M_EXT) == 0) + { + (void)m_free(m); /* There can be only one. */ + return (NULL); + } + } + + xs = mtod(m, struct xdr_string *); + m->m_len = mlen; + xs->len = txdr_unsigned(len); + strncpy(xs->data, str, len); + return (m); +} + +struct mbuf *xdr_string_decode(struct mbuf *m, char *str, int *len_p) +{ + struct xdr_string *xs; + int mlen; /* message length */ + int slen; /* string length */ + + if (m->m_len < 4) + { + m = m_pullup(m, 4); + if (m == NULL) + return (NULL); + } + + xs = mtod(m, struct xdr_string *); + slen = fxdr_unsigned(uint32_t, xs->len); + mlen = 4 + ((slen + 3) & ~3); + + if (slen > *len_p) + { + slen = *len_p; + } + + if (slen > m->m_pkthdr.len) + { + m_freem(m); + return (NULL); + } + + m_copydata(m, 4, slen, str); + m_adj(m, mlen); + + str[slen] = '\0'; + *len_p = slen; + + return (m); +} + +struct mbuf *xdr_inaddr_encode(struct in_addr *ia) +{ + struct mbuf *m; + struct xdr_inaddr *xi; + uint8_t *cp; + uint32_t *ip; + + m = m_get(M_WAIT, MT_DATA); + xi = mtod(m, struct xdr_inaddr *); + m->m_len = sizeof(*xi); + xi->atype = txdr_unsigned(1); + ip = xi->addr; + cp = (uint8_t *) & ia->s_addr; + *ip++ = txdr_unsigned(*cp++); + *ip++ = txdr_unsigned(*cp++); + *ip++ = txdr_unsigned(*cp++); + *ip++ = txdr_unsigned(*cp++); + + return (m); +} + +struct mbuf *xdr_inaddr_decode(struct mbuf *m, struct in_addr *ia) +{ + struct xdr_inaddr *xi; + uint8_t *cp; + uint32_t *ip; + + if (m->m_len < sizeof(*xi)) + { + m = m_pullup(m, sizeof(*xi)); + if (m == NULL) + return (NULL); + } + + xi = mtod(m, struct xdr_inaddr *); + if (xi->atype != txdr_unsigned(1)) + { + ia->s_addr = INADDR_ANY; + goto out; + } + + ip = xi->addr; + cp = (uint8_t *) & ia->s_addr; + *cp++ = fxdr_unsigned(uint8_t, *ip++); + *cp++ = fxdr_unsigned(uint8_t, *ip++); + *cp++ = fxdr_unsigned(uint8_t, *ip++); + *cp++ = fxdr_unsigned(uint8_t, *ip++); + +out: + m_adj(m, sizeof(*xi)); + return (m); +} diff --git a/nuttx/fs/nfs/rpc_types.h b/nuttx/fs/nfs/rpc_types.h new file mode 100644 index 000000000..e1ec76e6a --- /dev/null +++ b/nuttx/fs/nfs/rpc_types.h @@ -0,0 +1,111 @@ +/**************************************************************************** + * fs/nfs/rpc_types.h + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2012 Jose Pablo Rojas Vargas. All rights reserved. + * Author: Jose Pablo Rojas Vargas + * + * Leveraged from OpenBSD: + * + * Copyright (c) 1982, 1986, 1988, 1993 + * The Regents of the University of California. All rights reserved. + * + * 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_RPC_TYPES_H +#define __FS_NFS_RPC_TYPES_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +struct lock +{ + int dummy; +}; + +struct iovec +{ + void *iov_base; /* Base address. */ + size_t iov_len; /* Length. */ +}; + +enum uio_rw +{ + UIO_READ, + UIO_WRITE +}; + +/* Segment flag values. */ + +enum uio_seg +{ + UIO_USERSPACE, /* from user data space */ + UIO_SYSSPACE /* from system space */ +}; + +struct uio +{ + struct iovec *uio_iov; /* scatter/gather list */ + int uio_iovcnt; /* length of scatter/gather list */ + off_t uio_offset; /* offset in target object */ + ssize_t uio_resid; /* remaining bytes to process */ + enum uio_seg uio_segflg; /* address space */ + enum uio_rw uio_rw; /* operation */ + struct thread *uio_procp; /* owner */ +}; + +struct componentname +{ + /* Arguments to lookup. */ + + unsigned long cn_nameiop; /* namei operation */ + uint64_t cn_flags; /* flags to namei */ + struct thread *cn_thread; /* thread requesting lookup */ + struct ucred *cn_cred; /* credentials */ + int cn_lkflags; /* Lock flags LK_EXCLUSIVE or LK_SHARED */ + + /* Shared between lookup and commit routines. */ + + char *cn_pnbuf; /* pathname buffer */ + char *cn_nameptr; /* pointer to looked up name */ + long cn_namelen; /* length of looked up component */ + long cn_consume; /* chars to consume in lookup() */ +}; + +#endif /* __FS_NFS_RPC_TYPES_H */ diff --git a/nuttx/fs/nfs/rpc_v2.h b/nuttx/fs/nfs/rpc_v2.h new file mode 100644 index 000000000..3e4f215ff --- /dev/null +++ b/nuttx/fs/nfs/rpc_v2.h @@ -0,0 +1,117 @@ +/**************************************************************************** + * fs/nfs/rpc_types.h + * Definitions for Sun RPC Version 2, from + * "RPC: Remote Procedure Call Protocol Specification" RFC1057 + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2012 Jose Pablo Rojas Vargas. All rights reserved. + * Author: Jose Pablo Rojas Vargas + * + * 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_RPC_V2_H +#define __FS_NFS_RPC_V2_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Version # */ + +#define RPC_VER2 2 + +/* Authentication */ + +#define RPCAUTH_NULL 0 +#define RPCAUTH_UNIX 1 +#define RPCAUTH_SHORT 2 +#define RPCAUTH_KERB4 4 +#define RPCAUTH_MAXSIZ 400 +#define RPCVERF_MAXSIZ 12 + /* For Kerb, can actually be 400 */ +#define RPCAUTH_UNIXGIDS 16 + +/* Constants associated with authentication flavours. */ + +#define RPCAKN_FULLNAME 0 +#define RPCAKN_NICKNAME 1 + +/* Rpc Constants */ + +#define RPC_CALL 0 +#define RPC_REPLY 1 +#define RPC_MSGACCEPTED 0 +#define RPC_MSGDENIED 1 +#define RPC_PROGUNAVAIL 1 +#define RPC_PROGMISMATCH 2 +#define RPC_PROCUNAVAIL 3 +#define RPC_GARBAGE 4 + +#define RPC_MISMATCH 0 +#define RPC_AUTHERR 1 + +/* Authentication failures */ + +#define AUTH_BADCRED 1 +#define AUTH_REJECTCRED 2 +#define AUTH_BADVERF 3 +#define AUTH_REJECTVERF 4 +#define AUTH_TOOWEAK 5 + +/* Sizes of rpc header parts */ + +#define RPC_SIZ 24 +#define RPC_REPLYSIZ 28 + +/* RPC Prog definitions */ + +#define RPCPROG_MNT 100005 +#define RPCMNT_VER1 1 +#define RPCMNT_VER3 3 +#define RPCMNT_MOUNT 1 +#define RPCMNT_DUMP 2 +#define RPCMNT_UMOUNT 3 +#define RPCMNT_UMNTALL 4 +#define RPCMNT_EXPORT 5 +#define RPCMNT_NAMELEN 255 +#define RPCMNT_PATHLEN 1024 +#define RPCPROG_NFS 100003 + +#endif /* __FS_NFS_RPC_V2_H */ diff --git a/nuttx/fs/nfs/xdr_subs.h b/nuttx/fs/nfs/xdr_subs.h new file mode 100644 index 000000000..97bb24aee --- /dev/null +++ b/nuttx/fs/nfs/xdr_subs.h @@ -0,0 +1,103 @@ +/**************************************************************************** + * fs/nfs/rpc_types.h + * Definitions for Sun RPC Version 2, from + * "RPC: Remote Procedure Call Protocol Specification" RFC1057 + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2012 Jose Pablo Rojas Vargas. All rights reserved. + * Author: Jose Pablo Rojas Vargas + * + * 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_XDR_SUBS_H +#define __FS_NFS_XDR_SUBS_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ +/* Macros used for conversion to/from xdr representation by nfs... + * These use the MACHINE DEPENDENT routines ntohl, htonl + * As defined by "XDR: External Data Representation Standard" RFC1014 + * + * To simplify the implementation, we use ntohl/htonl even on big-endian + * machines, and count on them being `#define'd away. Some of these + * might be slightly more efficient as quad_t copies on a big-endian, + * but we cannot count on their alignment anyway. + */ + +#define fxdr_unsigned(t, v) ((t)ntohl((int32_t)(v))) +#define txdr_unsigned(v) (htonl((int32_t)(v))) + +#define fxdr_nfsv2time(f, t) { \ + (t)->tv_sec = ntohl(((struct nfsv2_time *)(f))->nfsv2_sec); \ + if (((struct nfsv2_time *)(f))->nfsv2_usec != 0xffffffff) \ + (t)->tv_nsec = 1000 * ntohl(((struct nfsv2_time *)(f))->nfsv2_usec); \ + else \ + (t)->tv_nsec = 0; \ +} + +#define txdr_nfsv2time(f, t) { \ + ((struct nfsv2_time *)(t))->nfsv2_sec = htonl((f)->tv_sec); \ + if ((f)->tv_nsec != -1) \ + ((struct nfsv2_time *)(t))->nfsv2_usec = htonl((f)->tv_nsec / 1000); \ + else \ + ((struct nfsv2_time *)(t))->nfsv2_usec = 0xffffffff; \ +} + +#define fxdr_nfsv3time(f, t) { \ + (t)->tv_sec = ntohl(((struct nfsv3_time *)(f))->nfsv3_sec); \ + (t)->tv_nsec = ntohl(((struct nfsv3_time *)(f))->nfsv3_nsec); \ +} + +#define txdr_nfsv3time(f, t) { \ + ((struct nfsv3_time *)(t))->nfsv3_sec = htonl((f)->tv_sec); \ + ((struct nfsv3_time *)(t))->nfsv3_nsec = htonl((f)->tv_nsec); \ +} + +#define fxdr_hyper(f) \ + ((((u_quad_t)ntohl(((u_int32_t *)(f))[0])) << 32) | \ + (u_quad_t)(ntohl(((u_int32_t *)(f))[1]))) + +#define txdr_hyper(f, t) { \ + ((u_int32_t *)(t))[0] = htonl((u_int32_t)((f) >> 32)); \ + ((u_int32_t *)(t))[1] = htonl((u_int32_t)((f) & 0xffffffff)); \ +} + +#endif /* __FS_NFS_XDR_SUBS_H */ -- cgit v1.2.3