diff options
Diffstat (limited to 'host/lib/usrp/b100')
| -rw-r--r-- | host/lib/usrp/b100/CMakeLists.txt | 3 | ||||
| -rw-r--r-- | host/lib/usrp/b100/b100_ctrl.cpp | 257 | ||||
| -rw-r--r-- | host/lib/usrp/b100/b100_ctrl.hpp | 70 | ||||
| -rw-r--r-- | host/lib/usrp/b100/b100_impl.cpp | 132 | ||||
| -rw-r--r-- | host/lib/usrp/b100/b100_impl.hpp | 31 | ||||
| -rw-r--r-- | host/lib/usrp/b100/b100_regs.hpp | 116 | ||||
| -rw-r--r-- | host/lib/usrp/b100/ctrl_packet.hpp | 75 | ||||
| -rw-r--r-- | host/lib/usrp/b100/dboard_iface.cpp | 2 | ||||
| -rw-r--r-- | host/lib/usrp/b100/io_impl.cpp | 71 | 
9 files changed, 129 insertions, 628 deletions
| 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_ctrl.cpp b/host/lib/usrp/b100/b100_ctrl.cpp deleted file mode 100644 index e6136c00e..000000000 --- a/host/lib/usrp/b100/b100_ctrl.cpp +++ /dev/null @@ -1,257 +0,0 @@ -// -// Copyright 2011 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 "b100_ctrl.hpp" -#include <uhd/transport/bounded_buffer.hpp> -#include <uhd/transport/usb_zero_copy.hpp> -#include <uhd/transport/zero_copy.hpp> -#include <uhd/transport/vrt_if_packet.hpp> -#include <uhd/utils/thread_priority.hpp> -#include <uhd/utils/msg.hpp> -#include <uhd/utils/tasks.hpp> -#include <uhd/types/metadata.hpp> -#include <uhd/types/serial.hpp> -#include "ctrl_packet.hpp" -#include <boost/thread/thread.hpp> -#include <boost/bind.hpp> -#include <uhd/exception.hpp> - -using namespace uhd::transport; -using namespace uhd; - -bool b100_ctrl_debug = false; - -class b100_ctrl_impl : public b100_ctrl { -public: -    b100_ctrl_impl(uhd::transport::zero_copy_if::sptr ctrl_transport): -        sync_ctrl_fifo(2), -        _ctrl_transport(ctrl_transport), -        _seq(0) -    { -        viking_marauder = task::make(boost::bind(&b100_ctrl_impl::viking_marauder_loop, this)); -    } - -    ~b100_ctrl_impl(void){ -        //stop the marauder first so it cant access deconstructed objects -        viking_marauder.reset(); -    } - -    int write(boost::uint32_t addr, const ctrl_data_t &data); -    ctrl_data_t read(boost::uint32_t addr, size_t len); - -    bool get_ctrl_data(ctrl_data_t &pkt_data, double timeout); - -    void poke32(wb_addr_type addr, boost::uint32_t data){ -        boost::mutex::scoped_lock lock(_ctrl_mutex); - -        ctrl_data_t words(2); -        words[0] = data & 0x0000FFFF; -        words[1] = data >> 16; -        this->write(addr, words); -    } - -    boost::uint32_t peek32(wb_addr_type addr){ -        boost::mutex::scoped_lock lock(_ctrl_mutex); - -        ctrl_data_t words = this->read(addr, 2); -        return boost::uint32_t((boost::uint32_t(words[1]) << 16) | words[0]); -    } - -    void poke16(wb_addr_type addr, boost::uint16_t data){ -        boost::mutex::scoped_lock lock(_ctrl_mutex); - -        ctrl_data_t words(1); -        words[0] = data; -        this->write(addr, words); -    } - -    boost::uint16_t peek16(wb_addr_type addr){ -        boost::mutex::scoped_lock lock(_ctrl_mutex); - -        ctrl_data_t words = this->read(addr, 1); -        return boost::uint16_t(words[0]); -    } - -    void set_async_cb(const async_cb_type &async_cb){ -        boost::mutex::scoped_lock lock(_async_mutex); -        _async_cb = async_cb; -    } - -private: -    int send_pkt(boost::uint16_t *cmd); - -    //änd hërë wë gö ä-Vïkïng för äsynchronous control packets -    void viking_marauder_loop(void); -    bounded_buffer<ctrl_data_t> sync_ctrl_fifo; -    async_cb_type _async_cb; -    task::sptr viking_marauder; - -    uhd::transport::zero_copy_if::sptr _ctrl_transport; -    boost::uint8_t _seq; -    boost::mutex _ctrl_mutex, _async_mutex; -}; - -/*********************************************************************** - * helper functions for packing/unpacking control packets - **********************************************************************/ -void pack_ctrl_pkt(boost::uint16_t *pkt_buff, -                          const ctrl_pkt_t &pkt){ -    //first two bits are OP -    //next six bits are CALLBACKS -    //next 8 bits are SEQUENCE -    //next 16 bits are LENGTH (16-bit word) -    //next 32 bits are ADDRESS (16-bit word LSW) -    //then DATA (28 16-bit words) -    pkt_buff[0] = (boost::uint16_t(pkt.pkt_meta.op) << 14) | (boost::uint16_t(pkt.pkt_meta.callbacks) << 8) | pkt.pkt_meta.seq; -    pkt_buff[1] = pkt.pkt_meta.len; -    pkt_buff[2] = (pkt.pkt_meta.addr & 0x00000FFF); -    pkt_buff[3] = 0x0000; //address high bits always 0 on this device - -    for(size_t i = 0; i < pkt.data.size(); i++) { -        pkt_buff[4+i] = pkt.data[i]; -    } -} - -void unpack_ctrl_pkt(const boost::uint16_t *pkt_buff, -                            ctrl_pkt_t &pkt){ -    pkt.pkt_meta.seq = pkt_buff[0] & 0xFF; -    pkt.pkt_meta.op = CTRL_PKT_OP_READ; //really this is useless -    pkt.pkt_meta.len = pkt_buff[1]; -    pkt.pkt_meta.callbacks = 0; //callbacks aren't implemented yet -    pkt.pkt_meta.addr = pkt_buff[2] | boost::uint32_t(pkt_buff[3] << 16); - -    //let's check this so we don't go pushing 64K of crap onto the pkt -    if(pkt.pkt_meta.len > CTRL_PACKET_DATA_LENGTH) { -        throw uhd::runtime_error("Received control packet too long"); -    } - -    for(int i = 4; i < 4+pkt.pkt_meta.len; i++) pkt.data.push_back(pkt_buff[i]); -} - -int b100_ctrl_impl::send_pkt(boost::uint16_t *cmd) { -    managed_send_buffer::sptr sbuf = _ctrl_transport->get_send_buff(); -    if(!sbuf.get()) { -        throw uhd::runtime_error("Control channel send error"); -    } - -    //FIXME there's a better way to do this -    for(size_t i = 0; i < (CTRL_PACKET_LENGTH / sizeof(boost::uint16_t)); i++) { -        sbuf->cast<boost::uint16_t *>()[i] = cmd[i]; -    } -    sbuf->commit(CTRL_PACKET_LENGTH); //fixed size transaction -    return 0; -} - -int b100_ctrl_impl::write(boost::uint32_t addr, const ctrl_data_t &data) { -    UHD_ASSERT_THROW(data.size() <= (CTRL_PACKET_DATA_LENGTH / sizeof(boost::uint16_t))); -    ctrl_pkt_t pkt; -    pkt.data = data; -    pkt.pkt_meta.op = CTRL_PKT_OP_WRITE; -    pkt.pkt_meta.callbacks = 0; -    pkt.pkt_meta.seq = _seq++; -    pkt.pkt_meta.len = pkt.data.size(); -    pkt.pkt_meta.addr = addr; -    boost::uint16_t pkt_buff[CTRL_PACKET_LENGTH / sizeof(boost::uint16_t)] = {}; - -    pack_ctrl_pkt(pkt_buff, pkt); -    size_t result = send_pkt(pkt_buff); -    return result; -} - -ctrl_data_t b100_ctrl_impl::read(boost::uint32_t addr, size_t len) { -    UHD_ASSERT_THROW(len <= (CTRL_PACKET_DATA_LENGTH / sizeof(boost::uint16_t))); - -    ctrl_pkt_t pkt; -    pkt.pkt_meta.op = CTRL_PKT_OP_READ; -    pkt.pkt_meta.callbacks = 0; -    pkt.pkt_meta.seq = _seq++; -    pkt.pkt_meta.len = len; -    pkt.pkt_meta.addr = addr; -    boost::uint16_t pkt_buff[CTRL_PACKET_LENGTH / sizeof(boost::uint16_t)] = {}; - -    //flush anything that might be in the queue -    while (get_ctrl_data(pkt.data, 0.0)){ -        UHD_MSG(error) << "B100: control read found unexpected packet." << std::endl; -    } - -    pack_ctrl_pkt(pkt_buff, pkt); -    send_pkt(pkt_buff); - -    //block with timeout waiting for the response to appear -    if (not get_ctrl_data(pkt.data, 0.1)) throw uhd::runtime_error( -        "B100: timeout waiting for control response packet." -    ); - -    return pkt.data; -} - -/*********************************************************************** - * Viking marauders go pillaging for asynchronous control packets in the - * control response endpoint. Sync packets go in sync_ctrl_fifo, - * async TX error messages go in async_msg_fifo. sync_ctrl_fifo should - * never have more than 1 message in it, since it's expected that we'll - * wait for a control operation to finish before starting another one. - **********************************************************************/ -void b100_ctrl_impl::viking_marauder_loop(void){ -    set_thread_priority_safe(); - -    while (not boost::this_thread::interruption_requested()){ -        managed_recv_buffer::sptr rbuf = _ctrl_transport->get_recv_buff(1.0); -        if(rbuf.get() == NULL) continue; //that's ok, there are plenty of villages to pillage! -        const boost::uint16_t *pkt_buf = rbuf->cast<const boost::uint16_t *>(); - -        if(pkt_buf[0] >> 8 == CTRL_PACKET_HEADER_MAGIC) { -            //so it's got a control packet header, let's parse it. -            ctrl_pkt_t pkt; -            unpack_ctrl_pkt(pkt_buf, pkt); - -            if(pkt.pkt_meta.seq != boost::uint8_t(_seq - 1)) { -                UHD_MSG(error) -                    << "Sequence error on control channel." << std::endl -                    << "Exiting control loop." << std::endl -                ; -                return; -            } -            if(pkt.pkt_meta.len > (CTRL_PACKET_LENGTH - CTRL_PACKET_HEADER_LENGTH)) { -                UHD_MSG(error) -                    << "Control channel packet length too long" << std::endl -                    << "Exiting control loop." << std::endl -                ; -                return; -            } - -            //push it onto the queue -            sync_ctrl_fifo.push_with_pop_on_full(pkt.data); -        } -        else{ //otherwise let the async callback handle it -            boost::mutex::scoped_lock lock(_async_mutex); -            if (not _async_cb.empty()) _async_cb(rbuf); -        } -    } -} - -bool b100_ctrl_impl::get_ctrl_data(ctrl_data_t &pkt_data, double timeout){ -    boost::this_thread::disable_interruption di; //disable because the wait can throw -    return sync_ctrl_fifo.pop_with_timed_wait(pkt_data, timeout); -} - -/*********************************************************************** - * Public make function for b100_ctrl interface - **********************************************************************/ -b100_ctrl::sptr b100_ctrl::make(uhd::transport::zero_copy_if::sptr ctrl_transport){ -    return sptr(new b100_ctrl_impl(ctrl_transport)); -} diff --git a/host/lib/usrp/b100/b100_ctrl.hpp b/host/lib/usrp/b100/b100_ctrl.hpp deleted file mode 100644 index 74884d525..000000000 --- a/host/lib/usrp/b100/b100_ctrl.hpp +++ /dev/null @@ -1,70 +0,0 @@ -// -// Copyright 2011 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_B100_CTRL_HPP -#define INCLUDED_B100_CTRL_HPP - -#include "wb_iface.hpp" -#include <uhd/transport/usb_zero_copy.hpp> -#include <uhd/types/serial.hpp> -#include <boost/shared_ptr.hpp> -#include <boost/utility.hpp> -#include "ctrl_packet.hpp" -#include <boost/function.hpp> - -class b100_ctrl : boost::noncopyable, public wb_iface{ -public: -    typedef boost::shared_ptr<b100_ctrl> sptr; -    typedef boost::function<void(uhd::transport::managed_recv_buffer::sptr)> async_cb_type; - -    /*! -     * Make a USRP control object from a data transport -     * \param ctrl_transport a USB data transport -     * \return a new b100 control object -     */ -    static sptr make(uhd::transport::zero_copy_if::sptr ctrl_transport); - -    //! set an async callback for messages -    virtual void set_async_cb(const async_cb_type &async_cb) = 0; - -    /*! -     * Write a byte vector to an FPGA register -     * \param addr the FPGA register address -     * \param bytes the data to write -     * \return 0 on success, error code on failure -     */ -    virtual int write(boost::uint32_t addr, const ctrl_data_t &data) = 0; - -    /*! -     * Read a byte vector from an FPGA register (blocking read) -     * \param addr the FPGA register address -     * \param len the length of the read -     * \return a vector of bytes from the register(s) in question -     */ -    virtual ctrl_data_t read(boost::uint32_t addr, size_t len) = 0; - -    /*! -     * Get a sync ctrl packet (blocking) -     * \param the packet data buffer -     * \param the timeout value -     * \return true if it got something -     */ -    virtual bool get_ctrl_data(ctrl_data_t &pkt_data, double timeout) = 0; - -}; - -#endif /* INCLUDED_B100_CTRL_HPP */ diff --git a/host/lib/usrp/b100/b100_impl.cpp b/host/lib/usrp/b100/b100_impl.cpp index b1d9a577a..c4d050242 100644 --- a/host/lib/usrp/b100/b100_impl.cpp +++ b/host/lib/usrp/b100/b100_impl.cpp @@ -17,9 +17,8 @@  #include "apply_corrections.hpp"  #include "b100_impl.hpp" -#include "b100_ctrl.hpp" +#include "b100_regs.hpp"  #include <uhd/transport/usb_control.hpp> -#include "ctrl_packet.hpp"  #include <uhd/utils/msg.hpp>  #include <uhd/exception.hpp>  #include <uhd/utils/static.hpp> @@ -30,8 +29,8 @@  #include <boost/filesystem.hpp>  #include <boost/thread/thread.hpp>  #include <boost/lexical_cast.hpp> -#include "b100_regs.hpp"  #include <cstdio> +#include <iostream>  using namespace uhd;  using namespace uhd::usrp; @@ -82,13 +81,10 @@ static device_addrs_t b100_find(const device_addr_t &hint)              b100_fw_image = find_image_path(hint.get("fw", B100_FW_FILE_NAME));          }          catch(...){ -            UHD_MSG(warning) << boost::format( -                "Could not locate B100 firmware.\n" -                "Please install the images package.\n" -            ); +            UHD_MSG(warning) << boost::format("Could not locate B100 firmware. %s\n") % print_images_error();              return b100_addrs;          } -        UHD_LOG << "the  firmware image: " << b100_fw_image << std::endl; +        UHD_LOG << "the firmware image: " << b100_fw_image << std::endl;          usb_control::sptr control;          try{control = usb_control::make(handle, 0);} @@ -114,7 +110,7 @@ static device_addrs_t b100_find(const device_addr_t &hint)              catch(const uhd::exception &){continue;} //ignore claimed              fx2_ctrl::sptr fx2_ctrl = fx2_ctrl::make(control); -            const mboard_eeprom_t mb_eeprom = mboard_eeprom_t(*fx2_ctrl, mboard_eeprom_t::MAP_B100); +            const mboard_eeprom_t mb_eeprom = mboard_eeprom_t(*fx2_ctrl, B100_EEPROM_MAP_KEY);              device_addr_t new_addr;              new_addr["type"] = "b100";              new_addr["name"] = mb_eeprom["name"]; @@ -187,10 +183,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, @@ -198,17 +194,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 &){ @@ -216,7 +217,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; @@ -226,8 +227,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 @@ -241,6 +241,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 @@ -250,21 +254,21 @@ 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      ////////////////////////////////////////////////////////////////////      _tree->create<std::string>("/name").set("B-Series Device");      const fs_path mb_path = "/mboards/0"; -    _tree->create<std::string>(mb_path / "name").set("B100 (B-Hundo)"); +    _tree->create<std::string>(mb_path / "name").set("B100"); +    _tree->create<std::string>(mb_path / "codename").set("B-Hundo");      _tree->create<std::string>(mb_path / "load_eeprom")          .subscribe(boost::bind(&fx2_ctrl::usrp_load_eeprom, _fx2_ctrl, _1));      ////////////////////////////////////////////////////////////////////      // setup the mboard eeprom      //////////////////////////////////////////////////////////////////// -    const mboard_eeprom_t mb_eeprom(*_fx2_ctrl, mboard_eeprom_t::MAP_B100); +    const mboard_eeprom_t mb_eeprom(*_fx2_ctrl, B100_EEPROM_MAP_KEY);      _tree->create<mboard_eeprom_t>(mb_path / "eeprom")          .set(mb_eeprom)          .subscribe(boost::bind(&b100_impl::set_mb_eeprom, this, _1)); @@ -275,12 +279,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"); @@ -302,8 +311,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)); @@ -332,13 +341,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)); @@ -361,7 +374,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") @@ -381,12 +394,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)); @@ -410,7 +423,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)); @@ -424,6 +437,9 @@ b100_impl::b100_impl(const device_addr_t &device_addr){      tx_db_eeprom.load(*_fpga_i2c_ctrl, I2C_ADDR_TX_A);      gdb_eeprom.load(*_fpga_i2c_ctrl, I2C_ADDR_TX_A ^ 5); +    //disable rx dc offset if LFRX +    if (rx_db_eeprom.id == 0x000f) _tree->access<bool>(rx_fe_path / "dc_offset" / "enable").set(false); +      //create the properties and register subscribers      _tree->create<dboard_eeprom_t>(mb_path / "dboards/A/rx_eeprom")          .set(rx_db_eeprom) @@ -436,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, @@ -456,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 @@ -481,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){ @@ -493,13 +512,14 @@ void b100_impl::check_fw_compat(void){      if (fw_compat_num != B100_FW_COMPAT_NUM){          throw uhd::runtime_error(str(boost::format(              "Expected firmware compatibility number 0x%x, but got 0x%x:\n" -            "The firmware build is not compatible with the host code build." -        ) % B100_FW_COMPAT_NUM % fw_compat_num)); +            "The firmware build is not compatible with the host code build.\n" +            "%s" +        ) % B100_FW_COMPAT_NUM % fw_compat_num % print_images_error()));      }  }  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; @@ -509,7 +529,8 @@ void b100_impl::check_fpga_compat(void){          throw uhd::runtime_error(str(boost::format(              "Expected FPGA compatibility number %d, but got %d:\n"              "The FPGA build is not compatible with the host code build." -        ) % int(B100_FPGA_COMPAT_NUM) % fpga_major)); +            "%s" +        ) % int(B100_FPGA_COMPAT_NUM) % fpga_major % print_images_error()));      }      _tree->create<std::string>("/mboards/0/fpga_version").set(str(boost::format("%u.%u") % fpga_major % fpga_minor));  } @@ -523,7 +544,7 @@ double b100_impl::update_rx_codec_gain(const double gain){  }  void b100_impl::set_mb_eeprom(const uhd::usrp::mboard_eeprom_t &mb_eeprom){ -    mb_eeprom.commit(*_fx2_ctrl, mboard_eeprom_t::MAP_B100); +    mb_eeprom.commit(*_fx2_ctrl, B100_EEPROM_MAP_KEY);  }  void b100_impl::set_db_eeprom(const std::string &type, const uhd::usrp::dboard_eeprom_t &db_eeprom){ @@ -533,6 +554,19 @@ void b100_impl::set_db_eeprom(const std::string &type, const uhd::usrp::dboard_e  }  void b100_impl::update_clock_source(const std::string &source){ + +    if (source == "pps_sync"){ +        _clock_ctrl->use_external_ref(); +        _fifo_ctrl->poke32(TOREG(SR_MISC+2), 1); +        return; +    } +    if (source == "_pps_sync_"){ +        _clock_ctrl->use_external_ref(); +        _fifo_ctrl->poke32(TOREG(SR_MISC+2), 3); +        return; +    } +    _fifo_ctrl->poke32(TOREG(SR_MISC+2), 0); +      if      (source == "auto")     _clock_ctrl->use_auto_ref();      else if (source == "internal") _clock_ctrl->use_internal_ref();      else if (source == "external") _clock_ctrl->use_external_ref(); diff --git a/host/lib/usrp/b100/b100_impl.hpp b/host/lib/usrp/b100/b100_impl.hpp index 82d5a5f53..68d7043a1 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,12 +46,14 @@  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 = 0x09; -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";  #define I2C_ADDR_TX_A       (I2C_DEV_EEPROM | 0x4)  #define I2C_ADDR_RX_A       (I2C_DEV_EEPROM | 0x5) @@ -89,8 +90,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; @@ -99,20 +100,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; @@ -135,7 +133,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/ctrl_packet.hpp b/host/lib/usrp/b100/ctrl_packet.hpp deleted file mode 100644 index bab1f0de1..000000000 --- a/host/lib/usrp/b100/ctrl_packet.hpp +++ /dev/null @@ -1,75 +0,0 @@ -// -// Copyright 2011 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_CTRL_PACKET_HPP -#define INCLUDED_CTRL_PACKET_HPP - -#include <uhd/config.hpp> -#include <boost/cstdint.hpp> -#include <uhd/types/serial.hpp> - -typedef std::vector<boost::uint16_t> ctrl_data_t; - -/*! - * Control packet operation type - */ -enum ctrl_pkt_op_t {  -    CTRL_PKT_OP_WRITE = 1, -    CTRL_PKT_OP_READ = 2, -    CTRL_PKT_OP_READBACK = 3 -}; - -/*! - * Control packet transaction length - */ -const size_t CTRL_PACKET_LENGTH = 32; -const size_t CTRL_PACKET_HEADER_LENGTH = 8; -const size_t CTRL_PACKET_DATA_LENGTH = 24; //=length-header - -/*! - * Control packet header magic value - */ -const boost::uint8_t CTRL_PACKET_HEADER_MAGIC = 0xAA; - -/*!  - * Callback triggers for readback operation - */ -//FIXME: these are not real numbers, callbacks aren't implemented yet -const boost::uint16_t CTRL_PACKET_CALLBACK_SPI = 0x0001; -const boost::uint16_t CTRL_PACKET_CALLBACK_I2C = 0x0002; -//and so on - -/*! - * Metadata structure to describe a control packet - */ -struct UHD_API ctrl_pkt_meta_t { -    ctrl_pkt_op_t op; -    boost::uint8_t callbacks; -    boost::uint8_t seq; -    boost::uint16_t len; -    boost::uint32_t addr; -}; - -/*!  - * Full control packet structure - */ -struct UHD_API ctrl_pkt_t { -    ctrl_pkt_meta_t pkt_meta; -    ctrl_data_t data; -}; - -#endif /* INCLUDED_CTRL_PACKET_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 05d701313..723756dcc 100644 --- a/host/lib/usrp/b100/io_impl.cpp +++ b/host/lib/usrp/b100/io_impl.cpp @@ -15,15 +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 "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> @@ -36,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(); @@ -110,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++){ @@ -180,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);  }  /*********************************************************************** @@ -226,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] | 
