diff options
Diffstat (limited to 'host/lib/usrp/e100')
| -rw-r--r-- | host/lib/usrp/e100/dboard_iface.cpp | 2 | ||||
| -rw-r--r-- | host/lib/usrp/e100/e100_ctrl.cpp | 181 | ||||
| -rw-r--r-- | host/lib/usrp/e100/e100_ctrl.hpp | 9 | ||||
| -rw-r--r-- | host/lib/usrp/e100/e100_impl.cpp | 145 | ||||
| -rw-r--r-- | host/lib/usrp/e100/e100_impl.hpp | 22 | ||||
| -rw-r--r-- | host/lib/usrp/e100/e100_regs.hpp | 130 | ||||
| -rw-r--r-- | host/lib/usrp/e100/include/linux/usrp_e.h | 4 | ||||
| -rw-r--r-- | host/lib/usrp/e100/io_impl.cpp | 143 | 
8 files changed, 272 insertions, 364 deletions
| diff --git a/host/lib/usrp/e100/dboard_iface.cpp b/host/lib/usrp/e100/dboard_iface.cpp index 6afc7bc48..532b2dc9e 100644 --- a/host/lib/usrp/e100/dboard_iface.cpp +++ b/host/lib/usrp/e100/dboard_iface.cpp @@ -45,7 +45,7 @@ public:          _spi_iface = spi_iface;          _clock = clock;          _codec = codec; -        _gpio = gpio_core_200::make(_wb_iface, E100_REG_SR_ADDR(UE_SR_GPIO), E100_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/e100/e100_ctrl.cpp b/host/lib/usrp/e100/e100_ctrl.cpp index eb529c9c1..408d259dc 100644 --- a/host/lib/usrp/e100/e100_ctrl.cpp +++ b/host/lib/usrp/e100/e100_ctrl.cpp @@ -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 @@ -23,13 +23,16 @@  #include <sys/ioctl.h> //ioctl  #include <fcntl.h> //open, close  #include <linux/usrp_e.h> //ioctl structures and constants +#include <poll.h> //poll  #include <boost/thread/thread.hpp> //sleep  #include <boost/thread/mutex.hpp> +#include <boost/thread/condition_variable.hpp>  #include <boost/foreach.hpp>  #include <boost/format.hpp>  #include <fstream>  using namespace uhd; +using namespace uhd::transport;  /***********************************************************************   * Sysfs GPIO wrapper class @@ -71,6 +74,53 @@ private:  };  /*********************************************************************** + * Protection for dual GPIO access - sometimes MISO, sometimes have resp + **********************************************************************/ +static boost::mutex gpio_has_resp_mutex; +static boost::condition_variable gpio_has_resp_cond; +static bool gpio_has_resp_claimed = false; +static gpio gpio_has_resp(147, "in"); + +struct gpio_has_resp_claimer +{ +    gpio_has_resp_claimer(void) +    { +        boost::mutex::scoped_lock lock(gpio_has_resp_mutex); +        gpio_has_resp_claimed = true; +    } + +    ~gpio_has_resp_claimer(void) +    { +        boost::mutex::scoped_lock lock(gpio_has_resp_mutex); +        gpio_has_resp_claimed = false; +        lock.unlock(); +        gpio_has_resp_cond.notify_one(); +    } +}; + +static inline bool gpio_has_resp_value(void) +{ +    boost::mutex::scoped_lock lock(gpio_has_resp_mutex); +    while (gpio_has_resp_claimed) +    { +        gpio_has_resp_cond.wait(lock); +    } +    return bool(gpio_has_resp()); +} + +static bool inline gpio_has_resp_wait(const double timeout) +{ +    if (gpio_has_resp_value()) return true; +    const boost::system_time exit_time = boost::get_system_time() + boost::posix_time::milliseconds(long(timeout*1e6)); +    while (boost::get_system_time() < exit_time) +    { +        boost::this_thread::sleep(boost::posix_time::milliseconds(1)); +        if (gpio_has_resp_value()) return true; +    } +    return false; +} + +/***********************************************************************   * Aux spi implementation   **********************************************************************/  class aux_spi_iface_impl : public spi_iface{ @@ -79,7 +129,8 @@ public:          spi_sclk_gpio(65, "out"),          spi_sen_gpio(186, "out"),          spi_mosi_gpio(145, "out"), -        spi_miso_gpio(147, "in"){} +        //spi_miso_gpio(147, "in"){} +        spi_miso_gpio(gpio_has_resp){}      boost::uint32_t transact_spi(          int, const spi_config_t &, //not used params @@ -87,6 +138,8 @@ public:          size_t num_bits,          bool readback      ){ +        gpio_has_resp_claimer claimer(); +          boost::uint32_t rb_bits = 0;          this->spi_sen_gpio(0); @@ -105,7 +158,7 @@ public:      }  private: -    gpio spi_sclk_gpio, spi_sen_gpio, spi_mosi_gpio, spi_miso_gpio; +    gpio spi_sclk_gpio, spi_sen_gpio, spi_mosi_gpio, &spi_miso_gpio;  };  uhd::spi_iface::sptr e100_ctrl::make_aux_spi_iface(void){ @@ -244,6 +297,57 @@ uhd::uart_iface::sptr e100_ctrl::make_gps_uart_iface(const std::string &node){  }  /*********************************************************************** + * Simple managed buffers + **********************************************************************/ +struct e100_simpl_mrb : managed_recv_buffer +{ +    usrp_e_ctl32 data; +    e100_ctrl *ctrl; + +    void release(void) +    { +        //NOP +    } + +    sptr get_new(void) +    { +        const size_t max_words32 = 8; //.LAST_ADDR(10'h00f)) resp_fifo_to_gpmc + +        //load the data struct +        data.offset = 0; +        data.count = max_words32; + +        //call the ioctl +        ctrl->ioctl(USRP_E_READ_CTL32, &data); + +        if (data.buf[0] == 0 or ~data.buf[0] == 0) return sptr(); //bad VRT hdr, treat like timeout + +        return make(this, data.buf, sizeof(data.buf)); +    } +}; + +struct e100_simpl_msb : managed_send_buffer +{ +    usrp_e_ctl32 data; +    e100_ctrl *ctrl; + +    void release(void) +    { +        //load the data struct +        data.offset = 0; +        data.count = size()/4+1/*1 for flush pad*/; + +        //call the ioctl +        ctrl->ioctl(USRP_E_WRITE_CTL32, &data); +    } + +    sptr get_new(void) +    { +        return make(this, data.buf, sizeof(data.buf)); +    } +}; + +/***********************************************************************   * USRP-E100 control implementation   **********************************************************************/  class e100_ctrl_impl : public e100_ctrl{ @@ -273,8 +377,14 @@ public:              ) % USRP_E_COMPAT_NUMBER % module_compat_num));          } -        //perform a global reset after opening -        this->poke32(E100_REG_GLOBAL_RESET, 0); +        //hit the magic arst condition +        //async_reset <= ~EM_NCS6 && ~EM_NWE && (EM_A[9:2] == 8'hff) && EM_D[0]; +        usrp_e_ctl16 datax; +        datax.offset = 0x3fc; +        datax.count = 2; +        datax.buf[0] = 1; +        datax.buf[1] = 0; +        this->ioctl(USRP_E_WRITE_CTL16, &datax);      }      ~e100_ctrl_impl(void){ @@ -293,58 +403,45 @@ public:              ));          }      } +      /******************************************************************* -     * Peek and Poke +     * The managed buffer interface       ******************************************************************/ -    void poke32(wb_addr_type addr, boost::uint32_t value){ -        //load the data struct -        usrp_e_ctl32 data; -        data.offset = addr; -        data.count = 1; -        data.buf[0] = value; - -        //call the ioctl -        this->ioctl(USRP_E_WRITE_CTL32, &data); +    managed_recv_buffer::sptr get_recv_buff(double timeout){ +        if (not gpio_has_resp_wait(timeout)) +        { +            return managed_recv_buffer::sptr(); +        } +        _mrb.ctrl = this; +        return _mrb.get_new();      } -    void poke16(wb_addr_type addr, boost::uint16_t value){ -        //load the data struct -        usrp_e_ctl16 data; -        data.offset = addr; -        data.count = 1; -        data.buf[0] = value; - -        //call the ioctl -        this->ioctl(USRP_E_WRITE_CTL16, &data); +    managed_send_buffer::sptr get_send_buff(double){ +        _msb.ctrl = this; +        return _msb.get_new();      } -    boost::uint32_t peek32(wb_addr_type addr){ -        //load the data struct -        usrp_e_ctl32 data; -        data.offset = addr; -        data.count = 1; - -        //call the ioctl -        this->ioctl(USRP_E_READ_CTL32, &data); - -        return data.buf[0]; +    size_t get_num_recv_frames(void) const{ +        return 1;      } -    boost::uint16_t peek16(wb_addr_type addr){ -        //load the data struct -        usrp_e_ctl16 data; -        data.offset = addr; -        data.count = 1; +    size_t get_recv_frame_size(void) const{ +        return sizeof(_mrb.data.buf); +    } -        //call the ioctl -        this->ioctl(USRP_E_READ_CTL16, &data); +    size_t get_num_send_frames(void) const{ +        return 1; +    } -        return data.buf[0]; +    size_t get_send_frame_size(void) const{ +        return sizeof(_msb.data.buf);      }  private:      int _node_fd;      boost::mutex _ioctl_mutex; +    e100_simpl_mrb _mrb; +    e100_simpl_msb _msb;  };  /*********************************************************************** diff --git a/host/lib/usrp/e100/e100_ctrl.hpp b/host/lib/usrp/e100/e100_ctrl.hpp index fd66791d4..72dce134e 100644 --- a/host/lib/usrp/e100/e100_ctrl.hpp +++ b/host/lib/usrp/e100/e100_ctrl.hpp @@ -1,5 +1,5 @@  // -// Copyright 2011 Ettus Research LLC +// 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 @@ -18,12 +18,11 @@  #ifndef INCLUDED_B100_CTRL_HPP  #define INCLUDED_B100_CTRL_HPP -#include "wb_iface.hpp" +#include <uhd/transport/zero_copy.hpp>  #include <uhd/types/serial.hpp>  #include <boost/shared_ptr.hpp> -#include <boost/utility.hpp> -class e100_ctrl : boost::noncopyable, public wb_iface{ +class e100_ctrl : public uhd::transport::zero_copy_if{  public:      typedef boost::shared_ptr<e100_ctrl> sptr; @@ -33,7 +32,7 @@ public:      //! Make an i2c iface for the i2c device node      static uhd::i2c_iface::sptr make_dev_i2c_iface(const std::string &node); -    //! Make an i2c iface for the i2c device node +    //! Make a spi iface for the spi gpio      static uhd::spi_iface::sptr make_aux_spi_iface(void);      //! Make a uart iface for the uart device node diff --git a/host/lib/usrp/e100/e100_impl.cpp b/host/lib/usrp/e100/e100_impl.cpp index d55ea5ec5..a517dfcba 100644 --- a/host/lib/usrp/e100/e100_impl.cpp +++ b/host/lib/usrp/e100/e100_impl.cpp @@ -28,6 +28,7 @@  #include <boost/functional/hash.hpp>  #include <boost/assign/list_of.hpp>  #include <fstream> +#include <ctime>  using namespace uhd;  using namespace uhd::usrp; @@ -86,15 +87,6 @@ static device_addrs_t e100_find(const device_addr_t &hint){  /***********************************************************************   * Make   **********************************************************************/ -static size_t hash_fpga_file(const std::string &file_path){ -    size_t hash = 0; -    std::ifstream file(file_path.c_str()); -    if (not file.good()) throw uhd::io_error("cannot open fpga file for read: " + file_path); -    while (file.good()) boost::hash_combine(hash, file.get()); -    file.close(); -    return hash; -} -  static device::sptr e100_make(const device_addr_t &device_addr){      return device::sptr(new e100_impl(device_addr));  } @@ -114,10 +106,6 @@ static const uhd::dict<std::string, std::string> model_to_fpga_file_name = boost  e100_impl::e100_impl(const uhd::device_addr_t &device_addr){      _tree = property_tree::make(); -    //setup the main interface into fpga -    const std::string node = device_addr["node"]; -    _fpga_ctrl = e100_ctrl::make(node); -      //read the eeprom so we can determine the hardware      _dev_i2c_iface = e100_ctrl::make_dev_i2c_iface(E100_I2C_DEV_NODE);      const mboard_eeprom_t mb_eeprom(*_dev_i2c_iface, E100_EEPROM_MAP_KEY); @@ -134,19 +122,11 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){      //extract the fpga path and compute hash      const std::string default_fpga_file_name = model_to_fpga_file_name[model];      const std::string e100_fpga_image = find_image_path(device_addr.get("fpga", default_fpga_file_name)); -    const boost::uint32_t file_hash = boost::uint32_t(hash_fpga_file(e100_fpga_image)); - -    //When the hash does not match: -    // - close the device node -    // - load the fpga bin file -    // - re-open the device node -    if (_fpga_ctrl->peek32(E100_REG_RB_MISC_TEST32) != file_hash){ -        _fpga_ctrl.reset(); -        e100_load_fpga(e100_fpga_image); -        _fpga_ctrl = e100_ctrl::make(node); -    } +    e100_load_fpga(e100_fpga_image); -    //setup clock control here to ensure that the FPGA has a good clock before we continue +    //////////////////////////////////////////////////////////////////// +    // Setup the FPGA clock over AUX SPI +    ////////////////////////////////////////////////////////////////////      bool dboard_clocks_diff = true;      if      (mb_eeprom.get("revision", "0") == "3") dboard_clocks_diff = false;      else if (mb_eeprom.get("revision", "0") == "4") dboard_clocks_diff = true; @@ -158,12 +138,32 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){      _aux_spi_iface = e100_ctrl::make_aux_spi_iface();      _clock_ctrl = e100_clock_ctrl::make(_aux_spi_iface, master_clock_rate, dboard_clocks_diff); +    //////////////////////////////////////////////////////////////////// +    // setup the main interface into fpga +    //  - do this after aux spi, because we share gpio147 +    //////////////////////////////////////////////////////////////////// +    const std::string node = device_addr["node"]; +    _fpga_ctrl = e100_ctrl::make(node); + +    //////////////////////////////////////////////////////////////////// +    // Initialize FPGA control communication +    //////////////////////////////////////////////////////////////////// +    fifo_ctrl_excelsior_config fifo_ctrl_config; +    fifo_ctrl_config.async_sid_base = E100_TX_ASYNC_SID; +    fifo_ctrl_config.num_async_chan = 1; +    fifo_ctrl_config.ctrl_sid_base = E100_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(_fpga_ctrl, fifo_ctrl_config); +      //Perform wishbone readback tests, these tests also write the hash      bool test_fail = false; -    UHD_MSG(status) << "Performing wishbone readback test... " << std::flush; +    UHD_MSG(status) << "Performing control readback test... " << std::flush; +    size_t hash = time(NULL);      for (size_t i = 0; i < 100; i++){ -        _fpga_ctrl->poke32(E100_REG_SR_MISC_TEST32, file_hash); -        test_fail = _fpga_ctrl->peek32(E100_REG_RB_MISC_TEST32) != file_hash; +        boost::hash_combine(hash, i); +        _fifo_ctrl->poke32(TOREG(SR_MISC+0), boost::uint32_t(hash)); +        test_fail = _fifo_ctrl->peek32(REG_RB_CONFIG0) != boost::uint32_t(hash);          if (test_fail) break; //exit loop on any failure      }      UHD_MSG(status) << ((test_fail)? " fail" : "pass") << std::endl; @@ -180,8 +180,7 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){      ////////////////////////////////////////////////////////////////////      // Create controller objects      //////////////////////////////////////////////////////////////////// -    _fpga_i2c_ctrl = i2c_core_100::make(_fpga_ctrl, E100_REG_SLAVE(3)); -    _fpga_spi_ctrl = spi_core_100::make(_fpga_ctrl, E100_REG_SLAVE(2)); +    _fpga_i2c_ctrl = i2c_core_200::make(_fifo_ctrl, TOREG(SR_I2C), REG_RB_I2C);      _data_transport = e100_make_mmap_zero_copy(_fpga_ctrl);      //////////////////////////////////////////////////////////////////// @@ -205,12 +204,17 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){      //^^^ clock created up top, just reg props here... ^^^      _tree->create<double>(mb_path / "tick_rate")          .publish(boost::bind(&e100_clock_ctrl::get_fpga_clock_rate, _clock_ctrl)) +        .subscribe(boost::bind(&fifo_ctrl_excelsior::set_tick_rate, _fifo_ctrl, _1))          .subscribe(boost::bind(&e100_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 = e100_codec_ctrl::make(_fpga_spi_ctrl); +    _codec_ctrl = e100_codec_ctrl::make(_fifo_ctrl/*spi*/);      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"); @@ -232,24 +236,37 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){      ////////////////////////////////////////////////////////////////////      // Create the GPSDO control      //////////////////////////////////////////////////////////////////// -    try{ -        _gps = gps_ctrl::make(e100_ctrl::make_gps_uart_iface(E100_UART_DEV_NODE)); -    } -    catch(std::exception &e){ -        UHD_MSG(error) << "An error occurred making GPSDO control: " << e.what() << std::endl; -    } -    if (_gps.get() != NULL and _gps->gps_detected()){ -        BOOST_FOREACH(const std::string &name, _gps->get_sensors()){ -            _tree->create<sensor_value_t>(mb_path / "sensors" / name) -                .publish(boost::bind(&gps_ctrl::get_sensor, _gps, name)); +    static const fs::path GPSDO_VOLATILE_PATH("/media/ram/e100_internal_gpsdo.cache"); +    if (not fs::exists(GPSDO_VOLATILE_PATH)) +    { +        UHD_MSG(status) << "Detecting internal GPSDO.... " << std::flush; +        try{ +            _gps = gps_ctrl::make(e100_ctrl::make_gps_uart_iface(E100_UART_DEV_NODE)); +        } +        catch(std::exception &e){ +            UHD_MSG(error) << "An error occurred making GPSDO control: " << e.what() << std::endl; +        } +        if (_gps and _gps->gps_detected()) +        { +            UHD_MSG(status) << "found" << std::endl; +            BOOST_FOREACH(const std::string &name, _gps->get_sensors()) +            { +                _tree->create<sensor_value_t>(mb_path / "sensors" / name) +                    .publish(boost::bind(&gps_ctrl::get_sensor, _gps, name)); +            } +        } +        else +        { +            UHD_MSG(status) << "not found" << std::endl; +            std::ofstream(GPSDO_VOLATILE_PATH.string().c_str(), std::ofstream::binary) << "42" << std::endl;          }      }      ////////////////////////////////////////////////////////////////////      // create frontend control objects      //////////////////////////////////////////////////////////////////// -    _rx_fe = rx_frontend_core_200::make(_fpga_ctrl, E100_REG_SR_ADDR(UE_SR_RX_FRONT)); -    _tx_fe = tx_frontend_core_200::make(_fpga_ctrl, E100_REG_SR_ADDR(UE_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(&e100_impl::update_rx_subdev_spec, this, _1)); @@ -278,13 +295,17 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){      ////////////////////////////////////////////////////////////////////      // create rx dsp control objects      //////////////////////////////////////////////////////////////////// -    _rx_dsps.push_back(rx_dsp_core_200::make( -        _fpga_ctrl, E100_REG_SR_ADDR(UE_SR_RX_DSP0), E100_REG_SR_ADDR(UE_SR_RX_CTRL0), E100_RX_SID_BASE + 0 -    )); -    _rx_dsps.push_back(rx_dsp_core_200::make( -        _fpga_ctrl, E100_REG_SR_ADDR(UE_SR_RX_DSP1), E100_REG_SR_ADDR(UE_SR_RX_CTRL1), E100_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), +            E100_RX_SID_BASE + dspno +        )); +          _rx_dsps[dspno]->set_link_rate(E100_RX_LINK_RATE_BPS);          _tree->access<double>(mb_path / "tick_rate")              .subscribe(boost::bind(&rx_dsp_core_200::set_tick_rate, _rx_dsps[dspno], _1)); @@ -307,7 +328,7 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){      // create tx dsp control objects      ////////////////////////////////////////////////////////////////////      _tx_dsp = tx_dsp_core_200::make( -        _fpga_ctrl, E100_REG_SR_ADDR(UE_SR_TX_DSP), E100_REG_SR_ADDR(UE_SR_TX_CTRL), E100_TX_ASYNC_SID +        _fifo_ctrl, TOREG(SR_TX_DSP), TOREG(SR_TX_CTRL), E100_TX_ASYNC_SID      );      _tx_dsp->set_link_rate(E100_TX_LINK_RATE_BPS);      _tree->access<double>(mb_path / "tick_rate") @@ -327,12 +348,12 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){      // create time control objects      ////////////////////////////////////////////////////////////////////      time64_core_200::readback_bases_type time64_rb_bases; -    time64_rb_bases.rb_hi_now = E100_REG_RB_TIME_NOW_HI; -    time64_rb_bases.rb_lo_now = E100_REG_RB_TIME_NOW_LO; -    time64_rb_bases.rb_hi_pps = E100_REG_RB_TIME_PPS_HI; -    time64_rb_bases.rb_lo_pps = E100_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, E100_REG_SR_ADDR(UE_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)); @@ -357,7 +378,7 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){      ////////////////////////////////////////////////////////////////////      // create user-defined control objects      //////////////////////////////////////////////////////////////////// -    _user = user_settings_core_200::make(_fpga_ctrl, E100_REG_SR_ADDR(UE_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)); @@ -383,7 +404,7 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){          .subscribe(boost::bind(&e100_impl::set_db_eeprom, this, "gdb", _1));      //create a new dboard interface and manager -    _dboard_iface = make_e100_dboard_iface(_fpga_ctrl, _fpga_i2c_ctrl, _fpga_spi_ctrl, _clock_ctrl, _codec_ctrl); +    _dboard_iface = make_e100_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, @@ -403,7 +424,11 @@ e100_impl::e100_impl(const uhd::device_addr_t &device_addr){      }      //initialize io handling -    this->io_init(); +    _recv_demuxer = recv_packet_demuxer::make(_data_transport, _rx_dsps.size(), E100_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 @@ -474,7 +499,7 @@ sensor_value_t e100_impl::get_ref_locked(void){  }  void e100_impl::check_fpga_compat(void){ -    const boost::uint32_t fpga_compat_num = _fpga_ctrl->peek32(E100_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/e100/e100_impl.hpp b/host/lib/usrp/e100/e100_impl.hpp index 381c085e0..6f64d4b80 100644 --- a/host/lib/usrp/e100/e100_impl.hpp +++ b/host/lib/usrp/e100/e100_impl.hpp @@ -18,17 +18,17 @@  #include "e100_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/usrp/subdev_spec.hpp>  #include <uhd/usrp/dboard_eeprom.hpp>  #include <uhd/usrp/mboard_eeprom.hpp> @@ -49,9 +49,10 @@ static const double          E100_RX_LINK_RATE_BPS = 166e6/3/2*2;  static const double          E100_TX_LINK_RATE_BPS = 166e6/3/1*2;  static const std::string     E100_I2C_DEV_NODE = "/dev/i2c-3";  static const std::string     E100_UART_DEV_NODE = "/dev/ttyO0"; -static const boost::uint16_t E100_FPGA_COMPAT_NUM = 10; -static const boost::uint32_t E100_RX_SID_BASE = 2; -static const boost::uint32_t E100_TX_ASYNC_SID = 1; +static const boost::uint16_t E100_FPGA_COMPAT_NUM = 11; +static const boost::uint32_t E100_RX_SID_BASE = 30; +static const boost::uint32_t E100_TX_ASYNC_SID = 10; +static const boost::uint32_t E100_CTRL_MSG_SID = 20;  static const double          E100_DEFAULT_CLOCK_RATE = 64e6;  static const std::string     E100_EEPROM_MAP_KEY = "E100"; @@ -87,8 +88,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; @@ -104,15 +105,12 @@ private:      //transports      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; diff --git a/host/lib/usrp/e100/e100_regs.hpp b/host/lib/usrp/e100/e100_regs.hpp index 75be2cfbe..654163dce 100644 --- a/host/lib/usrp/e100/e100_regs.hpp +++ b/host/lib/usrp/e100/e100_regs.hpp @@ -15,55 +15,45 @@  // along with this program.  If not, see <http://www.gnu.org/licenses/>.  // -//////////////////////////////////////////////////////////////// -// -//         Memory map for embedded 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_E100_REGS_HPP  #define INCLUDED_E100_REGS_HPP -///////////////////////////////////////////////////// -// Slave pointers +#include <boost/cstdint.hpp> -#define E100_REG_SLAVE(n) ((n)<<7) +#define TOREG(x) ((x)*4) -///////////////////////////////////////////////////// -// Slave 0 -- Misc Regs +#define localparam static const int -#define E100_REG_MISC_BASE E100_REG_SLAVE(0) +localparam SR_MISC         = 0;      // 5 +localparam SR_USER_REGS    = 5;      // 2 -#define E100_REG_MISC_LED        E100_REG_MISC_BASE + 0 -#define E100_REG_MISC_SW         E100_REG_MISC_BASE + 2 -#define E100_REG_MISC_CGEN_CTRL  E100_REG_MISC_BASE + 4 -#define E100_REG_MISC_CGEN_ST    E100_REG_MISC_BASE + 6 -#define E100_REG_MISC_TEST       E100_REG_MISC_BASE + 8 -#define E100_REG_MISC_RX_LEN     E100_REG_MISC_BASE + 10 -#define E100_REG_MISC_TX_LEN     E100_REG_MISC_BASE + 12 -#define E100_REG_MISC_XFER_RATE  E100_REG_MISC_BASE + 14 +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 E100_REG_UART_BASE E100_REG_SLAVE(1) +localparam SR_RX_CTRL1     = 128;     // 9 +localparam SR_RX_DSP1      = 138;     // 7 -#define E100_REG_UART_CLKDIV  E100_REG_UART_BASE + 0 -#define E100_REG_UART_TXLEVEL E100_REG_UART_BASE + 2 -#define E100_REG_UART_RXLEVEL E100_REG_UART_BASE + 4 -#define E100_REG_UART_TXCHAR  E100_REG_UART_BASE + 6 -#define E100_REG_UART_RXCHAR  E100_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 E100_REG_SPI_BASE E100_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_CONFIG0     TOREG(4) +#define REG_RB_CONFIG1     TOREG(5) +#define REG_RB_NUM_RX_DSP  TOREG(6)  //spi slave constants  #define UE_SPI_SS_AD9522    (1 << 3) @@ -71,67 +61,5 @@  #define UE_SPI_SS_TX_DB     (1 << 1)  #define UE_SPI_SS_RX_DB     (1 << 0) -//////////////////////////////////////////////// -// Slave 3 -- I2C Core - -#define E100_REG_I2C_BASE E100_REG_SLAVE(3) - -//////////////////////////////////////////////// -// Slave 5 -- Error messages buffer - -#define E100_REG_ERR_BUFF E100_REG_SLAVE(5) - -/////////////////////////////////////////////////// -// Slave 7 -- Readback Mux 32 - -#define E100_REG_RB_MUX_32_BASE  E100_REG_SLAVE(7) - -#define E100_REG_RB_TIME_NOW_HI     E100_REG_RB_MUX_32_BASE + 0 -#define E100_REG_RB_TIME_NOW_LO     E100_REG_RB_MUX_32_BASE + 4 -#define E100_REG_RB_TIME_PPS_HI     E100_REG_RB_MUX_32_BASE + 8 -#define E100_REG_RB_TIME_PPS_LO     E100_REG_RB_MUX_32_BASE + 12 -#define E100_REG_RB_MISC_TEST32     E100_REG_RB_MUX_32_BASE + 16 -#define E100_REG_RB_ERR_STATUS      E100_REG_RB_MUX_32_BASE + 20 -#define E100_REG_RB_COMPAT          E100_REG_RB_MUX_32_BASE + 24 -#define E100_REG_RB_GPIO            E100_REG_RB_MUX_32_BASE + 28 - -//////////////////////////////////////////////////// -// Slave 8 -- Settings Bus -// -// Output-only, no readback, 64 registers total -//  Each register must be written 64 bits at a time -//  First the address xxx_xx00 and then xxx_xx10 - -// 64 total regs in address space -#define UE_SR_RX_CTRL0 0       // 9 regs (+0 to +8) -#define UE_SR_RX_DSP0 10       // 4 regs (+0 to +3) -#define UE_SR_RX_CTRL1 16      // 9 regs (+0 to +8) -#define UE_SR_RX_DSP1 26       // 4 regs (+0 to +3) -#define UE_SR_ERR_CTRL 30      // 1 reg -#define UE_SR_TX_CTRL 32       // 4 regs (+0 to +3) -#define UE_SR_TX_DSP 38        // 3 regs (+0 to +2) - -#define UE_SR_TIME64 42        // 6 regs (+0 to +5) -#define UE_SR_RX_FRONT 48      // 5 regs (+0 to +4) -#define UE_SR_TX_FRONT 54      // 5 regs (+0 to +4) - -#define UE_SR_REG_TEST32 60    // 1 reg -#define UE_SR_CLEAR_FIFO 61    // 1 reg -#define UE_SR_GLOBAL_RESET 63  // 1 reg -#define UE_SR_USER_REGS 64     // 2 regs - -#define UE_SR_GPIO 128 - -#define E100_REG_SR_ADDR(n) (E100_REG_SLAVE(8) + (4*(n))) - -#define E100_REG_SR_MISC_TEST32        E100_REG_SR_ADDR(UE_SR_REG_TEST32) -#define E100_REG_SR_ERR_CTRL           E100_REG_SR_ADDR(UE_SR_ERR_CTRL) - -///////////////////////////////////////////////// -// Magic reset regs -//////////////////////////////////////////////// -#define E100_REG_CLEAR_FIFO         E100_REG_SR_ADDR(UE_SR_CLEAR_FIFO) -#define E100_REG_GLOBAL_RESET       E100_REG_SR_ADDR(UE_SR_GLOBAL_RESET) - -#endif +#endif /*INCLUDED_E100_REGS_HPP*/ diff --git a/host/lib/usrp/e100/include/linux/usrp_e.h b/host/lib/usrp/e100/include/linux/usrp_e.h index 37e9ee31a..f0512a40c 100644 --- a/host/lib/usrp/e100/include/linux/usrp_e.h +++ b/host/lib/usrp/e100/include/linux/usrp_e.h @@ -1,6 +1,6 @@  /* - *  Copyright (C) 2010 Ettus Research, LLC + *  Copyright (C) 2010-2012 Ettus Research, LLC   *   *  Written by Philip Balister <philip@opensdr.com>   * @@ -36,7 +36,7 @@ struct usrp_e_ctl32 {  #define USRP_E_GET_RB_INFO      _IOR(USRP_E_IOC_MAGIC, 0x27, struct usrp_e_ring_buffer_size_t)  #define USRP_E_GET_COMPAT_NUMBER _IO(USRP_E_IOC_MAGIC, 0x28) -#define USRP_E_COMPAT_NUMBER 3 +#define USRP_E_COMPAT_NUMBER 4  /* Flag defines */  #define RB_USER (1<<0) diff --git a/host/lib/usrp/e100/io_impl.cpp b/host/lib/usrp/e100/io_impl.cpp index 332fe76ae..4d521e222 100644 --- a/host/lib/usrp/e100/io_impl.cpp +++ b/host/lib/usrp/e100/io_impl.cpp @@ -15,27 +15,16 @@  // 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 <linux/usrp_e.h> //ioctl structures and constants  #include "e100_impl.hpp" -#include "e100_regs.hpp"  #include <uhd/utils/msg.hpp>  #include <uhd/utils/log.hpp>  #include <uhd/utils/tasks.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> -#include <boost/thread/thread.hpp> -#include <poll.h> //poll -#include <fcntl.h> //open, close -#include <sstream> -#include <fstream>  #include <boost/make_shared.hpp>  using namespace uhd; @@ -44,134 +33,7 @@ using namespace uhd::transport;  static const size_t vrt_send_header_offset_words32 = 1; -/*********************************************************************** - * io impl details (internal to this file) - * - pirate crew of 1 - * - bounded buffer - * - thread loop - * - vrt packet handler states - **********************************************************************/ -struct e100_impl::io_impl{ -    io_impl(void): -        false_alarm(0), async_msg_fifo(1000/*messages deep*/) -    { /* NOP */ } - -    double tick_rate; //set by update tick rate method -    e100_ctrl::sptr iface; //so handle irq can peek and poke -    void handle_irq(void); -    size_t false_alarm; -    //The data transport is listed first so that it is deconstructed last, -    //which is after the states and booty which may hold managed buffers. -    recv_packet_demuxer::sptr demuxer; - -    //a pirate's life is the life for me! -    void recv_pirate_loop( -        spi_iface::sptr //keep a sptr to iface which shares gpio147 -    ){ -        //open the GPIO and set it up for an IRQ -        std::ofstream edge_file("/sys/class/gpio/gpio147/edge"); -        edge_file << "rising" << std::endl << std::flush; -        edge_file.close(); -        int fd = ::open("/sys/class/gpio/gpio147/value", O_RDONLY); -        if (fd < 0) UHD_MSG(error) << "Unable to open GPIO for IRQ\n"; - -        while (not boost::this_thread::interruption_requested()){ -            pollfd pfd; -            pfd.fd = fd; -            pfd.events = POLLPRI | POLLERR; -            ssize_t ret = ::poll(&pfd, 1, 100/*ms*/); -            if (ret > 0) this->handle_irq(); -        } - -        //cleanup before thread exit -        ::close(fd); -    } -    bounded_buffer<async_metadata_t> async_msg_fifo; -    task::sptr pirate_task; -}; - -void e100_impl::io_impl::handle_irq(void){ -    //check the status of the async msg buffer -    const boost::uint32_t status = iface->peek32(E100_REG_RB_ERR_STATUS); -    if ((status & 0x3) == 0){ //not done or error -        //This could be a false-alarm because spi readback is mixed in. -        //So we just sleep for a bit rather than interrupt continuously. -        if (false_alarm++ > 3) boost::this_thread::sleep(boost::posix_time::milliseconds(1)); -        return; -    } -    false_alarm = 0; //its a real message, reset the count... -    //std::cout << boost::format("status: 0x%x") % status << std::endl; - -    //load the data struct and call the ioctl -    usrp_e_ctl32 data; -    data.offset = E100_REG_ERR_BUFF; -    data.count = status >> 16; -    iface->ioctl(USRP_E_READ_CTL32, &data); -    //for (size_t i = 0; i < data.count; i++){ -        //data.buf[i] = iface->peek32(E100_REG_ERR_BUFF + i*sizeof(boost::uint32_t)); -        //std::cout << boost::format("    buff[%u] = 0x%08x\n") % i % data.buf[i]; -    //} - -    //unpack the vrt header and process below... -    vrt::if_packet_info_t if_packet_info; -    if_packet_info.num_packet_words32 = data.count; -    try{vrt::if_hdr_unpack_le(data.buf, if_packet_info);} -    catch(const std::exception &e){ -        UHD_MSG(error) << "Error unpacking vrt header:\n" << e.what() << std::endl; -        goto prepare; -    } - -    //handle a tx async report message -    if (if_packet_info.sid == E100_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, data.buf, tick_rate); - -        //push the message onto the queue -        async_msg_fifo.push_with_pop_on_full(metadata); - -        //print some fastpath messages -        standard_async_msg_prints(metadata); -    } - -    //prepare for the next round -    prepare: -    iface->poke32(E100_REG_SR_ERR_CTRL, 1 << 0); //clear -    while ((iface->peek32(E100_REG_RB_ERR_STATUS) & (1 << 2)) == 0){} //wait for idle -    iface->poke32(E100_REG_SR_ERR_CTRL, 1 << 1); //start -} - -/*********************************************************************** - * Helper Functions - **********************************************************************/ -void e100_impl::io_init(void){ - -    //create new io impl -    _io_impl = UHD_PIMPL_MAKE(io_impl, ()); -    _io_impl->demuxer = recv_packet_demuxer::make(_data_transport, _rx_dsps.size(), E100_RX_SID_BASE); -    _io_impl->iface = _fpga_ctrl; - -    //clear fifo state machines -    _fpga_ctrl->poke32(E100_REG_CLEAR_FIFO, 0); - -    //allocate streamer weak ptrs containers -    _rx_streamers.resize(_rx_dsps.size()); -    _tx_streamers.resize(1/*known to be 1 dsp*/); - -    //prepare the async msg buffer for incoming messages -    _fpga_ctrl->poke32(E100_REG_SR_ERR_CTRL, 1 << 0); //clear -    while ((_fpga_ctrl->peek32(E100_REG_RB_ERR_STATUS) & (1 << 2)) == 0){} //wait for idle -    _fpga_ctrl->poke32(E100_REG_SR_ERR_CTRL, 1 << 1); //start - -    //spawn a pirate, yarrr! -    _io_impl->pirate_task = task::make(boost::bind( -        &e100_impl::io_impl::recv_pirate_loop, _io_impl.get(), _aux_spi_iface -    )); -} -  void e100_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++){ @@ -254,8 +116,7 @@ void e100_impl::update_tx_subdev_spec(const uhd::usrp::subdev_spec_t &spec){  bool e100_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);  }  /*********************************************************************** @@ -300,7 +161,7 @@ rx_streamer::sptr e100_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] | 
