diff options
Diffstat (limited to 'host/lib')
| -rw-r--r-- | host/lib/transport/simple_claimer.hpp | 64 | ||||
| -rw-r--r-- | host/lib/transport/super_recv_packet_handler.hpp | 93 | ||||
| -rw-r--r-- | host/lib/transport/super_send_packet_handler.hpp | 102 | ||||
| -rw-r--r-- | host/lib/transport/udp_zero_copy.cpp | 2 | ||||
| -rw-r--r-- | host/lib/transport/usb_zero_copy_wrapper.cpp | 3 | ||||
| -rw-r--r-- | host/lib/types/ranges.cpp | 21 | ||||
| -rw-r--r-- | host/lib/usrp/b100/CMakeLists.txt | 3 | ||||
| -rw-r--r-- | host/lib/usrp/b100/b100_impl.cpp | 91 | ||||
| -rw-r--r-- | host/lib/usrp/b100/b100_impl.hpp | 30 | ||||
| -rw-r--r-- | host/lib/usrp/b100/b100_regs.hpp | 116 | ||||
| -rw-r--r-- | host/lib/usrp/b100/dboard_iface.cpp | 2 | ||||
| -rw-r--r-- | host/lib/usrp/b100/io_impl.cpp | 72 | ||||
| -rw-r--r-- | host/lib/usrp/common/CMakeLists.txt | 3 | ||||
| -rw-r--r-- | host/lib/usrp/common/fifo_ctrl_excelsior.cpp | 293 | ||||
| -rw-r--r-- | host/lib/usrp/common/fifo_ctrl_excelsior.hpp | 63 | 
15 files changed, 614 insertions, 344 deletions
| diff --git a/host/lib/transport/simple_claimer.hpp b/host/lib/transport/simple_claimer.hpp deleted file mode 100644 index 3bbc49a05..000000000 --- a/host/lib/transport/simple_claimer.hpp +++ /dev/null @@ -1,64 +0,0 @@ -// -// Copyright 2012 Ettus Research LLC -// -// This program 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 of the License, or -// (at your option) any later version. -// -// This program 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, see <http://www.gnu.org/licenses/>. -// - -#ifndef INCLUDED_LIBUHD_TRANSPORT_SIMPLE_CLAIMER_HPP -#define INCLUDED_LIBUHD_TRANSPORT_SIMPLE_CLAIMER_HPP - -#include <uhd/config.hpp> -#include <boost/thread/condition.hpp> -#include <boost/thread/mutex.hpp> - -namespace uhd{ namespace transport{ - -/*********************************************************************** - * Claimer class to provide synchronization for multi-thread access. - * Claiming enables buffer classes to be used with a buffer queue. - **********************************************************************/ -class simple_claimer{ -public: -    simple_claimer(void){ -        this->release(); -    } - -    UHD_INLINE void release(void){ -        boost::mutex::scoped_lock lock(_mutex); -        _locked = false; -        lock.unlock(); -        _cond.notify_one(); -    } - -    UHD_INLINE bool claim_with_wait(const double timeout){ -        boost::mutex::scoped_lock lock(_mutex); -        while (_locked){ -            if (not _cond.timed_wait(lock, boost::posix_time::microseconds(long(timeout*1e6)))){ -                break; -            } -        } -        const bool ret = not _locked; -        _locked = true; -        return ret; -    } - -private: -    bool _locked; -    boost::mutex _mutex; -    boost::condition_variable _cond; -}; - -}} //namespace uhd::transport - -#endif /* INCLUDED_LIBUHD_TRANSPORT_SIMPLE_CLAIMER_HPP */ diff --git a/host/lib/transport/super_recv_packet_handler.hpp b/host/lib/transport/super_recv_packet_handler.hpp index 205c7a3a3..4b96199e2 100644 --- a/host/lib/transport/super_recv_packet_handler.hpp +++ b/host/lib/transport/super_recv_packet_handler.hpp @@ -23,6 +23,8 @@  #include <uhd/convert.hpp>  #include <uhd/stream.hpp>  #include <uhd/utils/msg.hpp> +#include <uhd/utils/tasks.hpp> +#include <uhd/utils/atomic.hpp>  #include <uhd/utils/byteswap.hpp>  #include <uhd/types/metadata.hpp>  #include <uhd/transport/vrt_if_packet.hpp> @@ -31,6 +33,9 @@  #include <boost/foreach.hpp>  #include <boost/function.hpp>  #include <boost/format.hpp> +#include <boost/bind.hpp> +#include <boost/make_shared.hpp> +#include <boost/thread/barrier.hpp>  #include <iostream>  #include <vector> @@ -73,12 +78,23 @@ public:          set_alignment_failure_threshold(1000);      } +    ~recv_packet_handler(void){ +        _task_handlers.clear(); +    } +      //! Resize the number of transport channels      void resize(const size_t size){          if (this->size() == size) return; +        _task_handlers.clear();          _props.resize(size);          //re-initialize all buffers infos by re-creating the vector          _buffers_infos = std::vector<buffers_info_type>(4, buffers_info_type(size)); +        _task_barrier_entry.resize(size); +        _task_barrier_exit.resize(size); +        _task_handlers.resize(size); +        for (size_t i = 1/*skip 0*/; i < size; i++){ +            _task_handlers[i] = task::make(boost::bind(&recv_packet_handler::converter_thread_task, this, i)); +        };      }      //! Get the channel width of this handler @@ -125,7 +141,7 @@ public:      //! Set the conversion routine for all channels      void set_converter(const uhd::convert::id_type &id){ -        _io_buffs.resize(id.num_outputs); +        _num_outputs = id.num_outputs;          _converter = uhd::convert::get_converter(id)();          this->set_scale_factor(1/32767.); //update after setting converter          _bytes_per_otw_item = uhd::convert::get_bytes_per_item(id.input_format); @@ -207,7 +223,7 @@ private:          handle_overflow_type handle_overflow;      };      std::vector<xport_chan_props_type> _props; -    std::vector<void *> _io_buffs; //used in conversion +    size_t _num_outputs;      size_t _bytes_per_otw_item; //used in conversion      size_t _bytes_per_cpu_item; //used in conversion      uhd::convert::converter::sptr _converter; //used in conversion @@ -512,24 +528,19 @@ private:          //extract the number of samples available to copy          const size_t nsamps_available = info.data_bytes_to_copy/_bytes_per_otw_item; -        const size_t nsamps_to_copy = std::min(nsamps_per_buff*_io_buffs.size(), nsamps_available); +        const size_t nsamps_to_copy = std::min(nsamps_per_buff*_num_outputs, nsamps_available);          const size_t bytes_to_copy = nsamps_to_copy*_bytes_per_otw_item; -        const size_t nsamps_to_copy_per_io_buff = nsamps_to_copy/_io_buffs.size(); +        const size_t nsamps_to_copy_per_io_buff = nsamps_to_copy/_num_outputs; -        size_t buff_index = 0; -        BOOST_FOREACH(per_buffer_info_type &buff_info, info){ +        //setup the data to share with converter threads +        _convert_nsamps = nsamps_to_copy_per_io_buff; +        _convert_buffs = &buffs; +        _convert_buffer_offset_bytes = buffer_offset_bytes; +        _convert_bytes_to_copy = bytes_to_copy; -            //fill a vector with pointers to the io buffers -            BOOST_FOREACH(void *&io_buff, _io_buffs){ -                io_buff = reinterpret_cast<char *>(buffs[buff_index++]) + buffer_offset_bytes; -            } +        //perform N channels of conversion +        converter_thread_task(0); -            //copy-convert the samples from the recv buffer -            _converter->conv(buff_info.copy_buff, _io_buffs, nsamps_to_copy_per_io_buff); - -            //update the rx copy buffer to reflect the bytes copied -            buff_info.copy_buff += bytes_to_copy; -        }          //update the copy buffer's availability          info.data_bytes_to_copy -= bytes_to_copy; @@ -538,15 +549,53 @@ private:          metadata.fragment_offset = info.fragment_offset_in_samps;          info.fragment_offset_in_samps += nsamps_to_copy; //set for next call -        //done with buffers? this action releases buffers in-order -        if (not metadata.more_fragments){ -            BOOST_FOREACH(per_buffer_info_type &buff_info, info){ -                buff_info.buff.reset(); //effectively a release -            } +        return nsamps_to_copy_per_io_buff; +    } + +    /******************************************************************* +     * Perform one thread's work of the conversion task. +     * The entry and exit use a dual synchronization barrier, +     * to wait for data to become ready and block until completion. +     ******************************************************************/ +    UHD_INLINE void converter_thread_task(const size_t index) +    { +        _task_barrier_entry.wait(); + +        //shortcut references to local data structures +        buffers_info_type &buff_info = get_curr_buffer_info(); +        per_buffer_info_type &info = buff_info[index]; +        const rx_streamer::buffs_type &buffs = *_convert_buffs; + +        //fill IO buffs with pointers into the output buffer +        void *io_buffs[4/*max interleave*/]; +        for (size_t i = 0; i < _num_outputs; i++){ +            char *b = reinterpret_cast<char *>(buffs[index*_num_outputs + i]); +            io_buffs[i] = b + _convert_buffer_offset_bytes;          } +        const ref_vector<void *> out_buffs(io_buffs, _num_outputs); -        return nsamps_to_copy_per_io_buff; +        //perform the conversion operation +        _converter->conv(info.copy_buff, out_buffs, _convert_nsamps); + +        //advance the pointer for the source buffer +        info.copy_buff += _convert_bytes_to_copy; + +        //release the buffer if fully consumed +        if (buff_info.data_bytes_to_copy == _convert_bytes_to_copy){ +            info.buff.reset(); //effectively a release +        } + +        _task_barrier_exit.wait();      } + +    //! Shared variables for the worker threads +    reusable_barrier _task_barrier_entry, _task_barrier_exit; +    std::vector<task::sptr> _task_handlers; +    size_t _convert_nsamps; +    const rx_streamer::buffs_type *_convert_buffs; +    size_t _convert_buffer_offset_bytes; +    size_t _convert_bytes_to_copy; +  };  class recv_packet_streamer : public recv_packet_handler, public rx_streamer{ diff --git a/host/lib/transport/super_send_packet_handler.hpp b/host/lib/transport/super_send_packet_handler.hpp index 02cfad80f..8f943effb 100644 --- a/host/lib/transport/super_send_packet_handler.hpp +++ b/host/lib/transport/super_send_packet_handler.hpp @@ -23,6 +23,8 @@  #include <uhd/convert.hpp>  #include <uhd/stream.hpp>  #include <uhd/utils/msg.hpp> +#include <uhd/utils/tasks.hpp> +#include <uhd/utils/atomic.hpp>  #include <uhd/utils/byteswap.hpp>  #include <uhd/types/metadata.hpp>  #include <uhd/transport/vrt_if_packet.hpp> @@ -58,12 +60,23 @@ public:          this->resize(size);      } +    ~send_packet_handler(void){ +        _task_handlers.clear(); +    } +      //! Resize the number of transport channels      void resize(const size_t size){          if (this->size() == size) return; +        _task_handlers.clear();          _props.resize(size);          static const boost::uint64_t zero = 0;          _zero_buffs.resize(size, &zero); +        _task_barrier_entry.resize(size); +        _task_barrier_exit.resize(size); +        _task_handlers.resize(size); +        for (size_t i = 1/*skip 0*/; i < size; i++){ +            _task_handlers[i] = task::make(boost::bind(&send_packet_handler::converter_thread_task, this, i)); +        };      }      //! Get the channel width of this handler @@ -104,7 +117,7 @@ public:      //! Set the conversion routine for all channels      void set_converter(const uhd::convert::id_type &id){ -        _io_buffs.resize(id.num_inputs); +        _num_inputs = id.num_inputs;          _converter = uhd::convert::get_converter(id)();          this->set_scale_factor(32767.); //update after setting converter          _bytes_per_otw_item = uhd::convert::get_bytes_per_item(id.output_format); @@ -205,9 +218,10 @@ private:          get_buff_type get_buff;          bool has_sid;          boost::uint32_t sid; +        managed_send_buffer::sptr buff;      };      std::vector<xport_chan_props_type> _props; -    std::vector<const void *> _io_buffs; //used in conversion +    size_t _num_inputs;      size_t _bytes_per_otw_item; //used in conversion      size_t _bytes_per_cpu_item; //used in conversion      uhd::convert::converter::sptr _converter; //used in conversion @@ -226,39 +240,77 @@ private:          const size_t buffer_offset_bytes = 0      ){          //load the rest of the if_packet_info in here -        if_packet_info.num_payload_bytes = nsamps_per_buff*_io_buffs.size()*_bytes_per_otw_item; +        if_packet_info.num_payload_bytes = nsamps_per_buff*_num_inputs*_bytes_per_otw_item;          if_packet_info.num_payload_words32 = (if_packet_info.num_payload_bytes + 3/*round up*/)/sizeof(boost::uint32_t);          if_packet_info.packet_count = _next_packet_seq; -        size_t buff_index = 0; +        //get a buffer for each channel or timeout          BOOST_FOREACH(xport_chan_props_type &props, _props){ -            managed_send_buffer::sptr buff = props.get_buff(timeout); -            if (buff.get() == NULL) return 0; //timeout - -            //fill a vector with pointers to the io buffers -            BOOST_FOREACH(const void *&io_buff, _io_buffs){ -                io_buff = reinterpret_cast<const char *>(buffs[buff_index++]) + buffer_offset_bytes; -            } -            boost::uint32_t *otw_mem = buff->cast<boost::uint32_t *>() + _header_offset_words32; - -            //pack metadata into a vrt header -            if_packet_info.has_sid = props.has_sid; -            if_packet_info.sid = props.sid; -            _vrt_packer(otw_mem, if_packet_info); -            otw_mem += if_packet_info.num_header_words32; +            if (not props.buff) props.buff = props.get_buff(timeout); +            if (not props.buff) return 0; //timeout +        } -            //copy-convert the samples into the send buffer -            _converter->conv(_io_buffs, otw_mem, nsamps_per_buff); +        //setup the data to share with converter threads +        _convert_nsamps = nsamps_per_buff; +        _convert_buffs = &buffs; +        _convert_buffer_offset_bytes = buffer_offset_bytes; +        _convert_if_packet_info = &if_packet_info; -            //commit the samples to the zero-copy interface -            size_t num_bytes_total = (_header_offset_words32+if_packet_info.num_packet_words32)*sizeof(boost::uint32_t); -            buff->commit(num_bytes_total); -            buff.reset(); //effectively a release +        //perform N channels of conversion +        converter_thread_task(0); -        }          _next_packet_seq++; //increment sequence after commits          return nsamps_per_buff;      } + +    /******************************************************************* +     * Perform one thread's work of the conversion task. +     * The entry and exit use a dual synchronization barrier, +     * to wait for data to become ready and block until completion. +     ******************************************************************/ +    UHD_INLINE void converter_thread_task(const size_t index) +    { +        _task_barrier_entry.wait(); + +        //shortcut references to local data structures +        managed_send_buffer::sptr &buff = _props[index].buff; +        vrt::if_packet_info_t if_packet_info = *_convert_if_packet_info; +        const tx_streamer::buffs_type &buffs = *_convert_buffs; + +        //fill IO buffs with pointers into the output buffer +        const void *io_buffs[4/*max interleave*/]; +        for (size_t i = 0; i < _num_inputs; i++){ +            const char *b = reinterpret_cast<const char *>(buffs[index*_num_inputs + i]); +            io_buffs[i] = b + _convert_buffer_offset_bytes; +        } +        const ref_vector<const void *> in_buffs(io_buffs, _num_inputs); + +        //pack metadata into a vrt header +        boost::uint32_t *otw_mem = buff->cast<boost::uint32_t *>() + _header_offset_words32; +        if_packet_info.has_sid = _props[index].has_sid; +        if_packet_info.sid = _props[index].sid; +        _vrt_packer(otw_mem, if_packet_info); +        otw_mem += if_packet_info.num_header_words32; + +        //perform the conversion operation +        _converter->conv(in_buffs, otw_mem, _convert_nsamps); + +        //commit the samples to the zero-copy interface +        const size_t num_vita_words32 = _header_offset_words32+if_packet_info.num_packet_words32; +        buff->commit(num_vita_words32*sizeof(boost::uint32_t)); +        buff.reset(); //effectively a release + +        _task_barrier_exit.wait(); +    } + +    //! Shared variables for the worker threads +    reusable_barrier _task_barrier_entry, _task_barrier_exit; +    std::vector<task::sptr> _task_handlers; +    size_t _convert_nsamps; +    const tx_streamer::buffs_type *_convert_buffs; +    size_t _convert_buffer_offset_bytes; +    vrt::if_packet_info_t *_convert_if_packet_info; +  };  class send_packet_streamer : public send_packet_handler, public tx_streamer{ diff --git a/host/lib/transport/udp_zero_copy.cpp b/host/lib/transport/udp_zero_copy.cpp index 9765c19c0..9125be53a 100644 --- a/host/lib/transport/udp_zero_copy.cpp +++ b/host/lib/transport/udp_zero_copy.cpp @@ -16,12 +16,12 @@  //  #include "udp_common.hpp" -#include "simple_claimer.hpp"  #include <uhd/transport/udp_zero_copy.hpp>  #include <uhd/transport/udp_simple.hpp> //mtu  #include <uhd/transport/buffer_pool.hpp>  #include <uhd/utils/msg.hpp>  #include <uhd/utils/log.hpp> +#include <uhd/utils/atomic.hpp>  #include <boost/format.hpp>  #include <boost/make_shared.hpp>  #include <vector> diff --git a/host/lib/transport/usb_zero_copy_wrapper.cpp b/host/lib/transport/usb_zero_copy_wrapper.cpp index d59ea36ff..d04244ca9 100644 --- a/host/lib/transport/usb_zero_copy_wrapper.cpp +++ b/host/lib/transport/usb_zero_copy_wrapper.cpp @@ -15,12 +15,12 @@  // along with this program.  If not, see <http://www.gnu.org/licenses/>.  // -#include "simple_claimer.hpp"  #include <uhd/transport/usb_zero_copy.hpp>  #include <uhd/transport/buffer_pool.hpp>  #include <uhd/utils/byteswap.hpp>  #include <uhd/utils/msg.hpp>  #include <uhd/utils/tasks.hpp> +#include <uhd/utils/atomic.hpp>  #include <boost/foreach.hpp>  #include <boost/make_shared.hpp>  #include <boost/thread/mutex.hpp> @@ -29,6 +29,7 @@  #include <vector>  #include <iostream> +using namespace uhd;  using namespace uhd::transport;  static const boost::posix_time::time_duration AUTOFLUSH_TIMEOUT(boost::posix_time::milliseconds(1)); diff --git a/host/lib/types/ranges.cpp b/host/lib/types/ranges.cpp index 6e39bc688..82a9a84e1 100644 --- a/host/lib/types/ranges.cpp +++ b/host/lib/types/ranges.cpp @@ -1,5 +1,5 @@  // -// Copyright 2011-2011 Ettus Research LLC +// Copyright 2011-2012 Ettus Research LLC  //  // This program is free software: you can redistribute it and/or modify  // it under the terms of the GNU General Public License as published by @@ -27,17 +27,8 @@ using namespace uhd;  /***********************************************************************   * range_t implementation code   **********************************************************************/ -struct range_t::impl{ -    impl(double start, double stop, double step): -        start(start), stop(stop), step(step) -    { -        /* NOP */ -    } -    double start, stop, step; -}; -  range_t::range_t(double value): -    _impl(UHD_PIMPL_MAKE(impl, (value, value, 0))) +    _start(value), _stop(value), _step(0.0)  {      /* NOP */  } @@ -45,7 +36,7 @@ range_t::range_t(double value):  range_t::range_t(      double start, double stop, double step  ): -    _impl(UHD_PIMPL_MAKE(impl, (start, stop, step))) +    _start(start), _stop(stop), _step(step)  {      if (stop < start){          throw uhd::value_error("cannot make range where stop < start"); @@ -53,15 +44,15 @@ range_t::range_t(  }  double range_t::start(void) const{ -    return _impl->start; +    return _start;  }  double range_t::stop(void) const{ -    return _impl->stop; +    return _stop;  }  double range_t::step(void) const{ -    return _impl->step; +    return _step;  }  const std::string range_t::to_pp_string(void) const{ diff --git a/host/lib/usrp/b100/CMakeLists.txt b/host/lib/usrp/b100/CMakeLists.txt index 1237f52d1..d2c33b512 100644 --- a/host/lib/usrp/b100/CMakeLists.txt +++ b/host/lib/usrp/b100/CMakeLists.txt @@ -1,5 +1,5 @@  # -# Copyright 2011 Ettus Research LLC +# Copyright 2011-2012 Ettus Research LLC  #  # This program is free software: you can redistribute it and/or modify  # it under the terms of the GNU General Public License as published by @@ -26,7 +26,6 @@ LIBUHD_REGISTER_COMPONENT("B100" ENABLE_B100 ON "ENABLE_LIBUHD;ENABLE_USB" OFF)  IF(ENABLE_B100)      LIBUHD_APPEND_SOURCES( -        ${CMAKE_CURRENT_SOURCE_DIR}/b100_ctrl.cpp          ${CMAKE_CURRENT_SOURCE_DIR}/b100_impl.cpp          ${CMAKE_CURRENT_SOURCE_DIR}/clock_ctrl.cpp          ${CMAKE_CURRENT_SOURCE_DIR}/codec_ctrl.cpp diff --git a/host/lib/usrp/b100/b100_impl.cpp b/host/lib/usrp/b100/b100_impl.cpp index eec777842..94dc88db4 100644 --- a/host/lib/usrp/b100/b100_impl.cpp +++ b/host/lib/usrp/b100/b100_impl.cpp @@ -17,12 +17,11 @@  #include "apply_corrections.hpp"  #include "b100_impl.hpp" -#include "b100_ctrl.hpp" +#include "b100_regs.hpp"  #include "fpga_regs_standard.h"  #include "usrp_i2c_addr.h"  #include "usrp_commands.h"  #include <uhd/transport/usb_control.hpp> -#include "ctrl_packet.hpp"  #include <uhd/utils/msg.hpp>  #include <uhd/exception.hpp>  #include <uhd/utils/static.hpp> @@ -33,7 +32,6 @@  #include <boost/filesystem.hpp>  #include <boost/thread/thread.hpp>  #include <boost/lexical_cast.hpp> -#include "b100_regs.hpp"  #include <cstdio>  #include <iostream> @@ -188,10 +186,10 @@ b100_impl::b100_impl(const device_addr_t &device_addr){      //create the control transport      device_addr_t ctrl_xport_args; -    ctrl_xport_args["recv_frame_size"] = boost::lexical_cast<std::string>(CTRL_PACKET_LENGTH); +    ctrl_xport_args["recv_frame_size"] = "512";      ctrl_xport_args["num_recv_frames"] = "16"; -    ctrl_xport_args["send_frame_size"] = boost::lexical_cast<std::string>(CTRL_PACKET_LENGTH); -    ctrl_xport_args["num_send_frames"] = "4"; +    ctrl_xport_args["send_frame_size"] = "512"; +    ctrl_xport_args["num_send_frames"] = "16";      _ctrl_transport = usb_zero_copy::make(          handle, @@ -199,17 +197,22 @@ b100_impl::b100_impl(const device_addr_t &device_addr){          3, 4, //interface, endpoint          ctrl_xport_args      ); -    while (_ctrl_transport->get_recv_buff(0.0)){} //flush ctrl xport      this->enable_gpif(true);      //////////////////////////////////////////////////////////////////// -    // Initialize FPGA wishbone communication +    // Initialize FPGA control communication      //////////////////////////////////////////////////////////////////// -    _fpga_ctrl = b100_ctrl::make(_ctrl_transport); -    _fpga_ctrl->poke32(B100_REG_GLOBAL_RESET, 0); //global fpga reset +    fifo_ctrl_excelsior_config fifo_ctrl_config; +    fifo_ctrl_config.async_sid_base = B100_TX_ASYNC_SID; +    fifo_ctrl_config.num_async_chan = 1; +    fifo_ctrl_config.ctrl_sid_base = B100_CTRL_MSG_SID; +    fifo_ctrl_config.spi_base = TOREG(SR_SPI); +    fifo_ctrl_config.spi_rb = REG_RB_SPI; +    _fifo_ctrl = fifo_ctrl_excelsior::make(_ctrl_transport, fifo_ctrl_config); +      //perform a test peek operation      try{ -        _fpga_ctrl->peek32(0); +        _fifo_ctrl->peek32(0);      }      //try reset once in the case of failure      catch(const uhd::exception &){ @@ -217,7 +220,7 @@ b100_impl::b100_impl(const device_addr_t &device_addr){          UHD_MSG(warning) <<              "The control endpoint was left in a bad state.\n"              "Attempting endpoint re-enumeration...\n" << std::endl; -        _fpga_ctrl.reset(); +        _fifo_ctrl.reset();          _ctrl_transport.reset();          _fx2_ctrl->usrp_fx2_reset();          goto b100_impl_constructor_begin; @@ -227,8 +230,7 @@ b100_impl::b100_impl(const device_addr_t &device_addr){      ////////////////////////////////////////////////////////////////////      // Initialize peripherals after reset      //////////////////////////////////////////////////////////////////// -    _fpga_i2c_ctrl = i2c_core_100::make(_fpga_ctrl, B100_REG_SLAVE(3)); -    _fpga_spi_ctrl = spi_core_100::make(_fpga_ctrl, B100_REG_SLAVE(2)); +    _fpga_i2c_ctrl = i2c_core_200::make(_fifo_ctrl, TOREG(SR_I2C), REG_RB_I2C);      ////////////////////////////////////////////////////////////////////      // Create data transport @@ -242,6 +244,10 @@ b100_impl::b100_impl(const device_addr_t &device_addr){      data_xport_args["send_frame_size"] = device_addr.get("send_frame_size", "16384");      data_xport_args["num_send_frames"] = device_addr.get("num_send_frames", "16"); +    //let packet padder know the LUT size in number of words32 +    const size_t rx_lut_size = size_t(data_xport_args.cast<double>("recv_frame_size", 0.0)); +    _fifo_ctrl->poke32(TOREG(SR_PADDER+0), rx_lut_size/sizeof(boost::uint32_t)); +      _data_transport = usb_zero_copy::make_wrapper(          usb_zero_copy::make(              handle,        // identifier @@ -251,7 +257,6 @@ b100_impl::b100_impl(const device_addr_t &device_addr){          ),          B100_MAX_PKT_BYTE_LIMIT      ); -    while (_data_transport->get_recv_buff(0.0)){} //flush data xport      ////////////////////////////////////////////////////////////////////      // Initialize the properties tree @@ -277,12 +282,17 @@ b100_impl::b100_impl(const device_addr_t &device_addr){      //^^^ clock created up top, just reg props here... ^^^      _tree->create<double>(mb_path / "tick_rate")          .publish(boost::bind(&b100_clock_ctrl::get_fpga_clock_rate, _clock_ctrl)) +        .subscribe(boost::bind(&fifo_ctrl_excelsior::set_tick_rate, _fifo_ctrl, _1))          .subscribe(boost::bind(&b100_impl::update_tick_rate, this, _1)); +    //subscribe the command time while we are at it +    _tree->create<time_spec_t>(mb_path / "time/cmd") +        .subscribe(boost::bind(&fifo_ctrl_excelsior::set_time, _fifo_ctrl, _1)); +      ////////////////////////////////////////////////////////////////////      // create codec control objects      //////////////////////////////////////////////////////////////////// -    _codec_ctrl = b100_codec_ctrl::make(_fpga_spi_ctrl); +    _codec_ctrl = b100_codec_ctrl::make(_fifo_ctrl);      const fs_path rx_codec_path = mb_path / "rx_codecs/A";      const fs_path tx_codec_path = mb_path / "tx_codecs/A";      _tree->create<std::string>(rx_codec_path / "name").set("ad9522"); @@ -304,8 +314,8 @@ b100_impl::b100_impl(const device_addr_t &device_addr){      ////////////////////////////////////////////////////////////////////      // create frontend control objects      //////////////////////////////////////////////////////////////////// -    _rx_fe = rx_frontend_core_200::make(_fpga_ctrl, B100_REG_SR_ADDR(B100_SR_RX_FRONT)); -    _tx_fe = tx_frontend_core_200::make(_fpga_ctrl, B100_REG_SR_ADDR(B100_SR_TX_FRONT)); +    _rx_fe = rx_frontend_core_200::make(_fifo_ctrl, TOREG(SR_RX_FE)); +    _tx_fe = tx_frontend_core_200::make(_fifo_ctrl, TOREG(SR_TX_FE));      _tree->create<subdev_spec_t>(mb_path / "rx_subdev_spec")          .subscribe(boost::bind(&b100_impl::update_rx_subdev_spec, this, _1)); @@ -334,13 +344,17 @@ b100_impl::b100_impl(const device_addr_t &device_addr){      ////////////////////////////////////////////////////////////////////      // create rx dsp control objects      //////////////////////////////////////////////////////////////////// -    _rx_dsps.push_back(rx_dsp_core_200::make( -        _fpga_ctrl, B100_REG_SR_ADDR(B100_SR_RX_DSP0), B100_REG_SR_ADDR(B100_SR_RX_CTRL0), B100_RX_SID_BASE + 0 -    )); -    _rx_dsps.push_back(rx_dsp_core_200::make( -        _fpga_ctrl, B100_REG_SR_ADDR(B100_SR_RX_DSP1), B100_REG_SR_ADDR(B100_SR_RX_CTRL1), B100_RX_SID_BASE + 1 -    )); -    for (size_t dspno = 0; dspno < _rx_dsps.size(); dspno++){ +    const size_t num_rx_dsps = _fifo_ctrl->peek32(REG_RB_NUM_RX_DSP); +    for (size_t dspno = 0; dspno < num_rx_dsps; dspno++) +    { +        const size_t sr_off = dspno*32; +        _rx_dsps.push_back(rx_dsp_core_200::make( +            _fifo_ctrl, +            TOREG(SR_RX_DSP0+sr_off), +            TOREG(SR_RX_CTRL0+sr_off), +            B100_RX_SID_BASE + dspno +        )); +          _rx_dsps[dspno]->set_link_rate(B100_LINK_RATE_BPS);          _tree->access<double>(mb_path / "tick_rate")              .subscribe(boost::bind(&rx_dsp_core_200::set_tick_rate, _rx_dsps[dspno], _1)); @@ -363,7 +377,7 @@ b100_impl::b100_impl(const device_addr_t &device_addr){      // create tx dsp control objects      ////////////////////////////////////////////////////////////////////      _tx_dsp = tx_dsp_core_200::make( -        _fpga_ctrl, B100_REG_SR_ADDR(B100_SR_TX_DSP), B100_REG_SR_ADDR(B100_SR_TX_CTRL), B100_TX_ASYNC_SID +        _fifo_ctrl, TOREG(SR_TX_DSP), TOREG(SR_TX_CTRL), B100_TX_ASYNC_SID      );      _tx_dsp->set_link_rate(B100_LINK_RATE_BPS);      _tree->access<double>(mb_path / "tick_rate") @@ -383,12 +397,12 @@ b100_impl::b100_impl(const device_addr_t &device_addr){      // create time control objects      ////////////////////////////////////////////////////////////////////      time64_core_200::readback_bases_type time64_rb_bases; -    time64_rb_bases.rb_hi_now = B100_REG_RB_TIME_NOW_HI; -    time64_rb_bases.rb_lo_now = B100_REG_RB_TIME_NOW_LO; -    time64_rb_bases.rb_hi_pps = B100_REG_RB_TIME_PPS_HI; -    time64_rb_bases.rb_lo_pps = B100_REG_RB_TIME_PPS_LO; +    time64_rb_bases.rb_hi_now = REG_RB_TIME_NOW_HI; +    time64_rb_bases.rb_lo_now = REG_RB_TIME_NOW_LO; +    time64_rb_bases.rb_hi_pps = REG_RB_TIME_PPS_HI; +    time64_rb_bases.rb_lo_pps = REG_RB_TIME_PPS_LO;      _time64 = time64_core_200::make( -        _fpga_ctrl, B100_REG_SR_ADDR(B100_SR_TIME64), time64_rb_bases +        _fifo_ctrl, TOREG(SR_TIME64), time64_rb_bases      );      _tree->access<double>(mb_path / "tick_rate")          .subscribe(boost::bind(&time64_core_200::set_tick_rate, _time64, _1)); @@ -412,7 +426,7 @@ b100_impl::b100_impl(const device_addr_t &device_addr){      ////////////////////////////////////////////////////////////////////      // create user-defined control objects      //////////////////////////////////////////////////////////////////// -    _user = user_settings_core_200::make(_fpga_ctrl, B100_REG_SR_ADDR(B100_SR_USER_REGS)); +    _user = user_settings_core_200::make(_fifo_ctrl, TOREG(SR_USER_REGS));      _tree->create<user_settings_core_200::user_reg_t>(mb_path / "user/regs")          .subscribe(boost::bind(&user_settings_core_200::set_reg, _user, _1)); @@ -438,7 +452,7 @@ b100_impl::b100_impl(const device_addr_t &device_addr){          .subscribe(boost::bind(&b100_impl::set_db_eeprom, this, "gdb", _1));      //create a new dboard interface and manager -    _dboard_iface = make_b100_dboard_iface(_fpga_ctrl, _fpga_i2c_ctrl, _fpga_spi_ctrl, _clock_ctrl, _codec_ctrl); +    _dboard_iface = make_b100_dboard_iface(_fifo_ctrl, _fpga_i2c_ctrl, _fifo_ctrl/*spi*/, _clock_ctrl, _codec_ctrl);      _tree->create<dboard_iface::sptr>(mb_path / "dboards/A/iface").set(_dboard_iface);      _dboard_manager = dboard_manager::make(          rx_db_eeprom.id, tx_db_eeprom.id, gdb_eeprom.id, @@ -458,7 +472,11 @@ b100_impl::b100_impl(const device_addr_t &device_addr){      }      //initialize io handling -    this->io_init(); +    _recv_demuxer = recv_packet_demuxer::make(_data_transport, _rx_dsps.size(), B100_RX_SID_BASE); + +    //allocate streamer weak ptrs containers +    _rx_streamers.resize(_rx_dsps.size()); +    _tx_streamers.resize(1/*known to be 1 dsp*/);      ////////////////////////////////////////////////////////////////////      // do some post-init tasks @@ -483,8 +501,7 @@ b100_impl::b100_impl(const device_addr_t &device_addr){  }  b100_impl::~b100_impl(void){ -    //set an empty async callback now that we deconstruct -    _fpga_ctrl->set_async_cb(b100_ctrl::async_cb_type()); +    //NOP  }  void b100_impl::check_fw_compat(void){ @@ -502,7 +519,7 @@ void b100_impl::check_fw_compat(void){  }  void b100_impl::check_fpga_compat(void){ -    const boost::uint32_t fpga_compat_num = _fpga_ctrl->peek32(B100_REG_RB_COMPAT); +    const boost::uint32_t fpga_compat_num = _fifo_ctrl->peek32(REG_RB_COMPAT);      boost::uint16_t fpga_major = fpga_compat_num >> 16, fpga_minor = fpga_compat_num & 0xffff;      if (fpga_major == 0){ //old version scheme          fpga_major = fpga_minor; diff --git a/host/lib/usrp/b100/b100_impl.hpp b/host/lib/usrp/b100/b100_impl.hpp index 22e22bcff..250229fb8 100644 --- a/host/lib/usrp/b100/b100_impl.hpp +++ b/host/lib/usrp/b100/b100_impl.hpp @@ -19,20 +19,19 @@  #define INCLUDED_B100_IMPL_HPP  #include "fx2_ctrl.hpp" -#include "b100_ctrl.hpp"  #include "clock_ctrl.hpp"  #include "codec_ctrl.hpp" -#include "spi_core_100.hpp" -#include "i2c_core_100.hpp" +#include "i2c_core_200.hpp"  #include "rx_frontend_core_200.hpp"  #include "tx_frontend_core_200.hpp"  #include "rx_dsp_core_200.hpp"  #include "tx_dsp_core_200.hpp"  #include "time64_core_200.hpp" +#include "fifo_ctrl_excelsior.hpp"  #include "user_settings_core_200.hpp" +#include "recv_packet_demuxer.hpp"  #include <uhd/device.hpp>  #include <uhd/property_tree.hpp> -#include <uhd/utils/pimpl.hpp>  #include <uhd/types/dict.hpp>  #include <uhd/types/sensors.hpp>  #include <uhd/types/clock_config.hpp> @@ -47,10 +46,11 @@  static const double          B100_LINK_RATE_BPS = 256e6/5; //pratical link rate (< 480 Mbps)  static const std::string     B100_FW_FILE_NAME = "usrp_b100_fw.ihx";  static const std::string     B100_FPGA_FILE_NAME = "usrp_b100_fpga.bin"; -static const boost::uint16_t B100_FW_COMPAT_NUM = 0x03; -static const boost::uint16_t B100_FPGA_COMPAT_NUM = 10; -static const boost::uint32_t B100_RX_SID_BASE = 2; -static const boost::uint32_t B100_TX_ASYNC_SID = 1; +static const boost::uint16_t B100_FW_COMPAT_NUM = 0x04; +static const boost::uint16_t B100_FPGA_COMPAT_NUM = 11; +static const boost::uint32_t B100_RX_SID_BASE = 30; +static const boost::uint32_t B100_TX_ASYNC_SID = 10; +static const boost::uint32_t B100_CTRL_MSG_SID = 20;  static const double          B100_DEFAULT_TICK_RATE = 64e6;  static const size_t          B100_MAX_PKT_BYTE_LIMIT = 2048;  static const std::string     B100_EEPROM_MAP_KEY = "B100"; @@ -80,8 +80,8 @@ private:      uhd::property_tree::sptr _tree;      //controllers -    spi_core_100::sptr _fpga_spi_ctrl; -    i2c_core_100::sptr _fpga_i2c_ctrl; +    fifo_ctrl_excelsior::sptr _fifo_ctrl; +    i2c_core_200::sptr _fpga_i2c_ctrl;      rx_frontend_core_200::sptr _rx_fe;      tx_frontend_core_200::sptr _tx_fe;      std::vector<rx_dsp_core_200::sptr> _rx_dsps; @@ -90,20 +90,17 @@ private:      user_settings_core_200::sptr _user;      b100_clock_ctrl::sptr _clock_ctrl;      b100_codec_ctrl::sptr _codec_ctrl; -    b100_ctrl::sptr _fpga_ctrl;      uhd::usrp::fx2_ctrl::sptr _fx2_ctrl;      //transports -    uhd::transport::zero_copy_if::sptr _data_transport, _ctrl_transport; +    uhd::transport::zero_copy_if::sptr _ctrl_transport; +    uhd::transport::zero_copy_if::sptr _data_transport; +    uhd::usrp::recv_packet_demuxer::sptr _recv_demuxer;      //dboard stuff      uhd::usrp::dboard_manager::sptr _dboard_manager;      uhd::usrp::dboard_iface::sptr _dboard_iface; -    //handle io stuff -    UHD_PIMPL_DECL(io_impl) _io_impl; -    void io_init(void); -      //device properties interface      uhd::property_tree::sptr get_tree(void) const{          return _tree; @@ -126,7 +123,6 @@ private:      void update_clock_source(const std::string &);      void enable_gpif(const bool);      void clear_fpga_fifo(void); -    void handle_async_message(uhd::transport::managed_recv_buffer::sptr);      uhd::sensor_value_t get_ref_locked(void);      void set_rx_fe_corrections(const double);      void set_tx_fe_corrections(const double); diff --git a/host/lib/usrp/b100/b100_regs.hpp b/host/lib/usrp/b100/b100_regs.hpp index 987a09f03..48eb0460d 100644 --- a/host/lib/usrp/b100/b100_regs.hpp +++ b/host/lib/usrp/b100/b100_regs.hpp @@ -15,109 +15,49 @@  // along with this program.  If not, see <http://www.gnu.org/licenses/>.  // -//////////////////////////////////////////////////////////////// -// -//         Memory map for wishbone bus -// -//////////////////////////////////////////////////////////////// - -// All addresses are byte addresses.  All accesses are word (16-bit) accesses. -//  This means that address bit 0 is usually 0. -//  There are 11 bits of address for the control. -  #ifndef INCLUDED_B100_REGS_HPP  #define INCLUDED_B100_REGS_HPP -///////////////////////////////////////////////////// -// Slave pointers +#include <boost/cstdint.hpp> -#define B100_REG_SLAVE(n) ((n)<<7) +#define TOREG(x) ((x)*4) -///////////////////////////////////////////////////// -// Slave 0 -- Misc Regs +#define localparam static const int -#define B100_REG_MISC_BASE B100_REG_SLAVE(0) +localparam SR_MISC         = 0;      // 5 +localparam SR_USER_REGS    = 5;      // 2 +localparam SR_PADDER       = 10;     // 2 -#define B100_REG_MISC_LED        B100_REG_MISC_BASE + 0 -#define B100_REG_MISC_SW         B100_REG_MISC_BASE + 2 -#define B100_REG_MISC_CGEN_CTRL  B100_REG_MISC_BASE + 4 -#define B100_REG_MISC_CGEN_ST    B100_REG_MISC_BASE + 6 +localparam SR_TX_CTRL      = 32;     // 6 +localparam SR_TX_DSP       = 40;     // 5 +localparam SR_TX_FE        = 48;     // 5 -///////////////////////////////////////////////////// -// Slave 1 -- UART -//   CLKDIV is 16 bits, others are only 8 +localparam SR_RX_CTRL0     = 96;      // 9 +localparam SR_RX_DSP0      = 106;     // 7 +localparam SR_RX_FE        = 114;     // 5 -#define B100_REG_UART_BASE B100_REG_SLAVE(1) +localparam SR_RX_CTRL1     = 128;     // 9 +localparam SR_RX_DSP1      = 138;     // 7 -#define B100_REG_UART_CLKDIV  B100_REG_UART_BASE + 0 -#define B100_REG_UART_TXLEVEL B100_REG_UART_BASE + 2 -#define B100_REG_UART_RXLEVEL B100_REG_UART_BASE + 4 -#define B100_REG_UART_TXCHAR  B100_REG_UART_BASE + 6 -#define B100_REG_UART_RXCHAR  B100_REG_UART_BASE + 8 +localparam SR_TIME64       = 192;     // 6 +localparam SR_SPI          = 208;     // 3 +localparam SR_I2C          = 216;     // 1 +localparam SR_GPIO         = 224;     // 5 -///////////////////////////////////////////////////// -// Slave 2 -- SPI Core -//these are 32-bit registers mapped onto the 16-bit Wishbone bus.  -//Using peek32/poke32 should allow transparent use of these registers. -#define B100_REG_SPI_BASE B100_REG_SLAVE(2) +#define REG_RB_TIME_NOW_HI TOREG(10) +#define REG_RB_TIME_NOW_LO TOREG(11) +#define REG_RB_TIME_PPS_HI TOREG(14) +#define REG_RB_TIME_PPS_LO TOREG(15) +#define REG_RB_SPI         TOREG(0) +#define REG_RB_COMPAT      TOREG(1) +#define REG_RB_GPIO        TOREG(3) +#define REG_RB_I2C         TOREG(2) +#define REG_RB_NUM_RX_DSP  TOREG(6)  //spi slave constants  #define B100_SPI_SS_AD9862    (1 << 2)  #define B100_SPI_SS_TX_DB     (1 << 1)  #define B100_SPI_SS_RX_DB     (1 << 0) -//////////////////////////////////////////////// -// Slave 3 -- I2C Core - -#define B100_REG_I2C_BASE B100_REG_SLAVE(3) - -/////////////////////////////////////////////////// -// Slave 7 -- Readback Mux 32 - -#define B100_REG_RB_MUX_32_BASE  B100_REG_SLAVE(7) - -#define B100_REG_RB_TIME_NOW_HI     B100_REG_RB_MUX_32_BASE + 0 -#define B100_REG_RB_TIME_NOW_LO     B100_REG_RB_MUX_32_BASE + 4 -#define B100_REG_RB_TIME_PPS_HI     B100_REG_RB_MUX_32_BASE + 8 -#define B100_REG_RB_TIME_PPS_LO     B100_REG_RB_MUX_32_BASE + 12 -#define B100_REG_RB_MISC_TEST32     B100_REG_RB_MUX_32_BASE + 16 -#define B100_REG_RB_COMPAT          B100_REG_RB_MUX_32_BASE + 24 -#define B100_REG_RB_GPIO            B100_REG_RB_MUX_32_BASE + 28 - -//////////////////////////////////////////////////// -// Slaves 8 & 9 -- Settings Bus -// -// Output-only, no readback, 64 registers total -//  Each register must be written 32 bits at a time -//  First the address xxx_xx00 and then xxx_xx10 -// 64 total regs in address space -#define B100_SR_RX_CTRL0 0       // 9 regs (+0 to +8) -#define B100_SR_RX_DSP0 10       // 4 regs (+0 to +3) -#define B100_SR_RX_CTRL1 16      // 9 regs (+0 to +8) -#define B100_SR_RX_DSP1 26       // 4 regs (+0 to +3) -#define B100_SR_TX_CTRL 32       // 4 regs (+0 to +3) -#define B100_SR_TX_DSP 38        // 3 regs (+0 to +2) - -#define B100_SR_TIME64 42        // 6 regs (+0 to +5) -#define B100_SR_RX_FRONT 48      // 5 regs (+0 to +4) -#define B100_SR_TX_FRONT 54      // 5 regs (+0 to +4) - -#define B100_SR_REG_TEST32 60    // 1 reg -#define B100_SR_CLEAR_FIFO 61    // 1 reg -#define B100_SR_GLOBAL_RESET 63  // 1 reg -#define B100_SR_USER_REGS 64     // 2 regs - -#define B100_SR_GPIO 128 - -#define B100_REG_SR_ADDR(n) (B100_REG_SLAVE(8) + (4*(n))) - -#define B100_REG_SR_MISC_TEST32        B100_REG_SR_ADDR(B100_SR_REG_TEST32) - -///////////////////////////////////////////////// -// Magic reset regs -//////////////////////////////////////////////// -#define B100_REG_CLEAR_FIFO         B100_REG_SR_ADDR(B100_SR_CLEAR_FIFO) -#define B100_REG_GLOBAL_RESET       B100_REG_SR_ADDR(B100_SR_GLOBAL_RESET) - -#endif +#endif /*INCLUDED_B100_REGS_HPP*/ diff --git a/host/lib/usrp/b100/dboard_iface.cpp b/host/lib/usrp/b100/dboard_iface.cpp index 39ad5c5ac..25604da72 100644 --- a/host/lib/usrp/b100/dboard_iface.cpp +++ b/host/lib/usrp/b100/dboard_iface.cpp @@ -45,7 +45,7 @@ public:          _spi_iface = spi_iface;          _clock = clock;          _codec = codec; -        _gpio = gpio_core_200::make(_wb_iface, B100_REG_SR_ADDR(B100_SR_GPIO), B100_REG_RB_GPIO); +        _gpio = gpio_core_200::make(_wb_iface, TOREG(SR_GPIO), REG_RB_GPIO);          //init the clock rate shadows          this->set_clock_rate(UNIT_RX, _clock->get_fpga_clock_rate()); diff --git a/host/lib/usrp/b100/io_impl.cpp b/host/lib/usrp/b100/io_impl.cpp index 674380cca..723756dcc 100644 --- a/host/lib/usrp/b100/io_impl.cpp +++ b/host/lib/usrp/b100/io_impl.cpp @@ -15,16 +15,10 @@  // along with this program.  If not, see <http://www.gnu.org/licenses/>.  // -#include "recv_packet_demuxer.hpp"  #include "validate_subdev_spec.hpp" -#include "async_packet_handler.hpp"  #include "../../transport/super_recv_packet_handler.hpp"  #include "../../transport/super_send_packet_handler.hpp" -#include "usrp_commands.h"  #include "b100_impl.hpp" -#include "b100_regs.hpp" -#include <uhd/utils/thread_priority.hpp> -#include <uhd/transport/bounded_buffer.hpp>  #include <boost/bind.hpp>  #include <boost/format.hpp>  #include <boost/bind.hpp> @@ -37,66 +31,6 @@ using namespace uhd;  using namespace uhd::usrp;  using namespace uhd::transport; -/*********************************************************************** - * IO Implementation Details - **********************************************************************/ -struct b100_impl::io_impl{ -    io_impl(void): -        async_msg_fifo(1000/*messages deep*/) -    { /* NOP */ } - -    zero_copy_if::sptr data_transport; -    bounded_buffer<async_metadata_t> async_msg_fifo; -    recv_packet_demuxer::sptr demuxer; -    double tick_rate; -}; - -/*********************************************************************** - * Initialize internals within this file - **********************************************************************/ -void b100_impl::io_init(void){ - -    //clear fifo state machines -    _fpga_ctrl->poke32(B100_REG_CLEAR_FIFO, 0); - -    //allocate streamer weak ptrs containers -    _rx_streamers.resize(_rx_dsps.size()); -    _tx_streamers.resize(1/*known to be 1 dsp*/); - -    //create new io impl -    _io_impl = UHD_PIMPL_MAKE(io_impl, ()); -    _io_impl->demuxer = recv_packet_demuxer::make(_data_transport, _rx_dsps.size(), B100_RX_SID_BASE); - -    //now its safe to register the async callback -    _fpga_ctrl->set_async_cb(boost::bind(&b100_impl::handle_async_message, this, _1)); -} - -void b100_impl::handle_async_message(managed_recv_buffer::sptr rbuf){ -    vrt::if_packet_info_t if_packet_info; -    if_packet_info.num_packet_words32 = rbuf->size()/sizeof(boost::uint32_t); -    const boost::uint32_t *vrt_hdr = rbuf->cast<const boost::uint32_t *>(); -    try{ -        vrt::if_hdr_unpack_le(vrt_hdr, if_packet_info); -    } -    catch(const std::exception &e){ -        UHD_MSG(error) << "Error (handle_async_message): " << e.what() << std::endl; -    } - -    if (if_packet_info.sid == B100_TX_ASYNC_SID and if_packet_info.packet_type != vrt::if_packet_info_t::PACKET_TYPE_DATA){ - -        //fill in the async metadata -        async_metadata_t metadata; -        load_metadata_from_buff(uhd::wtohx<boost::uint32_t>, metadata, if_packet_info, vrt_hdr, _io_impl->tick_rate); - -        //push the message onto the queue -        _io_impl->async_msg_fifo.push_with_pop_on_full(metadata); - -        //print some fastpath messages -        standard_async_msg_prints(metadata); -    } -    else UHD_MSG(error) << "Unknown async packet" << std::endl; -} -  void b100_impl::update_rates(void){      const fs_path mb_path = "/mboards/0";      _tree->access<double>(mb_path / "tick_rate").update(); @@ -111,7 +45,6 @@ void b100_impl::update_rates(void){  }  void b100_impl::update_tick_rate(const double rate){ -    _io_impl->tick_rate = rate;      //update the tick rate on all existing streamers -> thread safe      for (size_t i = 0; i < _rx_streamers.size(); i++){ @@ -181,8 +114,7 @@ void b100_impl::update_tx_subdev_spec(const uhd::usrp::subdev_spec_t &spec){  bool b100_impl::recv_async_msg(      async_metadata_t &async_metadata, double timeout  ){ -    boost::this_thread::disable_interruption di; //disable because the wait can throw -    return _io_impl->async_msg_fifo.pop_with_timed_wait(async_metadata, timeout); +    return _fifo_ctrl->pop_async_msg(async_metadata, timeout);  }  /*********************************************************************** @@ -227,7 +159,7 @@ rx_streamer::sptr b100_impl::get_rx_stream(const uhd::stream_args_t &args_){          _rx_dsps[dsp]->set_nsamps_per_packet(spp); //seems to be a good place to set this          _rx_dsps[dsp]->setup(args);          my_streamer->set_xport_chan_get_buff(chan_i, boost::bind( -            &recv_packet_demuxer::get_recv_buff, _io_impl->demuxer, dsp, _1 +            &recv_packet_demuxer::get_recv_buff, _recv_demuxer, dsp, _1          ), true /*flush*/);          my_streamer->set_overflow_handler(chan_i, boost::bind(              &rx_dsp_core_200::handle_overflow, _rx_dsps[dsp] diff --git a/host/lib/usrp/common/CMakeLists.txt b/host/lib/usrp/common/CMakeLists.txt index 9abd34afa..fa07e3d1d 100644 --- a/host/lib/usrp/common/CMakeLists.txt +++ b/host/lib/usrp/common/CMakeLists.txt @@ -1,5 +1,5 @@  # -# Copyright 2011 Ettus Research LLC +# Copyright 2011-2012 Ettus Research LLC  #  # This program is free software: you can redistribute it and/or modify  # it under the terms of the GNU General Public License as published by @@ -32,4 +32,5 @@ LIBUHD_APPEND_SOURCES(      ${CMAKE_CURRENT_SOURCE_DIR}/apply_corrections.cpp      ${CMAKE_CURRENT_SOURCE_DIR}/validate_subdev_spec.cpp      ${CMAKE_CURRENT_SOURCE_DIR}/recv_packet_demuxer.cpp +    ${CMAKE_CURRENT_SOURCE_DIR}/fifo_ctrl_excelsior.cpp  ) diff --git a/host/lib/usrp/common/fifo_ctrl_excelsior.cpp b/host/lib/usrp/common/fifo_ctrl_excelsior.cpp new file mode 100644 index 000000000..5e4a1e243 --- /dev/null +++ b/host/lib/usrp/common/fifo_ctrl_excelsior.cpp @@ -0,0 +1,293 @@ +// +// Copyright 2012 Ettus Research LLC +// +// This program 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 of the License, or +// (at your option) any later version. +// +// This program 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, see <http://www.gnu.org/licenses/>. +// + +#include "fifo_ctrl_excelsior.hpp" +#include "async_packet_handler.hpp" +#include <uhd/exception.hpp> +#include <uhd/utils/msg.hpp> +#include <uhd/utils/byteswap.hpp> +#include <uhd/utils/tasks.hpp> +#include <uhd/utils/safe_call.hpp> +#include <uhd/utils/thread_priority.hpp> +#include <uhd/transport/vrt_if_packet.hpp> +#include <uhd/transport/bounded_buffer.hpp> +#include <boost/thread/mutex.hpp> +#include <boost/thread/thread.hpp> +#include <boost/format.hpp> +#include <boost/bind.hpp> + +using namespace uhd; +using namespace uhd::usrp; +using namespace uhd::transport; + +static const size_t POKE32_CMD = (1 << 8); +static const size_t PEEK32_CMD = 0; +static const double ACK_TIMEOUT = 0.5; +static const double MASSIVE_TIMEOUT = 10.0; //for when we wait on a timed command +static const boost::uint32_t MAX_SEQS_OUT = 15; + +#define SPI_DIV _config.spi_base + 0 +#define SPI_CTRL _config.spi_base + 4 +#define SPI_DATA _config.spi_base + 8 +#define SPI_DIVIDER 4 + +struct ctrl_result_t{ +    boost::uint32_t msg[2]; +}; + +class fifo_ctrl_excelsior_impl : public fifo_ctrl_excelsior{ +public: + +    fifo_ctrl_excelsior_impl(zero_copy_if::sptr xport, const fifo_ctrl_excelsior_config &config): +        _xport(xport), +        _config(config), +        _seq_out(0), +        _seq_ack(0), +        _timeout(ACK_TIMEOUT), +        _async_fifo(1000), +        _ctrl_fifo(MAX_SEQS_OUT+1) +    { +        while (_xport->get_recv_buff(0.0)){} //flush +        this->set_time(uhd::time_spec_t(0.0)); +        this->set_tick_rate(1.0); //something possible but bogus +        _msg_task = task::make(boost::bind(&fifo_ctrl_excelsior_impl::handle_msg, this)); +        this->init_spi(); +    } + +    ~fifo_ctrl_excelsior_impl(void){ +        _timeout = ACK_TIMEOUT; //reset timeout to something small +        UHD_SAFE_CALL( +            this->peek32(0); //dummy peek with the purpose of ack'ing all packets +        ) +    } + +    bool pop_async_msg(async_metadata_t &async_metadata, double timeout){ +        boost::this_thread::disable_interruption di; //disable because the wait can throw +        return _async_fifo.pop_with_timed_wait(async_metadata, timeout); +    } + +    void handle_msg(void){ +        set_thread_priority_safe(); +        while (not boost::this_thread::interruption_requested()){ +            this->handle_msg1(); +        } +    } + +    void handle_msg1(void){ +        managed_recv_buffer::sptr buff = _xport->get_recv_buff(); +        if (not buff) return; +        const boost::uint32_t *pkt = buff->cast<const boost::uint32_t *>(); +        vrt::if_packet_info_t packet_info; +        packet_info.num_packet_words32 = buff->size()/sizeof(boost::uint32_t); +        try{ +            vrt::if_hdr_unpack_le(pkt, packet_info); +        } +        catch(const std::exception &ex){ +            UHD_MSG(error) << "FIFO ctrl bad VITA packet: " << ex.what() << std::endl; +        } +        if (packet_info.has_sid and packet_info.sid == _config.ctrl_sid_base){ +            ctrl_result_t res = ctrl_result_t(); +            res.msg[0] = uhd::wtohx(pkt[packet_info.num_header_words32+0]); +            res.msg[1] = uhd::wtohx(pkt[packet_info.num_header_words32+1]); +            _ctrl_fifo.push_with_haste(res); +        } +        else if (packet_info.has_sid and packet_info.sid >= _config.async_sid_base and packet_info.sid <= _config.async_sid_base + _config.num_async_chan){ +            async_metadata_t metadata; +            load_metadata_from_buff(uhd::wtohx<boost::uint32_t>, metadata, packet_info, pkt, _tick_rate, packet_info.sid - _config.async_sid_base); +            _async_fifo.push_with_pop_on_full(metadata); +            standard_async_msg_prints(metadata); +        } +        else{ +            UHD_MSG(error) << "FIFO ctrl got unknown SID: " << packet_info.sid << std::endl; +        } +    } + +    /******************************************************************* +     * Peek and poke 32 bit implementation +     ******************************************************************/ +    void poke32(wb_addr_type addr, boost::uint32_t data){ +        boost::mutex::scoped_lock lock(_mutex); + +        this->send_pkt(addr, data, POKE32_CMD); + +        this->wait_for_ack(_seq_out-MAX_SEQS_OUT); +    } + +    boost::uint32_t peek32(wb_addr_type addr){ +        boost::mutex::scoped_lock lock(_mutex); + +        this->send_pkt(addr, 0, PEEK32_CMD); + +        return this->wait_for_ack(_seq_out); +    } + +    /******************************************************************* +     * Peek and poke 16 bit not implemented +     ******************************************************************/ +    void poke16(wb_addr_type, boost::uint16_t){ +        throw uhd::not_implemented_error("poke16 not implemented in fifo ctrl module"); +    } + +    boost::uint16_t peek16(wb_addr_type){ +        throw uhd::not_implemented_error("peek16 not implemented in fifo ctrl module"); +    } + +    /******************************************************************* +     * FIFO controlled SPI implementation +     ******************************************************************/ +    void init_spi(void){ +        boost::mutex::scoped_lock lock(_mutex); + +        this->send_pkt(SPI_DIV, SPI_DIVIDER, POKE32_CMD); +        this->wait_for_ack(_seq_out-MAX_SEQS_OUT); + +        _ctrl_word_cache = 0; // force update first time around +    } + +    boost::uint32_t transact_spi( +        int which_slave, +        const spi_config_t &config, +        boost::uint32_t data, +        size_t num_bits, +        bool readback +    ){ +        boost::mutex::scoped_lock lock(_mutex); + +        //load control word +        boost::uint32_t ctrl_word = 0; +        ctrl_word |= ((which_slave & 0xffffff) << 0); +        ctrl_word |= ((num_bits & 0x3ff) << 24); +        if (config.mosi_edge == spi_config_t::EDGE_FALL) ctrl_word |= (1 << 31); +        if (config.miso_edge == spi_config_t::EDGE_RISE) ctrl_word |= (1 << 30); + +        //load data word (must be in upper bits) +        const boost::uint32_t data_out = data << (32 - num_bits); + +        //conditionally send control word +        if (_ctrl_word_cache != ctrl_word){ +            this->send_pkt(SPI_CTRL, ctrl_word, POKE32_CMD); +            this->wait_for_ack(_seq_out-MAX_SEQS_OUT); +            _ctrl_word_cache = ctrl_word; +        } + +        //send data word +        this->send_pkt(SPI_DATA, data_out, POKE32_CMD); +        this->wait_for_ack(_seq_out-MAX_SEQS_OUT); + +        //conditional readback +        if (readback){ +            this->send_pkt(_config.spi_rb, 0, PEEK32_CMD); +            return this->wait_for_ack(_seq_out); +        } + +        return 0; +    } + +    /******************************************************************* +     * Update methods for time +     ******************************************************************/ +    void set_time(const uhd::time_spec_t &time){ +        boost::mutex::scoped_lock lock(_mutex); +        _time = time; +        _use_time = _time != uhd::time_spec_t(0.0); +        if (_use_time) _timeout = MASSIVE_TIMEOUT; //permanently sets larger timeout +    } + +    void set_tick_rate(const double rate){ +        boost::mutex::scoped_lock lock(_mutex); +        _tick_rate = rate; +    } + +private: + +    /******************************************************************* +     * Primary control and interaction private methods +     ******************************************************************/ +    UHD_INLINE void send_pkt(wb_addr_type addr, boost::uint32_t data, int cmd){ +        managed_send_buffer::sptr buff = _xport->get_send_buff(0.0); +        if (not buff){ +            throw uhd::runtime_error("fifo ctrl timed out getting a send buffer"); +        } +        boost::uint32_t *pkt = buff->cast<boost::uint32_t *>(); + +        //load packet info +        vrt::if_packet_info_t packet_info; +        packet_info.packet_type = vrt::if_packet_info_t::PACKET_TYPE_CONTEXT; +        packet_info.num_payload_words32 = 2; +        packet_info.num_payload_bytes = packet_info.num_payload_words32*sizeof(boost::uint32_t); +        packet_info.packet_count = ++_seq_out; +        packet_info.tsf = _time.to_ticks(_tick_rate); +        packet_info.sob = false; +        packet_info.eob = false; +        packet_info.has_sid = false; +        packet_info.has_cid = false; +        packet_info.has_tsi = false; +        packet_info.has_tsf = _use_time; +        packet_info.has_tlr = false; + +        //load header +        vrt::if_hdr_pack_le(pkt, packet_info); + +        //load payload +        const boost::uint32_t ctrl_word = (addr/4 & 0xff) | cmd | (_seq_out << 16); +        pkt[packet_info.num_header_words32+0] = uhd::htowx(ctrl_word); +        pkt[packet_info.num_header_words32+1] = uhd::htowx(data); + +        //send the buffer over the interface +        buff->commit(sizeof(boost::uint32_t)*(packet_info.num_packet_words32)); +    } + +    UHD_INLINE bool wraparound_lt16(const boost::int16_t i0, const boost::int16_t i1){ +        if (((i0 ^ i1) & 0x8000) == 0) //same sign bits +            return boost::uint16_t(i0) < boost::uint16_t(i1); +        return boost::int16_t(i1 - i0) > 0; +    } + +    UHD_INLINE boost::uint32_t wait_for_ack(const boost::uint16_t seq_to_ack){ + +        while (wraparound_lt16(_seq_ack, seq_to_ack)){ +            ctrl_result_t res = ctrl_result_t(); +            if (not _ctrl_fifo.pop_with_timed_wait(res, _timeout)){ +                throw uhd::runtime_error("fifo ctrl timed out looking for acks"); +            } +            _seq_ack = res.msg[0] >> 16; +            if (_seq_ack == seq_to_ack) return res.msg[1]; +        } + +        return 0; +    } + +    zero_copy_if::sptr _xport; +    const fifo_ctrl_excelsior_config _config; +    boost::mutex _mutex; +    boost::uint16_t _seq_out; +    boost::uint16_t _seq_ack; +    uhd::time_spec_t _time; +    bool _use_time; +    double _tick_rate; +    double _timeout; +    boost::uint32_t _ctrl_word_cache; +    bounded_buffer<async_metadata_t> _async_fifo; +    bounded_buffer<ctrl_result_t> _ctrl_fifo; +    task::sptr _msg_task; +}; + + +fifo_ctrl_excelsior::sptr fifo_ctrl_excelsior::make(zero_copy_if::sptr xport, const fifo_ctrl_excelsior_config &config) +{ +    return sptr(new fifo_ctrl_excelsior_impl(xport, config)); +} diff --git a/host/lib/usrp/common/fifo_ctrl_excelsior.hpp b/host/lib/usrp/common/fifo_ctrl_excelsior.hpp new file mode 100644 index 000000000..c3ef65a2c --- /dev/null +++ b/host/lib/usrp/common/fifo_ctrl_excelsior.hpp @@ -0,0 +1,63 @@ +// +// Copyright 2012 Ettus Research LLC +// +// This program 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 of the License, or +// (at your option) any later version. +// +// This program 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, see <http://www.gnu.org/licenses/>. +// + +#ifndef INCLUDED_B200_CTRL_HPP +#define INCLUDED_B200_CTRL_HPP + +#include <uhd/types/time_spec.hpp> +#include <uhd/types/metadata.hpp> +#include <uhd/types/serial.hpp> +#include <uhd/transport/zero_copy.hpp> +#include <boost/shared_ptr.hpp> +#include <boost/utility.hpp> +#include "wb_iface.hpp" +#include <string> + + +struct fifo_ctrl_excelsior_config +{ +    size_t async_sid_base; +    size_t num_async_chan; +    size_t ctrl_sid_base; +    size_t spi_base; +    size_t spi_rb; +}; + +/*! + * Provide access to peek, poke, spi, and async messages. + */ +class fifo_ctrl_excelsior : public wb_iface, public uhd::spi_iface{ +public: +    typedef boost::shared_ptr<fifo_ctrl_excelsior> sptr; + +    //! Make a new control object +    static sptr make( +        uhd::transport::zero_copy_if::sptr xport, +        const fifo_ctrl_excelsior_config &config +    ); + +    //! Set the command time that will activate +    virtual void set_time(const uhd::time_spec_t &time) = 0; + +    //! Set the tick rate (converting time into ticks) +    virtual void set_tick_rate(const double rate) = 0; + +    //! Pop an async message from the queue or timeout +    virtual bool pop_async_msg(uhd::async_metadata_t &async_metadata, double timeout) = 0; +}; + +#endif /* INCLUDED_B200_CTRL_HPP */ | 
