commit-gnuradio
[Top][All Lists]
Advanced

[Date Prev][Date Next][Thread Prev][Thread Next][Date Index][Thread Index]

[Commit-gnuradio] r10985 - gnuradio/branches/developers/eb/vrt/vrt/lib


From: eb
Subject: [Commit-gnuradio] r10985 - gnuradio/branches/developers/eb/vrt/vrt/lib
Date: Thu, 7 May 2009 02:29:15 -0600 (MDT)

Author: eb
Date: 2009-05-07 02:29:15 -0600 (Thu, 07 May 2009)
New Revision: 10985

Added:
   gnuradio/branches/developers/eb/vrt/vrt/lib/data_handler.cc
   gnuradio/branches/developers/eb/vrt/vrt/lib/data_handler.h
Modified:
   gnuradio/branches/developers/eb/vrt/vrt/lib/Makefile.am
   gnuradio/branches/developers/eb/vrt/vrt/lib/socket_rx_buffer.cc
   gnuradio/branches/developers/eb/vrt/vrt/lib/socket_rx_buffer.h
Log:
work-in-progress

Modified: gnuradio/branches/developers/eb/vrt/vrt/lib/Makefile.am
===================================================================
--- gnuradio/branches/developers/eb/vrt/vrt/lib/Makefile.am     2009-05-07 
07:59:53 UTC (rev 10984)
+++ gnuradio/branches/developers/eb/vrt/vrt/lib/Makefile.am     2009-05-07 
08:29:15 UTC (rev 10985)
@@ -28,11 +28,14 @@
        libvrt.la
 
 libvrt_la_SOURCES = \
+       data_handler.cc \
        expanded_headers.cc \
        rx_packet_handler.cc \
-       rx_udp.cc
+       rx_udp.cc \
+       socket_rx_buffer.cc
 
 libvrt_la_LIBADD =
 
 # Private headers not needed for above the API development
-noinst_HEADERS =
+noinst_HEADERS = \
+       data_handler.h

Copied: gnuradio/branches/developers/eb/vrt/vrt/lib/data_handler.cc (from rev 
10980, gnuradio/branches/developers/eb/vrt/usrp2/host/lib/data_handler.cc)
===================================================================
--- gnuradio/branches/developers/eb/vrt/vrt/lib/data_handler.cc                 
        (rev 0)
+++ gnuradio/branches/developers/eb/vrt/vrt/lib/data_handler.cc 2009-05-07 
08:29:15 UTC (rev 10985)
@@ -0,0 +1,32 @@
+/* -*- c++ -*- */
+/*
+ * Copyright 2008,2009 Free Software Foundation, Inc.
+ * 
+ * This file is part of GNU Radio
+ * 
+ * GNU Radio is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 3, or (at your option)
+ * any later version.
+ * 
+ * GNU Radio is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ * 
+ * You should have received a copy of the GNU General Public License along
+ * with this program; if not, write to the Free Software Foundation, Inc.,
+ * 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
+ */
+
+#include "data_handler.h"
+
+namespace vrt {
+  
+  data_handler::~data_handler()
+  {
+    // default nop destructor
+  }
+
+}
+  

Copied: gnuradio/branches/developers/eb/vrt/vrt/lib/data_handler.h (from rev 
10980, 
gnuradio/branches/developers/eb/vrt/usrp2/host/include/usrp2/data_handler.h)
===================================================================
--- gnuradio/branches/developers/eb/vrt/vrt/lib/data_handler.h                  
        (rev 0)
+++ gnuradio/branches/developers/eb/vrt/vrt/lib/data_handler.h  2009-05-07 
08:29:15 UTC (rev 10985)
@@ -0,0 +1,53 @@
+/* -*- c++ -*- */
+/*
+ * Copyright 2008,2009 Free Software Foundation, Inc.
+ * 
+ * This file is part of GNU Radio
+ * 
+ * GNU Radio is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 3, or (at your option)
+ * any later version.
+ * 
+ * GNU Radio is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ * 
+ * You should have received a copy of the GNU General Public License along
+ * with this program; if not, write to the Free Software Foundation, Inc.,
+ * 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
+ */
+#ifndef INCLUDED_VRT_DATA_HANDLER_H
+#define INCLUDED_VRT_DATA_HANDLER_H
+
+#include <stdint.h>
+#include <stddef.h>
+
+namespace vrt {
+
+  /*!
+   * \brief Abstract function object called to handle received data blocks.
+   */
+  class data_handler 
+  {
+  public:
+
+    enum result_bits {
+      DONE     = 0x0002,       //< do not call this object again
+    };
+    
+    typedef int result;                //< bitmask of result_bits
+
+    /*!
+     * \param base points to the beginning of the data
+     * \param len is the length in bytes of the data
+     * \returns bitmask composed of DONE
+     */
+    virtual result operator()(const void *base, size_t len) = 0;
+    virtual ~data_handler();
+  };
+
+} // namespace vrt
+
+#endif /* INCLUDED_VRT_DATA_HANDLER_H */

Modified: gnuradio/branches/developers/eb/vrt/vrt/lib/socket_rx_buffer.cc
===================================================================
--- gnuradio/branches/developers/eb/vrt/vrt/lib/socket_rx_buffer.cc     
2009-05-07 07:59:53 UTC (rev 10984)
+++ gnuradio/branches/developers/eb/vrt/vrt/lib/socket_rx_buffer.cc     
2009-05-07 08:29:15 UTC (rev 10985)
@@ -1,6 +1,6 @@
 /* -*- c++ -*- */
 /*
- * Copyright 2008 Free Software Foundation, Inc.
+ * Copyright 2008,2009 Free Software Foundation, Inc.
  * 
  * This file is part of GNU Radio
  * 
@@ -23,9 +23,8 @@
 #include <config.h>
 #endif
 
-#include "eth_buffer.h"
-#include "ethernet.h"
-#include <usrp2/data_handler.h>
+#include "socket_rx_buffer.h"
+#include "data_handler.h"
 #include <linux/if_packet.h>
 #include <sys/socket.h>
 #include <sys/mman.h>
@@ -37,55 +36,47 @@
 #include <string.h>
 
 
-#define ETH_BUFFER_DEBUG      0 // define to 0 or 1
-#if ETH_BUFFER_DEBUG
+#define SOCKET_RX_BUFFER_DEBUG      1 // define to 0 or 1
+#if SOCKET_RX_BUFFER_DEBUG
 #define DEBUG_LOG(x) ::write(2, (x), 1)
 #else
 #define DEBUG_LOG(X)
 #endif
 
-#define DEFAULT_MEM_SIZE   25e6 // ~0.25s @ 100 MB/s
+#define DEFAULT_MEM_SIZE 62.5e6 // ~0.5s @ 125 MB/s
 #define MAX_MEM_SIZE     1000e6 // ~10.00s @ 100 MB/s. 
 #define MAX_SLAB_SIZE    131072 // 128 KB (FIXME fish out of /proc/slabinfo)
-#define MAX_PKT_SIZE       1512 // we don't do jumbo frames
 
-namespace usrp2 {
 
-  eth_buffer::eth_buffer(size_t rx_bufsize)
-    : d_fd(0), d_using_tpring(false), d_buflen(0), d_buf(0), d_frame_nr(0),
-      d_frame_size(0), d_head(0), d_ring(0), d_ethernet(new ethernet())
+namespace vrt {
+
+  const unsigned int socket_rx_buffer::MAX_PKTLEN = 8192;
+  const unsigned int socket_rx_buffer::MIN_PKTLEN = 64;
+  
+  socket_rx_buffer::socket_rx_buffer(int socket_fd, size_t rx_bufsize)
+    : d_fd(socket_fd), d_using_tpring(false), d_buflen(0), d_buf(0), 
d_frame_nr(0),
+      d_frame_size(0), d_head(0), d_ring(0)
   {
     if (rx_bufsize == 0)
       d_buflen = (size_t)DEFAULT_MEM_SIZE;
     else
       d_buflen = std::min((size_t)MAX_MEM_SIZE, rx_bufsize);
-       
-    memset(d_mac, 0, sizeof(d_mac));
   }
 
-  eth_buffer::~eth_buffer()
+  socket_rx_buffer::~socket_rx_buffer()
   {
     close();
   }
   
   bool 
-  eth_buffer::open(const std::string &ifname, int protocol)
+  socket_rx_buffer::open()
   {
-    if (!d_ethernet->open(ifname, protocol)) {
-      std::cerr << "eth_buffer: unable to open interface " 
-               << ifname << std::endl;
-      return false;
-    }
-
-    d_fd = d_ethernet->fd();
-    memcpy(d_mac, d_ethernet->mac(), sizeof(d_mac));
-    
     struct tpacket_req req;
     size_t page_size = getpagesize();
 
     // Calculate minimum power-of-two aligned size for frames
     req.tp_frame_size =
-      (unsigned int)rint(pow(2, 
ceil(log2(TPACKET_ALIGN(TPACKET_HDRLEN)+TPACKET_ALIGN(MAX_PKT_SIZE)))));
+      (unsigned int)rint(pow(2, 
ceil(log2(TPACKET_ALIGN(TPACKET_HDRLEN)+TPACKET_ALIGN(MAX_PKTLEN)))));
     d_frame_size = req.tp_frame_size;
 
     // Calculate minimum contiguous pages needed to enclose a frame
@@ -105,8 +96,8 @@
     d_frame_nr = req.tp_frame_nr;
 
 #if 0
-    if (ETH_BUFFER_DEBUG)
-      std::cerr << "eth_buffer:" 
+    if (SOCKET_RX_BUFFER_DEBUG)
+      std::cerr << "socket_rx_buffer:" 
                << " frame_size=" << req.tp_frame_size
                << " block_size=" << req.tp_block_size
                 << " block_nr=" << req.tp_block_nr
@@ -117,26 +108,26 @@
 
     // Try to get kernel shared memory buffer    
     if (setsockopt(d_fd, SOL_PACKET, PACKET_RX_RING, (void *)&req, 
sizeof(req))) {
-      perror("eth_buffer: setsockopt");
+      perror("socket_rx_buffer: setsockopt");
       d_using_tpring = false;
       if (!(d_buf = (uint8_t *)malloc(d_buflen))) {
-        std::cerr << "eth_buffer: failed to allocate packet memory" << 
std::endl;
+        std::cerr << "socket_rx_buffer: failed to allocate packet memory" << 
std::endl;
        return false;
       }
       
-      std::cerr << "eth_buffer: using malloc'd memory for buffer" << std::endl;
+      std::cerr << "socket_rx_buffer: using malloc'd memory for buffer" << 
std::endl;
     }
     else {
       d_using_tpring = true;
       void *p = mmap(0, d_buflen, PROT_READ|PROT_WRITE, MAP_SHARED, d_fd, 0);
       if (p == MAP_FAILED){
-        perror("eth_buffer: mmap");
+        perror("socket_rx_buffer: mmap");
        return false;
       }
       d_buf = (uint8_t *) p;
 
-      if (ETH_BUFFER_DEBUG)
-        std::cerr << "eth_buffer: using kernel shared mem for buffer" << 
std::endl;
+      if (SOCKET_RX_BUFFER_DEBUG)
+        std::cerr << "socket_rx_buffer: using kernel shared mem for buffer" << 
std::endl;
     }
 
     // Initialize our pointers into the packet ring
@@ -151,30 +142,22 @@
   }
 
   bool
-  eth_buffer::close()
+  socket_rx_buffer::close()
   {
-    // if we have background thread, stop it here
-
     if (!d_using_tpring && d_buf)
        free(d_buf);
-       
-    return d_ethernet->close();
-  }
 
-  bool 
-  eth_buffer::attach_pktfilter(pktfilter *pf)
-  {
-    return d_ethernet->attach_pktfilter(pf);
+    return true;
   }
 
   inline bool
-  eth_buffer::frame_available()
+  socket_rx_buffer::frame_available()
   {
     return (((tpacket_hdr *)d_ring[d_head])->tp_status != TP_STATUS_KERNEL);
   }
   
-  eth_buffer::result
-  eth_buffer::rx_frames(data_handler *f, int timeout_in_ms)
+  socket_rx_buffer::result
+  socket_rx_buffer::rx_frames(data_handler *f, int timeout_in_ms)
   {
     DEBUG_LOG("\n");
       
@@ -214,14 +197,13 @@
       // code.  This means that our uint32_t samples are not 4-byte
       // aligned.  We'll have to deal with it downstream.
 
-      if (0)
-       fprintf(stderr, "eth_buffer: base = %p  tp_mac = %3d  tp_net = %3d\n",
+      if (1)
+       fprintf(stderr, "socket_rx_buffer: base = %p  tp_mac = %3d  tp_net = 
%3d\n",
                base, hdr->tp_mac, hdr->tp_net);
 
       // Invoke data handler
       data_handler::result r = (*f)(base, len);
-      if (!(r & data_handler::KEEP))
-        hdr->tp_status = TP_STATUS_KERNEL; // mark it free
+      hdr->tp_status = TP_STATUS_KERNEL; // mark it free
 
       inc_head();
 
@@ -233,42 +215,4 @@
     return EB_OK;
   }
 
-  eth_buffer::result
-  eth_buffer::tx_frame(const void *base, size_t len, int flags)
-  {
-    DEBUG_LOG("T");
-
-    if (flags & EF_DONTWAIT)    // FIXME: implement flags
-      throw std::runtime_error("tx_frame: EF_DONTWAIT not implemented");
-
-    int res = d_ethernet->write_packet(base, len);
-    if (res < 0 || (unsigned int)res != len)
-      return EB_ERROR;
-
-    return EB_OK;
-  }
-
-  eth_buffer::result
-  eth_buffer::tx_framev(const eth_iovec *iov, int iovcnt, int flags)
-  {
-    DEBUG_LOG("T");
-
-    if (flags & EF_DONTWAIT)    // FIXME: implement flags
-      throw std::runtime_error("tx_frame: EF_DONTWAIT not implemented");
-
-    int res = d_ethernet->write_packetv(iov, iovcnt);
-    if (res < 0)
-      return EB_ERROR;
-
-    return EB_OK;
-  }
-
-  void
-  eth_buffer::release_frame(void *base)
-  {
-    // Get d_frame_size aligned header
-    tpacket_hdr *hdr = (tpacket_hdr *)((intptr_t)base & ~(d_frame_size-1));
-    hdr->tp_status = TP_STATUS_KERNEL; // mark it free
-  }
-  
-} // namespace usrp2
+} // namespace vrt

Modified: gnuradio/branches/developers/eb/vrt/vrt/lib/socket_rx_buffer.h
===================================================================
--- gnuradio/branches/developers/eb/vrt/vrt/lib/socket_rx_buffer.h      
2009-05-07 07:59:53 UTC (rev 10984)
+++ gnuradio/branches/developers/eb/vrt/vrt/lib/socket_rx_buffer.h      
2009-05-07 08:29:15 UTC (rev 10985)
@@ -1,6 +1,6 @@
 /* -*- c++ -*- */
 /*
- * Copyright 2008 Free Software Foundation, Inc.
+ * Copyright 2008,2009 Free Software Foundation, Inc.
  * 
  * This file is part of GNU Radio
  * 
@@ -18,19 +18,16 @@
  * with this program; if not, write to the Free Software Foundation, Inc.,
  * 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
  */
-#ifndef INCLUDED_USRP2_ETH_BUFFER_H
-#define INCLUDED_USRP2_ETH_BUFFER_H
+#ifndef INCLUDED_VRT_SOCKET_RX_BUFFER_H
+#define INCLUDED_VRT_SOCKET_RX_BUFFER_H
 
-#include "pktfilter.h"
-#include <eth_common.h>
 #include <boost/utility.hpp>
 #include <vector>
 #include <memory>
 #include <stdint.h>
 
-namespace usrp2 {
+namespace vrt {
 
-  class ethernet;
   class data_handler;
 
   /*!
@@ -41,11 +38,10 @@
    *
    * \internal
    */
-  class eth_buffer : boost::noncopyable 
+  class socket_rx_buffer : boost::noncopyable 
   {
     
     int                  d_fd;                 // socket file descriptor
-    uint8_t      d_mac[6];             // our mac address
     bool          d_using_tpring;       // using kernel mapped packet ring
     size_t        d_buflen;             // length of our buffer
     uint8_t      *d_buf;                // packet ring
@@ -54,7 +50,6 @@
     unsigned int  d_head;               // pointer to next frame
 
     std::vector<uint8_t *>  d_ring;     // pointers into buffer
-    std::auto_ptr<ethernet> d_ethernet; // our underlying interface
   
     bool frame_available();
 
@@ -66,6 +61,8 @@
        d_head = d_head + 1;
     }
 
+    bool open();
+    bool close();
 
   public:
 
@@ -76,42 +73,18 @@
       EB_TIMED_OUT,    //< The timeout expired before anything was ready
     };
 
-    static const unsigned int MAX_PKTLEN = 1512;
-    static const unsigned int MIN_PKTLEN = 64;
+    static const unsigned int MAX_PKTLEN;
+    static const unsigned int MIN_PKTLEN;
 
     /*!
+     * \param socket_fd file descriptor that corresponds to a socket
      * \param rx_bufsize is a hint as to the number of bytes of memory
      * to allocate for received ethernet frames (0 -> reasonable default)
      */
-    eth_buffer(size_t rx_bufsize = 0);
-    ~eth_buffer();
+    socket_rx_buffer(int socket_fd, size_t rx_bufsize = 0);
+    ~socket_rx_buffer();
     
     /*!
-     * \brief open the specified interface
-     *
-     * \param ifname ethernet interface name, e.g., "eth0"
-     * \param protocol is the ethertype protocol number in network order.
-     *    Use 0 to receive all protocols.
-     */
-    bool open(const std::string &ifname, int protocol);
-
-    /*!
-     * \brief close the interface
-     */
-    bool close();
-
-    /*!
-     * \brief attach packet filter to socket to restrict which packets read 
sees.
-     * \param pf       the packet filter
-     */
-    bool attach_pktfilter(pktfilter *pf);
-
-    /*!
-     * \brief return 6 byte string containing our MAC address
-     */
-    const uint8_t *mac() const { return d_mac; }
-
-    /*!
      * \brief Call \p f for each frame in the receive buffer.
      * \param f is the frame data handler
      * \param timeout (in ms) controls behavior when there are no frames to 
read
@@ -127,20 +100,10 @@
      * \p f will be called on each ethernet frame that is available.
      * \p f returns a bit mask with one of the following set or cleared:
      * 
-     * data_handler::KEEP  - hold onto the frame and present it again during 
-     *                       the next call to rx_frames, otherwise discard it
-     *
      * data_handler::DONE -  return from rx_frames now even though more frames
      *                       might be available; otherwise continue if more 
      *                       frames are ready.
      *
-     * The idea of holding onto a frame for the next iteration allows
-     * the caller to scan the received packet stream for particular
-     * classes of frames (such as command replies) leaving the rest
-     * intact.  On the next call all kept frames, followed by any new
-     * frames received, will be presented in order to \p f.  
-     * See usrp2.cc for an example of the pattern.
-     *
      * \returns EB_OK if at least one frame was received
      * \returns EB_WOULD_BLOCK if \p timeout is 0 and the call would have 
blocked
      * \returns EB_TIMED_OUT if timeout occurred
@@ -149,50 +112,11 @@
     result rx_frames(data_handler *f, int timeout=-1);
 
     /*
-     * \brief Release frame from buffer
-     *
-     * Call to release a frame previously held by a data_handler::KEEP.
-     * The pointer may be offset from the base of the frame up to its length.
-     */
-    void release_frame(void *p);
-
-    /*
-     * \brief Write an ethernet frame to the interface.
-     *
-     * \param base points to the beginning of the frame (the 14-byte ethernet 
header).
-     * \param len is the length of the frame in bytes.
-     * \param flags is 0 or the bitwise-or of values from eth_flags
-     *
-     * The frame must begin with a 14-byte ethernet header.
-     *
-     * \returns EB_OK if the frame was successfully enqueued.
-     * \returns EB_WOULD_BLOCK if flags contains EF_DONT_WAIT and the call 
would have blocked.
-     * \returns EB_ERROR if there was an unrecoverable error.
-     */
-    result tx_frame(const void *base, size_t len, int flags=0);
-
-    /*
-     * \brief Write an ethernet frame to the interface using scatter/gather.
-     *
-     * \param iov points to an array of iovec structs
-     * \param iovcnt is the number of entries
-     * \param flags is 0 or the bitwise-or of values from eth_flags
-     *
-     * The frame must begin with a 14-byte ethernet header.
-     *
-     * \returns EB_OK if the frame was successfully enqueued.
-     * \returns EB_WOULD_BLOCK if flags contains EF_DONT_WAIT and the call 
would have blocked.
-     * \returns EB_ERROR if there was an unrecoverable error.
-     */
-    result tx_framev(const eth_iovec *iov, int iovcnt, int flags=0);
-
-    /*
      * \brief Returns maximum possible number of frames in buffer
      */
     unsigned int max_frames() const { return d_frame_nr; }
-
   };
 
-};  // namespace usrp2
+};  // namespace vrt
 
-#endif /* INCLUDED_USRP2_ETH_BUFFER_H */
+#endif /* INCLUDED_VRT_SOCKET_RX_BUFFER_H */





reply via email to

[Prev in Thread] Current Thread [Next in Thread]