diff options
| -rw-r--r-- | host/lib/usrp/CMakeLists.txt | 2 | ||||
| -rw-r--r-- | host/lib/usrp/b100/CMakeLists.txt | 15 | ||||
| -rw-r--r-- | host/lib/usrp/b100/b100_ctrl.cpp | 74 | ||||
| -rw-r--r-- | host/lib/usrp/b100/b100_ctrl.hpp | 9 | ||||
| -rw-r--r-- | host/lib/usrp/b100/b100_iface.hpp | 5 | ||||
| -rw-r--r-- | host/lib/usrp/b100/b100_impl.cpp | 365 | ||||
| -rw-r--r-- | host/lib/usrp/b100/b100_impl.hpp | 197 | ||||
| -rw-r--r-- | host/lib/usrp/b100/clock_ctrl.cpp | 13 | ||||
| -rw-r--r-- | host/lib/usrp/b100/clock_ctrl.hpp | 6 | ||||
| -rw-r--r-- | host/lib/usrp/b100/codec_ctrl.cpp | 8 | ||||
| -rw-r--r-- | host/lib/usrp/b100/codec_ctrl.hpp | 4 | ||||
| -rw-r--r-- | host/lib/usrp/b100/dboard_iface.cpp | 59 | ||||
| -rw-r--r-- | host/lib/usrp/b100/io_impl.cpp | 155 | ||||
| -rw-r--r-- | host/lib/usrp/cores/time64_core_200.cpp | 6 | ||||
| -rw-r--r-- | host/lib/usrp/cores/time64_core_200.hpp | 2 | ||||
| -rw-r--r-- | host/lib/usrp/cores/wb_iface.hpp | 3 | ||||
| -rw-r--r-- | host/lib/usrp/fx2/fx2_ctrl.cpp | 36 | ||||
| -rw-r--r-- | host/lib/usrp/fx2/fx2_ctrl.hpp | 5 | ||||
| -rw-r--r-- | host/lib/usrp/usrp2/usrp2_impl.cpp | 10 | 
19 files changed, 584 insertions, 390 deletions
| diff --git a/host/lib/usrp/CMakeLists.txt b/host/lib/usrp/CMakeLists.txt index 2a9939d0b..8ea7c2fe0 100644 --- a/host/lib/usrp/CMakeLists.txt +++ b/host/lib/usrp/CMakeLists.txt @@ -35,5 +35,5 @@ INCLUDE_SUBDIRECTORY(dboard)  INCLUDE_SUBDIRECTORY(fx2)  #INCLUDE_SUBDIRECTORY(usrp1)  INCLUDE_SUBDIRECTORY(usrp2) -#INCLUDE_SUBDIRECTORY(b100) +INCLUDE_SUBDIRECTORY(b100)  #INCLUDE_SUBDIRECTORY(e100) diff --git a/host/lib/usrp/b100/CMakeLists.txt b/host/lib/usrp/b100/CMakeLists.txt index 28429c186..1237f52d1 100644 --- a/host/lib/usrp/b100/CMakeLists.txt +++ b/host/lib/usrp/b100/CMakeLists.txt @@ -26,22 +26,11 @@ 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}/clock_ctrl.hpp          ${CMAKE_CURRENT_SOURCE_DIR}/codec_ctrl.cpp -        ${CMAKE_CURRENT_SOURCE_DIR}/codec_ctrl.hpp -        ${CMAKE_CURRENT_SOURCE_DIR}/codec_impl.cpp -        ${CMAKE_CURRENT_SOURCE_DIR}/ctrl_packet.hpp -        ${CMAKE_CURRENT_SOURCE_DIR}/dboard_impl.cpp          ${CMAKE_CURRENT_SOURCE_DIR}/dboard_iface.cpp -        ${CMAKE_CURRENT_SOURCE_DIR}/dsp_impl.cpp          ${CMAKE_CURRENT_SOURCE_DIR}/io_impl.cpp -        ${CMAKE_CURRENT_SOURCE_DIR}/mboard_impl.cpp -        ${CMAKE_CURRENT_SOURCE_DIR}/b100_ctrl.cpp -        ${CMAKE_CURRENT_SOURCE_DIR}/b100_ctrl.hpp -        ${CMAKE_CURRENT_SOURCE_DIR}/b100_iface.cpp -        ${CMAKE_CURRENT_SOURCE_DIR}/b100_iface.hpp -        ${CMAKE_CURRENT_SOURCE_DIR}/b100_impl.cpp -        ${CMAKE_CURRENT_SOURCE_DIR}/b100_impl.hpp      )  ENDIF(ENABLE_B100) diff --git a/host/lib/usrp/b100/b100_ctrl.cpp b/host/lib/usrp/b100/b100_ctrl.cpp index 6d415facc..3f6d0d86e 100644 --- a/host/lib/usrp/b100/b100_ctrl.cpp +++ b/host/lib/usrp/b100/b100_ctrl.cpp @@ -36,7 +36,7 @@ bool b100_ctrl_debug = false;  class b100_ctrl_impl : public b100_ctrl {  public: -    b100_ctrl_impl(uhd::transport::usb_zero_copy::sptr ctrl_transport) :  +    b100_ctrl_impl(uhd::transport::zero_copy_if::sptr ctrl_transport) :          sync_ctrl_fifo(2),          async_msg_fifo(100),          _ctrl_transport(ctrl_transport), @@ -46,29 +46,61 @@ public:          viking_marauders.create_thread(boost::bind(&b100_ctrl_impl::viking_marauder_loop, this, boost::ref(spawn_barrier)));          spawn_barrier.wait();      } -     +      int write(boost::uint32_t addr, const ctrl_data_t &data);      ctrl_data_t read(boost::uint32_t addr, size_t len); -     +      ~b100_ctrl_impl(void) {          viking_marauders.interrupt_all();          viking_marauders.join_all();      } -     +      bool get_ctrl_data(ctrl_data_t &pkt_data, double timeout);      bool recv_async_msg(uhd::async_metadata_t &async_metadata, 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]); +    } +  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(boost::barrier &);      bounded_buffer<ctrl_data_t> sync_ctrl_fifo;      bounded_buffer<async_metadata_t> async_msg_fifo;      boost::thread_group viking_marauders; -     -    uhd::transport::usb_zero_copy::sptr _ctrl_transport; + +    uhd::transport::zero_copy_if::sptr _ctrl_transport;      boost::uint8_t _seq; +    boost::mutex _ctrl_mutex;  };  /*********************************************************************** @@ -86,7 +118,7 @@ void pack_ctrl_pkt(boost::uint16_t *pkt_buff,      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];      } @@ -99,7 +131,7 @@ void unpack_ctrl_pkt(const boost::uint16_t *pkt_buff,      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"); @@ -113,7 +145,7 @@ int b100_ctrl_impl::send_pkt(boost::uint16_t *cmd) {      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]; @@ -132,7 +164,7 @@ int b100_ctrl_impl::write(boost::uint32_t addr, const ctrl_data_t &data) {      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; @@ -151,7 +183,7 @@ ctrl_data_t b100_ctrl_impl::read(boost::uint32_t addr, size_t len) {      pack_ctrl_pkt(pkt_buff, pkt);      send_pkt(pkt_buff); -     +      //loop around waiting for the response to appear      while(!get_ctrl_data(pkt.data, 0.05)); @@ -168,24 +200,24 @@ ctrl_data_t b100_ctrl_impl::read(boost::uint32_t addr, size_t len) {  void b100_ctrl_impl::viking_marauder_loop(boost::barrier &spawn_barrier) {      spawn_barrier.wait();      set_thread_priority_safe(); -     +      while (not boost::this_thread::interruption_requested()){          managed_recv_buffer::sptr rbuf = _ctrl_transport->get_recv_buff();          if(!rbuf.get()) 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)) {                  throw uhd::runtime_error("Sequence error on control channel");              }              if(pkt.pkt_meta.len > (CTRL_PACKET_LENGTH - CTRL_PACKET_HEADER_LENGTH)) {                  throw uhd::runtime_error("Control channel packet length too long");              } -         +              //push it onto the queue              sync_ctrl_fifo.push_with_wait(pkt.data);          } else { //it's an async status pkt @@ -194,8 +226,8 @@ void b100_ctrl_impl::viking_marauder_loop(boost::barrier &spawn_barrier) {              if_packet_info.num_packet_words32 = rbuf->size()/sizeof(boost::uint32_t);              const boost::uint32_t *vrt_hdr = rbuf->cast<const boost::uint32_t *>();              vrt::if_hdr_unpack_le(vrt_hdr, if_packet_info); -             -            if(    if_packet_info.sid == B100_ASYNC_SID + +            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; @@ -207,7 +239,7 @@ void b100_ctrl_impl::viking_marauder_loop(boost::barrier &spawn_barrier) {                  metadata.event_code = async_metadata_t::event_code_t(sph::get_context_code(vrt_hdr, if_packet_info));                  async_msg_fifo.push_with_pop_on_full(metadata);                  if (metadata.event_code & -                    ( async_metadata_t::EVENT_CODE_UNDERFLOW  +                    ( async_metadata_t::EVENT_CODE_UNDERFLOW                      | async_metadata_t::EVENT_CODE_UNDERFLOW_IN_PACKET)                  ) UHD_MSG(fastpath) << "U";                  else if (metadata.event_code & @@ -234,6 +266,6 @@ bool b100_ctrl_impl::recv_async_msg(uhd::async_metadata_t &async_metadata, doubl  /***********************************************************************   * Public make function for b100_ctrl interface   **********************************************************************/ -b100_ctrl::sptr b100_ctrl::make(uhd::transport::usb_zero_copy::sptr ctrl_transport){ +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 index 17887181d..85e7530f3 100644 --- a/host/lib/usrp/b100/b100_ctrl.hpp +++ b/host/lib/usrp/b100/b100_ctrl.hpp @@ -18,6 +18,7 @@  #ifndef INCLUDED_B100_CTRL_HPP  #define INCLUDED_B100_CTRL_HPP +#include "wb_iface.hpp"  #include <uhd/transport/bounded_buffer.hpp>  #include <uhd/transport/usb_zero_copy.hpp>  #include <uhd/types/metadata.hpp> @@ -27,7 +28,7 @@  #include "ctrl_packet.hpp"  #include <boost/thread.hpp> -class b100_ctrl : boost::noncopyable{ +class b100_ctrl : boost::noncopyable, public wb_iface{  public:      typedef boost::shared_ptr<b100_ctrl> sptr; @@ -36,7 +37,7 @@ public:       * \param ctrl_transport a USB data transport       * \return a new b100 control object       */ -    static sptr make(uhd::transport::usb_zero_copy::sptr ctrl_transport); +    static sptr make(uhd::transport::zero_copy_if::sptr ctrl_transport);      /*!       * Write a byte vector to an FPGA register @@ -61,9 +62,9 @@ public:       * \return true if it got something       */      virtual bool get_ctrl_data(ctrl_data_t &pkt_data, double timeout) = 0; -     +      virtual bool recv_async_msg(uhd::async_metadata_t &async_metadata, double timeout) = 0; -     +  };  #endif /* INCLUDED_B100_CTRL_HPP */ diff --git a/host/lib/usrp/b100/b100_iface.hpp b/host/lib/usrp/b100/b100_iface.hpp index a98db98dc..f51d91c63 100644 --- a/host/lib/usrp/b100/b100_iface.hpp +++ b/host/lib/usrp/b100/b100_iface.hpp @@ -45,11 +45,6 @@ public:                       b100_ctrl::sptr fpga_ctrl = b100_ctrl::sptr()      ); -    //! TODO implement this for multiple hardwares revs in the future -    std::string get_cname(void){ -        return "USRP-B100"; -    } -      /*!       * Reset the GPIF interface on the FX2       * \param which endpoint to reset diff --git a/host/lib/usrp/b100/b100_impl.cpp b/host/lib/usrp/b100/b100_impl.cpp index d8c5e72ce..b3bf7b7f0 100644 --- a/host/lib/usrp/b100/b100_impl.cpp +++ b/host/lib/usrp/b100/b100_impl.cpp @@ -18,11 +18,10 @@  #include "b100_impl.hpp"  #include "b100_ctrl.hpp"  #include "fpga_regs_standard.h" -#include "usrp_spi_defs.h" +#include "usrp_i2c_addr.h" +#include "usrp_commands.h"  #include <uhd/transport/usb_control.hpp>  #include "ctrl_packet.hpp" -#include <uhd/usrp/device_props.hpp> -#include <uhd/usrp/mboard_props.hpp>  #include <uhd/utils/msg.hpp>  #include <uhd/exception.hpp>  #include <uhd/utils/static.hpp> @@ -100,11 +99,11 @@ static device_addrs_t b100_find(const device_addr_t &hint)          new_addr["serial"] = handle->get_serial();          //Attempt to read the name from the EEPROM and perform filtering. -        //This operation can throw due to compatibility mismatch.          try{              usb_control::sptr control = usb_control::make(handle); -            b100_iface::sptr iface = b100_iface::make(fx2_ctrl::make(control)); -            new_addr["name"] = iface->mb_eeprom["name"]; +            fx2_ctrl::sptr fx2_ctrl = fx2_ctrl::make(control); +            const mboard_eeprom_t mb_eeprom = mboard_eeprom_t(*fx2_ctrl, mboard_eeprom_t::MAP_B000); +            new_addr["name"] = mb_eeprom["name"];          }          catch(const uhd::exception &){              //set these values as empty string so the device may still be found @@ -128,6 +127,17 @@ static device_addrs_t b100_find(const device_addr_t &hint)   * Make   **********************************************************************/  static device::sptr b100_make(const device_addr_t &device_addr){ +    return device::sptr(new b100_impl(device_addr)); +} + +UHD_STATIC_BLOCK(register_b100_device){ +    device::register_device(&b100_find, &b100_make); +} + +/*********************************************************************** + * Structors + **********************************************************************/ +b100_impl::b100_impl(const device_addr_t &device_addr){      //extract the FPGA path for the B100      std::string b100_fpga_image = find_image_path( @@ -150,8 +160,14 @@ static device::sptr b100_make(const device_addr_t &device_addr){      //create control objects and a data transport      usb_control::sptr fx2_transport = usb_control::make(handle); -    fx2_ctrl::sptr fx2_ctrl = fx2_ctrl::make(fx2_transport); -    fx2_ctrl->usrp_load_fpga(b100_fpga_image); +    _fx2_ctrl = fx2_ctrl::make(fx2_transport); +    this->check_fw_compat(); //check after making fx2 +    //-- setup clock after making fx2 and before loading fpga --// +    _clock_ctrl = b100_clock_ctrl::make(_fx2_ctrl, device_addr.cast<double>("master_clock_rate", B100_DEFAULT_TICK_RATE)); +    _fx2_ctrl->usrp_load_fpga(b100_fpga_image); + +    //prepare GPIF before anything else is used +    this->prepare_gpif();      device_addr_t data_xport_args;      data_xport_args["recv_frame_size"] = device_addr.get("recv_frame_size", "16384"); @@ -159,7 +175,7 @@ static device::sptr b100_make(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"); -    usb_zero_copy::sptr data_transport = usb_zero_copy::make_wrapper( +    _data_transport = usb_zero_copy::make_wrapper(          usb_zero_copy::make(              handle,        // identifier              6,             // IN endpoint @@ -175,110 +191,281 @@ static device::sptr b100_make(const device_addr_t &device_addr){      ctrl_xport_args["send_frame_size"] = boost::lexical_cast<std::string>(CTRL_PACKET_LENGTH);      ctrl_xport_args["num_send_frames"] = "4"; -    usb_zero_copy::sptr ctrl_transport = usb_zero_copy::make( +    _ctrl_transport = usb_zero_copy::make(          handle,          8,          4,          ctrl_xport_args      ); -    const double master_clock_rate = device_addr.cast<double>("master_clock_rate", 64e6); - - -    //create the b100 implementation guts -    return device::sptr(new b100_impl(data_transport, ctrl_transport, fx2_ctrl, master_clock_rate)); -} - -UHD_STATIC_BLOCK(register_b100_device){ -    device::register_device(&b100_find, &b100_make); -} - -/*********************************************************************** - * Structors - **********************************************************************/ -b100_impl::b100_impl(uhd::transport::usb_zero_copy::sptr data_transport, -                         uhd::transport::usb_zero_copy::sptr ctrl_transport, -                         uhd::usrp::fx2_ctrl::sptr fx2_ctrl, -                         const double master_clock_rate) - : _data_transport(data_transport), _fx2_ctrl(fx2_ctrl) -{ -    _recv_otw_type.width = 16; -    _recv_otw_type.shift = 0; -    _recv_otw_type.byteorder = otw_type_t::BO_LITTLE_ENDIAN; - -    _send_otw_type.width = 16; -    _send_otw_type.shift = 0; -    _send_otw_type.byteorder = otw_type_t::BO_LITTLE_ENDIAN; - -    //this is the handler object for FPGA control packets -    _fpga_ctrl = b100_ctrl::make(ctrl_transport); - -    _iface = b100_iface::make(_fx2_ctrl, _fpga_ctrl); +    //////////////////////////////////////////////////////////////////// +    // Create controller objects +    //////////////////////////////////////////////////////////////////// +    _fpga_ctrl = b100_ctrl::make(_ctrl_transport); +    this->check_fpga_compat(); //check after making control +    _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)); + +    //////////////////////////////////////////////////////////////////// +    // Initialize the properties tree +    //////////////////////////////////////////////////////////////////// +    _tree = property_tree::make(); +    _tree->create<std::string>("/name").set("B-Series Device"); +    const property_tree::path_type mb_path = "/mboards/0"; +    _tree->create<std::string>(mb_path / "name").set("B100 (B-Hundo)"); + +    //////////////////////////////////////////////////////////////////// +    // setup the mboard eeprom +    //////////////////////////////////////////////////////////////////// +    const mboard_eeprom_t mb_eeprom = mboard_eeprom_t(*_fx2_ctrl, mboard_eeprom_t::MAP_B000); +    _tree->create<mboard_eeprom_t>(mb_path / "eeprom") +        .set(mb_eeprom) +        .subscribe(boost::bind(&b100_impl::set_mb_eeprom, this, _1)); + +    //////////////////////////////////////////////////////////////////// +    // create clock control objects +    //////////////////////////////////////////////////////////////////// +    //^^^ 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(&b100_impl::update_tick_rate, this, _1)); + +    //////////////////////////////////////////////////////////////////// +    // create codec control objects +    //////////////////////////////////////////////////////////////////// +    _codec_ctrl = b100_codec_ctrl::make(_fpga_spi_ctrl); +    const property_tree::path_type rx_codec_path = mb_path / "rx_codecs/A"; +    const property_tree::path_type tx_codec_path = mb_path / "tx_codecs/A"; +    _tree->create<std::string>(rx_codec_path / "name").set("ad9522"); +    _tree->create<meta_range_t>(rx_codec_path / "gains/pga/range").set(b100_codec_ctrl::rx_pga_gain_range); +    _tree->create<double>(rx_codec_path / "gains/pga/value") +        .coerce(boost::bind(&b100_impl::update_rx_codec_gain, this, _1)); +    _tree->create<std::string>(tx_codec_path / "name").set("ad9522"); +    _tree->create<meta_range_t>(tx_codec_path / "gains/pga/range").set(b100_codec_ctrl::tx_pga_gain_range); +    _tree->create<double>(tx_codec_path / "gains/pga/value") +        .subscribe(boost::bind(&b100_codec_ctrl::set_tx_pga_gain, _codec_ctrl, _1)) +        .publish(boost::bind(&b100_codec_ctrl::get_tx_pga_gain, _codec_ctrl)); + +    //////////////////////////////////////////////////////////////////// +    // and do the misc mboard sensors +    //////////////////////////////////////////////////////////////////// +    //none for now... +    _tree->create<int>(mb_path / "sensors"); //phony property so this dir exists + +    //////////////////////////////////////////////////////////////////// +    // 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)); +    //TODO lots of properties to expose here for frontends +    _tree->create<subdev_spec_t>(mb_path / "rx_subdev_spec") +        .subscribe(boost::bind(&b100_impl::update_rx_subdev_spec, this, _1)); +    _tree->create<subdev_spec_t>(mb_path / "tx_subdev_spec") +        .subscribe(boost::bind(&b100_impl::update_tx_subdev_spec, this, _1)); + +    //////////////////////////////////////////////////////////////////// +    // 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++){ +        _tree->access<double>(mb_path / "tick_rate") +            .subscribe(boost::bind(&rx_dsp_core_200::set_tick_rate, _rx_dsps[dspno], _1)); +        property_tree::path_type rx_dsp_path = mb_path / str(boost::format("rx_dsps/%u") % dspno); +        _tree->create<double>(rx_dsp_path / "rate/value") +            .coerce(boost::bind(&rx_dsp_core_200::set_host_rate, _rx_dsps[dspno], _1)) +            .subscribe(boost::bind(&b100_impl::update_rx_samp_rate, this, _1)); +        _tree->create<double>(rx_dsp_path / "freq/value") +            .coerce(boost::bind(&rx_dsp_core_200::set_freq, _rx_dsps[dspno], _1)); +        _tree->create<meta_range_t>(rx_dsp_path / "freq/range") +            .publish(boost::bind(&rx_dsp_core_200::get_freq_range, _rx_dsps[dspno])); +        _tree->create<stream_cmd_t>(rx_dsp_path / "stream_cmd") +            .subscribe(boost::bind(&rx_dsp_core_200::issue_stream_command, _rx_dsps[dspno], _1)); +    } -    //create clock interface -    _clock_ctrl = b100_clock_ctrl::make(_iface, master_clock_rate); +    //////////////////////////////////////////////////////////////////// +    // 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 +    ); +    _tree->access<double>(mb_path / "tick_rate") +        .subscribe(boost::bind(&tx_dsp_core_200::set_tick_rate, _tx_dsp, _1)); +    _tree->create<double>(mb_path / "tx_dsps/0/rate/value") +        .coerce(boost::bind(&tx_dsp_core_200::set_host_rate, _tx_dsp, _1)) +        .subscribe(boost::bind(&b100_impl::update_tx_samp_rate, this, _1)); +    _tree->create<double>(mb_path / "tx_dsps/0/freq/value") +        .coerce(boost::bind(&tx_dsp_core_200::set_freq, _tx_dsp, _1)); +    _tree->create<meta_range_t>(mb_path / "tx_dsps/0/freq/range") +        .publish(boost::bind(&tx_dsp_core_200::get_freq_range, _tx_dsp)); + +    //////////////////////////////////////////////////////////////////// +    // create time control objects +    //////////////////////////////////////////////////////////////////// +    time64_core_200::readback_bases_type time64_rb_bases; +    time64_rb_bases.rb_secs_now = B100_REG_RB_TIME_NOW_SECS; +    time64_rb_bases.rb_ticks_now = B100_REG_RB_TIME_NOW_TICKS; +    time64_rb_bases.rb_secs_pps = B100_REG_RB_TIME_PPS_SECS; +    time64_rb_bases.rb_ticks_pps = B100_REG_RB_TIME_PPS_TICKS; +    _time64 = time64_core_200::make( +        _fpga_ctrl, B100_REG_SR_ADDR(B100_SR_TIME64), time64_rb_bases +    ); +    _tree->access<double>(mb_path / "tick_rate") +        .subscribe(boost::bind(&time64_core_200::set_tick_rate, _time64, _1)); +    _tree->create<time_spec_t>(mb_path / "time/now") +        .publish(boost::bind(&time64_core_200::get_time_now, _time64)) +        .subscribe(boost::bind(&time64_core_200::set_time_now, _time64, _1)); +    _tree->create<time_spec_t>(mb_path / "time/pps") +        .publish(boost::bind(&time64_core_200::get_time_last_pps, _time64)) +        .subscribe(boost::bind(&time64_core_200::set_time_next_pps, _time64, _1)); +    //setup time source props +    _tree->create<std::string>(mb_path / "time_source/value") +        .subscribe(boost::bind(&time64_core_200::set_time_source, _time64, _1)); +    _tree->create<std::vector<std::string> >(mb_path / "time_source/options") +        .publish(boost::bind(&time64_core_200::get_time_sources, _time64)); +    //setup reference source props +    _tree->create<std::string>(mb_path / "ref_source/value") +        .subscribe(boost::bind(&b100_impl::update_ref_source, this, _1)); +    static const std::vector<std::string> ref_sources = boost::assign::list_of("internal")("sma")("auto"); +    _tree->create<std::vector<std::string> >(mb_path / "ref_source/options").set(ref_sources); + +    //////////////////////////////////////////////////////////////////// +    // create dboard control objects +    //////////////////////////////////////////////////////////////////// + +    //read the dboard eeprom to extract the dboard ids +    dboard_eeprom_t rx_db_eeprom, tx_db_eeprom, gdb_eeprom; +    rx_db_eeprom.load(*_fpga_i2c_ctrl, I2C_ADDR_RX_A); +    tx_db_eeprom.load(*_fpga_i2c_ctrl, I2C_ADDR_TX_A); +    gdb_eeprom.load(*_fpga_i2c_ctrl, I2C_ADDR_TX_A ^ 5); + +    //create the properties and register subscribers +    _tree->create<dboard_eeprom_t>(mb_path / "dboards/A/rx_eeprom") +        .set(rx_db_eeprom) +        .subscribe(boost::bind(&b100_impl::set_db_eeprom, this, "rx", _1)); +    _tree->create<dboard_eeprom_t>(mb_path / "dboards/A/tx_eeprom") +        .set(tx_db_eeprom) +        .subscribe(boost::bind(&b100_impl::set_db_eeprom, this, "tx", _1)); +    _tree->create<dboard_eeprom_t>(mb_path / "dboards/A/gdb_eeprom") +        .set(gdb_eeprom) +        .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); +    _tree->create<dboard_iface::sptr>(mb_path / "dboards/A/iface").set(_dboard_iface); +    _dboard_manager = dboard_manager::make( +        rx_db_eeprom.id, +        ((gdb_eeprom.id == dboard_id_t::none())? tx_db_eeprom : gdb_eeprom).id, +        _dboard_iface +    ); +    BOOST_FOREACH(const std::string &name, _dboard_manager->get_rx_subdev_names()){ +        dboard_manager::populate_prop_tree_from_subdev( +            _tree, mb_path / "dboards/A/rx_frontends" / name, +            _dboard_manager->get_rx_subdev(name) +        ); +    } +    BOOST_FOREACH(const std::string &name, _dboard_manager->get_tx_subdev_names()){ +        dboard_manager::populate_prop_tree_from_subdev( +            _tree, mb_path / "dboards/A/tx_frontends" / name, +            _dboard_manager->get_tx_subdev(name) +        ); +    } -    //create codec interface -    _codec_ctrl = b100_codec_ctrl::make(_iface); +    //initialize io handling +    this->io_init(); -    //initialize the codecs -    codec_init(); +    //////////////////////////////////////////////////////////////////// +    // do some post-init tasks +    //////////////////////////////////////////////////////////////////// +    _tree->access<double>(mb_path / "tick_rate").update() //update and then subscribe the clock callback +        .subscribe(boost::bind(&b100_clock_ctrl::set_fpga_clock_rate, _clock_ctrl, _1)); -    //initialize the mboard -    mboard_init(); +    //and now that the tick rate is set, init the host rates to something +    BOOST_FOREACH(const std::string &name, _tree->list(mb_path / "rx_dsps")){ +        _tree->access<double>(mb_path / "rx_dsps" / name / "rate" / "value").set(1e6); +    } +    BOOST_FOREACH(const std::string &name, _tree->list(mb_path / "tx_dsps")){ +        _tree->access<double>(mb_path / "tx_dsps" / name / "rate" / "value").set(1e6); +    } -    //initialize the dboards -    dboard_init(); +    _tree->access<subdev_spec_t>(mb_path / "rx_subdev_spec").set(subdev_spec_t("A:"+_dboard_manager->get_rx_subdev_names()[0])); +    _tree->access<subdev_spec_t>(mb_path / "tx_subdev_spec").set(subdev_spec_t("A:"+_dboard_manager->get_tx_subdev_names()[0])); +    _tree->access<std::string>(mb_path / "ref_source/value").set("internal"); +    _tree->access<std::string>(mb_path / "time_source/value").set("none"); +} -    //initialize the dsps -    dsp_init(); +b100_impl::~b100_impl(void){ +    /* NOP */ +} -    //init the subdev specs -    this->mboard_set(MBOARD_PROP_RX_SUBDEV_SPEC, subdev_spec_t()); -    this->mboard_set(MBOARD_PROP_TX_SUBDEV_SPEC, subdev_spec_t()); +void b100_impl::check_fw_compat(void){ +    unsigned char data[4]; //useless data buffer +    const boost::uint16_t fw_compat_num = _fx2_ctrl->usrp_control_read( +        VRQ_FW_COMPAT, 0, 0, data, sizeof(data) +    ); +    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)); +    } +} -    //initialize the send/recv buffs -    io_init(); +void b100_impl::check_fpga_compat(void){ +    const boost::uint16_t fpga_compat_num = _fpga_ctrl->peek16(B100_REG_MISC_COMPAT); +    if (fpga_compat_num != B100_FPGA_COMPAT_NUM){ +        throw uhd::runtime_error(str(boost::format( +            "Expected FPGA compatibility number 0x%x, but got 0x%x:\n" +            "The FPGA build is not compatible with the host code build." +        ) % B100_FPGA_COMPAT_NUM % fpga_compat_num)); +    }  } -b100_impl::~b100_impl(void){ -    /* NOP */ +double b100_impl::update_rx_codec_gain(const double gain){ +    //set gain on both I and Q, readback on one +    //TODO in the future, gains should have individual control +    _codec_ctrl->set_rx_pga_gain(gain, 'A'); +    _codec_ctrl->set_rx_pga_gain(gain, 'B'); +    return _codec_ctrl->get_rx_pga_gain('A');  } -bool b100_impl::recv_async_msg(uhd::async_metadata_t &md, double timeout){ -    return _fpga_ctrl->recv_async_msg(md, timeout); +void b100_impl::set_mb_eeprom(const uhd::usrp::mboard_eeprom_t &mb_eeprom){ +    mb_eeprom.commit(*_fx2_ctrl, mboard_eeprom_t::MAP_B000);  } -/*********************************************************************** - * Device Get - **********************************************************************/ -void b100_impl::get(const wax::obj &key_, wax::obj &val) -{ -    named_prop_t key = named_prop_t::extract(key_); +void b100_impl::set_db_eeprom(const std::string &type, const uhd::usrp::dboard_eeprom_t &db_eeprom){ +    if (type == "rx") db_eeprom.store(*_fpga_i2c_ctrl, I2C_ADDR_RX_A); +    if (type == "tx") db_eeprom.store(*_fpga_i2c_ctrl, I2C_ADDR_TX_A); +    if (type == "gdb") db_eeprom.store(*_fpga_i2c_ctrl, I2C_ADDR_TX_A ^ 5); +} -    //handle the get request conditioned on the key -    switch(key.as<device_prop_t>()){ -    case DEVICE_PROP_NAME: -        val = std::string("USRP-B100 device"); -        return; +void b100_impl::update_ref_source(const std::string &source){ +    if      (source == "auto")     _clock_ctrl->use_auto_ref(); +    else if (source == "internal") _clock_ctrl->use_internal_ref(); +    else if (source == "sma")      _clock_ctrl->use_external_ref(); +    else throw uhd::runtime_error("unhandled clock configuration reference source: " + source); +} -    case DEVICE_PROP_MBOARD: -        UHD_ASSERT_THROW(key.name == ""); -        val = _mboard_proxy->get_link(); -        return; +////////////////// some GPIF preparation related stuff ///////////////// +static void reset_gpif(fx2_ctrl::sptr _fx2_ctrl, boost::uint16_t ep) { +    _fx2_ctrl->usrp_control_write(VRQ_RESET_GPIF, ep, ep, 0, 0); +} -    case DEVICE_PROP_MBOARD_NAMES: -        val = prop_names_t(1, ""); //vector of size 1 with empty string -        return; +static void enable_gpif(fx2_ctrl::sptr _fx2_ctrl, bool en) { +    _fx2_ctrl->usrp_control_write(VRQ_ENABLE_GPIF, en ? 1 : 0, 0, 0, 0); +} -    default: UHD_THROW_PROP_GET_ERROR(); -    } +static void clear_fpga_fifo(fx2_ctrl::sptr _fx2_ctrl) { +    _fx2_ctrl->usrp_control_write(VRQ_CLEAR_FPGA_FIFO, 0, 0, 0, 0);  } -/*********************************************************************** - * Device Set - **********************************************************************/ -void b100_impl::set(const wax::obj &, const wax::obj &) -{ -    UHD_THROW_PROP_SET_ERROR(); +void b100_impl::prepare_gpif(void){ +    //TODO check the order of this: +    enable_gpif(_fx2_ctrl, true); +    reset_gpif(_fx2_ctrl, 6); +    clear_fpga_fifo(_fx2_ctrl);  } diff --git a/host/lib/usrp/b100/b100_impl.hpp b/host/lib/usrp/b100/b100_impl.hpp index b2381ef65..e0b7aa670 100644 --- a/host/lib/usrp/b100/b100_impl.hpp +++ b/host/lib/usrp/b100/b100_impl.hpp @@ -15,83 +15,55 @@  // along with this program.  If not, see <http://www.gnu.org/licenses/>.  // -#include "b100_iface.hpp" +#ifndef INCLUDED_B100_IMPL_HPP +#define INCLUDED_B100_IMPL_HPP + +#include "../fx2/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 "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 <uhd/device.hpp> +#include <uhd/property_tree.hpp>  #include <uhd/utils/pimpl.hpp>  #include <uhd/types/dict.hpp>  #include <uhd/types/otw_type.hpp>  #include <uhd/types/clock_config.hpp>  #include <uhd/types/stream_cmd.hpp> -#include <uhd/usrp/dboard_id.hpp> +#include <uhd/usrp/mboard_eeprom.hpp>  #include <uhd/usrp/subdev_spec.hpp>  #include <uhd/usrp/dboard_eeprom.hpp>  #include <uhd/usrp/dboard_manager.hpp>  #include <uhd/transport/usb_zero_copy.hpp> -#ifndef INCLUDED_B100_IMPL_HPP -#define INCLUDED_B100_IMPL_HPP -  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 = 0x02;  static const boost::uint16_t B100_FPGA_COMPAT_NUM = 0x05; -static const size_t          B100_NUM_RX_DSPS = 2; -static const size_t          B100_NUM_TX_DSPS = 1; -static const boost::uint32_t B100_DSP_SID_BASE = 2; //leave room for other dsp (increments by 1) -static const boost::uint32_t B100_ASYNC_SID = 1; +static const boost::uint32_t B100_RX_SID_BASE = 2; +static const boost::uint32_t B100_TX_ASYNC_SID = 1; +static const double          B100_DEFAULT_TICK_RATE = 64e6; -/*! - * Make a b100 dboard interface. - * \param iface the b100 interface object - * \param clock the clock control interface - * \param codec the codec control interface - * \return a sptr to a new dboard interface - */ +//! Make a b100 dboard interface  uhd::usrp::dboard_iface::sptr make_b100_dboard_iface( -    b100_iface::sptr iface, +    wb_iface::sptr wb_iface, +    uhd::i2c_iface::sptr i2c_iface, +    uhd::spi_iface::sptr spi_iface,      b100_clock_ctrl::sptr clock,      b100_codec_ctrl::sptr codec  ); -/*! - * Simple wax obj proxy class: - * Provides a wax obj interface for a set and a get function. - * This allows us to create nested properties structures - * while maintaining flattened code within the implementation. - */ -class wax_obj_proxy : public wax::obj { -public: -    typedef boost::function<void(const wax::obj &, wax::obj &)>       get_t; -    typedef boost::function<void(const wax::obj &, const wax::obj &)> set_t; -    typedef boost::shared_ptr<wax_obj_proxy> sptr; - -    static sptr make(const get_t &get, const set_t &set){ -        return sptr(new wax_obj_proxy(get, set)); -    } - -private: -    get_t _get; set_t _set; -    wax_obj_proxy(const get_t &get, const set_t &set): _get(get), _set(set) {}; -    void get(const wax::obj &key, wax::obj &val) {return _get(key, val);} -    void set(const wax::obj &key, const wax::obj &val) {return _set(key, val);} -}; - -/*! - * USRP1 implementation guts: - * The implementation details are encapsulated here. - * Handles properties on the mboard, dboard, dsps... - */ +//! Implementation guts  class b100_impl : public uhd::device {  public:      //structors -    b100_impl(uhd::transport::usb_zero_copy::sptr data_transport, -                uhd::transport::usb_zero_copy::sptr ctrl_transport, -                uhd::usrp::fx2_ctrl::sptr fx2_ctrl, -                double master_clock_rate); - +    b100_impl(const uhd::device_addr_t &);      ~b100_impl(void);      //the io interface @@ -100,114 +72,59 @@ public:                  const uhd::tx_metadata_t &,                  const uhd::io_type_t &,                  send_mode_t, double); -      size_t recv(const recv_buffs_type &,                  size_t, uhd::rx_metadata_t &,                  const uhd::io_type_t &,                  recv_mode_t, double); -      size_t get_max_send_samps_per_packet(void) const; -      size_t get_max_recv_samps_per_packet(void) const; -      bool recv_async_msg(uhd::async_metadata_t &, double);  private: -    //clock control +    uhd::property_tree::sptr _tree; + +    //controllers +    spi_core_100::sptr _fpga_spi_ctrl; +    i2c_core_100::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; +    tx_dsp_core_200::sptr _tx_dsp; +    time64_core_200::sptr _time64;      b100_clock_ctrl::sptr _clock_ctrl; - -    //interface to ioctls and file descriptor -    b100_iface::sptr _iface; - -    //handle io stuff -    uhd::transport::zero_copy_if::sptr _data_transport; -    UHD_PIMPL_DECL(io_impl) _io_impl; -    void update_xport_channel_mapping(void); -    void io_init(void); -    void handle_overrun(size_t); - -    //otw types -    uhd::otw_type_t _recv_otw_type; -    uhd::otw_type_t _send_otw_type; - -    //configuration shadows -    uhd::clock_config_t _clock_config; -    uhd::usrp::subdev_spec_t _rx_subdev_spec, _tx_subdev_spec; - -    //ad9862 codec control interface      b100_codec_ctrl::sptr _codec_ctrl; +    b100_ctrl::sptr _fpga_ctrl; +    uhd::usrp::fx2_ctrl::sptr _fx2_ctrl; -    //codec properties interfaces -    void codec_init(void); -    void rx_codec_get(const wax::obj &, wax::obj &); -    void rx_codec_set(const wax::obj &, const wax::obj &); -    void tx_codec_get(const wax::obj &, wax::obj &); -    void tx_codec_set(const wax::obj &, const wax::obj &); -    wax_obj_proxy::sptr _rx_codec_proxy, _tx_codec_proxy; - -    //device functions and settings -    void get(const wax::obj &, wax::obj &); -    void set(const wax::obj &, const wax::obj &); - -    //mboard functions and settings -    void mboard_init(void); -    void mboard_get(const wax::obj &, wax::obj &); -    void mboard_set(const wax::obj &, const wax::obj &); -    void update_clock_config(void); -    wax_obj_proxy::sptr _mboard_proxy; -     -    /*! -     * Make a usrp1 dboard interface. -     * \param iface the usrp1 interface object -     * \param clock the clock control interface -     * \param codec the codec control interface -     * \param dboard_slot the slot identifier -     * \param rx_dboard_id the db id for the rx board (used for evil dbsrx purposes) -     * \return a sptr to a new dboard interface -     */ -    static uhd::usrp::dboard_iface::sptr make_dboard_iface( -        b100_iface::sptr iface, -        b100_clock_ctrl::sptr clock, -        b100_codec_ctrl::sptr codec, -        const uhd::usrp::dboard_id_t &rx_dboard_id -    ); +    //transports +    uhd::transport::zero_copy_if::sptr _data_transport, _ctrl_transport; -    //xx dboard functions and settings -    void dboard_init(void); +    //dboard stuff      uhd::usrp::dboard_manager::sptr _dboard_manager;      uhd::usrp::dboard_iface::sptr _dboard_iface; -    //rx dboard functions and settings -    uhd::usrp::dboard_eeprom_t _rx_db_eeprom; -    void rx_dboard_get(const wax::obj &, wax::obj &); -    void rx_dboard_set(const wax::obj &, const wax::obj &); -    wax_obj_proxy::sptr _rx_dboard_proxy; - -    //tx dboard functions and settings -    uhd::usrp::dboard_eeprom_t _tx_db_eeprom, _gdb_eeprom; -    void tx_dboard_get(const wax::obj &, wax::obj &); -    void tx_dboard_set(const wax::obj &, const wax::obj &); -    wax_obj_proxy::sptr _tx_dboard_proxy; - -    //methods and shadows for the dsps -    UHD_PIMPL_DECL(dsp_impl) _dsp_impl; -    void dsp_init(void); -    void issue_ddc_stream_cmd(const uhd::stream_cmd_t &, size_t); - -    //properties interface for ddc -    void ddc_get(const wax::obj &, wax::obj &, size_t); -    void ddc_set(const wax::obj &, const wax::obj &, size_t); -    uhd::dict<std::string, wax_obj_proxy::sptr> _rx_dsp_proxies; - -    //properties interface for duc -    void duc_get(const wax::obj &, wax::obj &, size_t); -    void duc_set(const wax::obj &, const wax::obj &, size_t); -    uhd::dict<std::string, wax_obj_proxy::sptr> _tx_dsp_proxies; +    //handle io stuff +    uhd::otw_type_t _rx_otw_type, _tx_otw_type; +    UHD_PIMPL_DECL(io_impl) _io_impl; +    void io_init(void); -    //transports -    b100_ctrl::sptr _fpga_ctrl; -    uhd::usrp::fx2_ctrl::sptr _fx2_ctrl; +    //device properties interface +    void get(const wax::obj &, wax::obj &val){ +        val = _tree; //entry point into property tree +    } +    void check_fw_compat(void); +    void check_fpga_compat(void); +    double update_rx_codec_gain(const double); //sets A and B at once +    void set_mb_eeprom(const uhd::usrp::mboard_eeprom_t &); +    void set_db_eeprom(const std::string &, const uhd::usrp::dboard_eeprom_t &); +    void update_tick_rate(const double rate); +    void update_rx_samp_rate(const double rate); +    void update_tx_samp_rate(const double rate); +    void update_rx_subdev_spec(const uhd::usrp::subdev_spec_t &); +    void update_tx_subdev_spec(const uhd::usrp::subdev_spec_t &); +    void update_ref_source(const std::string &); +    void prepare_gpif(void);  };  #endif /* INCLUDED_b100_IMPL_HPP */ diff --git a/host/lib/usrp/b100/clock_ctrl.cpp b/host/lib/usrp/b100/clock_ctrl.cpp index 02091f00a..ee56a0e1c 100644 --- a/host/lib/usrp/b100/clock_ctrl.cpp +++ b/host/lib/usrp/b100/clock_ctrl.cpp @@ -169,7 +169,7 @@ static clock_settings_type get_clock_settings(double rate){   **********************************************************************/  class b100_clock_ctrl_impl : public b100_clock_ctrl{  public: -    b100_clock_ctrl_impl(b100_iface::sptr iface, double master_clock_rate){ +    b100_clock_ctrl_impl(i2c_iface::sptr iface, double master_clock_rate){          _iface = iface;          _chan_rate = 0.0;          _out_rate = 0.0; @@ -294,7 +294,6 @@ public:          //clock rate changed! update dboard clocks and FPGA ticks per second          set_rx_dboard_clock_rate(rate);          set_tx_dboard_clock_rate(rate); -        _iface->poke32(B100_REG_TIME64_TPS, boost::uint32_t(get_fpga_clock_rate()));      }      double get_fpga_clock_rate(void){ @@ -428,7 +427,7 @@ public:      }  private: -    b100_iface::sptr _iface; +    i2c_iface::sptr _iface;      ad9522_regs_t _ad9522_regs;      double _out_rate; //rate at the fpga and codec      double _chan_rate; //rate before final dividers @@ -447,16 +446,16 @@ private:          buf.push_back(boost::uint8_t(reg >> 8));          buf.push_back(boost::uint8_t(reg & 0xff)); -        _iface->get_fx2_i2c_iface().write_i2c(0x5C, buf); +        _iface->write_i2c(0x5C, buf);      }      boost::uint8_t read_reg(boost::uint16_t addr){          byte_vector_t buf;          buf.push_back(boost::uint8_t(addr >> 8));          buf.push_back(boost::uint8_t(addr & 0xff)); -        _iface->get_fx2_i2c_iface().write_i2c(0x5C, buf); +        _iface->write_i2c(0x5C, buf); -        buf = _iface->get_fx2_i2c_iface().read_i2c(0x5C, 1); +        buf = _iface->read_i2c(0x5C, 1);          return boost::uint32_t(buf[0] & 0xFF);      } @@ -520,6 +519,6 @@ private:  /***********************************************************************   * Clock Control Make   **********************************************************************/ -b100_clock_ctrl::sptr b100_clock_ctrl::make(b100_iface::sptr iface, double master_clock_rate){ +b100_clock_ctrl::sptr b100_clock_ctrl::make(i2c_iface::sptr iface, double master_clock_rate){      return sptr(new b100_clock_ctrl_impl(iface, master_clock_rate));  } diff --git a/host/lib/usrp/b100/clock_ctrl.hpp b/host/lib/usrp/b100/clock_ctrl.hpp index 3a24f2a66..5ef231281 100644 --- a/host/lib/usrp/b100/clock_ctrl.hpp +++ b/host/lib/usrp/b100/clock_ctrl.hpp @@ -18,7 +18,7 @@  #ifndef INCLUDED_B100_CLOCK_CTRL_HPP  #define INCLUDED_B100_CLOCK_CTRL_HPP -#include "b100_iface.hpp" +#include <uhd/types/serial.hpp>  #include <boost/shared_ptr.hpp>  #include <boost/utility.hpp>  #include <vector> @@ -34,11 +34,11 @@ public:      /*!       * Make a new clock control object. -     * \param iface the b100 iface object +     * \param iface the controller iface object       * \param master_clock_rate the master FPGA/sample clock rate       * \return the clock control object       */ -    static sptr make(b100_iface::sptr iface, double master_clock_rate); +    static sptr make(uhd::i2c_iface::sptr iface, double master_clock_rate);      /*!       * Set the rate of the fpga clock line. diff --git a/host/lib/usrp/b100/codec_ctrl.cpp b/host/lib/usrp/b100/codec_ctrl.cpp index 7e9f355d4..4f9036039 100644 --- a/host/lib/usrp/b100/codec_ctrl.cpp +++ b/host/lib/usrp/b100/codec_ctrl.cpp @@ -39,7 +39,7 @@ const gain_range_t b100_codec_ctrl::rx_pga_gain_range(0, 20, 1);  class b100_codec_ctrl_impl : public b100_codec_ctrl{  public:      //structors -    b100_codec_ctrl_impl(b100_iface::sptr iface); +    b100_codec_ctrl_impl(spi_iface::sptr iface);      ~b100_codec_ctrl_impl(void);      //aux adc and dac control @@ -53,7 +53,7 @@ public:      double get_rx_pga_gain(char);  private: -    b100_iface::sptr _iface; +    spi_iface::sptr _iface;      ad9862_regs_t _ad9862_regs;      void send_reg(boost::uint8_t addr);      void recv_reg(boost::uint8_t addr); @@ -62,7 +62,7 @@ private:  /***********************************************************************   * Codec Control Structors   **********************************************************************/ -b100_codec_ctrl_impl::b100_codec_ctrl_impl(b100_iface::sptr iface){ +b100_codec_ctrl_impl::b100_codec_ctrl_impl(spi_iface::sptr iface){      _iface = iface;      //soft reset @@ -278,6 +278,6 @@ void b100_codec_ctrl_impl::recv_reg(boost::uint8_t addr){  /***********************************************************************   * Codec Control Make   **********************************************************************/ -b100_codec_ctrl::sptr b100_codec_ctrl::make(b100_iface::sptr iface){ +b100_codec_ctrl::sptr b100_codec_ctrl::make(spi_iface::sptr iface){      return sptr(new b100_codec_ctrl_impl(iface));  } diff --git a/host/lib/usrp/b100/codec_ctrl.hpp b/host/lib/usrp/b100/codec_ctrl.hpp index 9ef960592..1f7bdef09 100644 --- a/host/lib/usrp/b100/codec_ctrl.hpp +++ b/host/lib/usrp/b100/codec_ctrl.hpp @@ -18,7 +18,7 @@  #ifndef INCLUDED_B100_CODEC_CTRL_HPP  #define INCLUDED_B100_CODEC_CTRL_HPP -#include "b100_iface.hpp" +#include <uhd/types/serial.hpp>  #include <uhd/types/ranges.hpp>  #include <boost/shared_ptr.hpp>  #include <boost/utility.hpp> @@ -40,7 +40,7 @@ public:       * \param iface the usrp_e iface object       * \return the codec control object       */ -    static sptr make(b100_iface::sptr iface); +    static sptr make(uhd::spi_iface::sptr iface);      //! aux adc identifier constants      enum aux_adc_t{ diff --git a/host/lib/usrp/b100/dboard_iface.cpp b/host/lib/usrp/b100/dboard_iface.cpp index 003d86d48..33c4b355d 100644 --- a/host/lib/usrp/b100/dboard_iface.cpp +++ b/host/lib/usrp/b100/dboard_iface.cpp @@ -15,7 +15,8 @@  // along with this program.  If not, see <http://www.gnu.org/licenses/>.  // -#include "b100_iface.hpp" +#include "wb_iface.hpp" +#include <uhd/types/serial.hpp>  #include "b100_regs.hpp"  #include "clock_ctrl.hpp"  #include "codec_ctrl.hpp" @@ -33,11 +34,15 @@ class b100_dboard_iface : public dboard_iface{  public:      b100_dboard_iface( -        b100_iface::sptr iface, +        wb_iface::sptr wb_iface, +        i2c_iface::sptr i2c_iface, +        spi_iface::sptr spi_iface,          b100_clock_ctrl::sptr clock,          b100_codec_ctrl::sptr codec      ){ -        _iface = iface; +        _wb_iface = wb_iface; +        _i2c_iface = i2c_iface; +        _spi_iface = spi_iface;          _clock = clock;          _codec = codec; @@ -45,8 +50,8 @@ public:          this->set_clock_rate(UNIT_RX, _clock->get_fpga_clock_rate());          this->set_clock_rate(UNIT_TX, _clock->get_fpga_clock_rate()); -        _iface->poke16(B100_REG_GPIO_RX_DBG, 0); -        _iface->poke16(B100_REG_GPIO_TX_DBG, 0); +        _wb_iface->poke16(B100_REG_GPIO_RX_DBG, 0); +        _wb_iface->poke16(B100_REG_GPIO_TX_DBG, 0);      }      ~b100_dboard_iface(void){ @@ -94,7 +99,9 @@ public:      double get_codec_rate(unit_t);  private: -    b100_iface::sptr _iface; +    wb_iface::sptr _wb_iface; +    i2c_iface::sptr _i2c_iface; +    spi_iface::sptr _spi_iface;      b100_clock_ctrl::sptr _clock;      b100_codec_ctrl::sptr _codec;      uhd::dict<unit_t, double> _clock_rates; @@ -104,11 +111,13 @@ private:   * Make Function   **********************************************************************/  dboard_iface::sptr make_b100_dboard_iface( -    b100_iface::sptr iface, +    wb_iface::sptr wb_iface, +    i2c_iface::sptr i2c_iface, +    spi_iface::sptr spi_iface,      b100_clock_ctrl::sptr clock,      b100_codec_ctrl::sptr codec  ){ -    return dboard_iface::sptr(new b100_dboard_iface(iface, clock, codec)); +    return dboard_iface::sptr(new b100_dboard_iface(wb_iface, i2c_iface, spi_iface, clock, codec));  }  /*********************************************************************** @@ -151,29 +160,29 @@ double b100_dboard_iface::get_codec_rate(unit_t){  void b100_dboard_iface::_set_pin_ctrl(unit_t unit, boost::uint16_t value){      UHD_ASSERT_THROW(GPIO_SEL_ATR == 1); //make this assumption      switch(unit){ -    case UNIT_RX: _iface->poke16(B100_REG_GPIO_RX_SEL, value); return; -    case UNIT_TX: _iface->poke16(B100_REG_GPIO_TX_SEL, value); return; +    case UNIT_RX: _wb_iface->poke16(B100_REG_GPIO_RX_SEL, value); return; +    case UNIT_TX: _wb_iface->poke16(B100_REG_GPIO_TX_SEL, value); return;      }  }  void b100_dboard_iface::_set_gpio_ddr(unit_t unit, boost::uint16_t value){      switch(unit){ -    case UNIT_RX: _iface->poke16(B100_REG_GPIO_RX_DDR, value); return; -    case UNIT_TX: _iface->poke16(B100_REG_GPIO_TX_DDR, value); return; +    case UNIT_RX: _wb_iface->poke16(B100_REG_GPIO_RX_DDR, value); return; +    case UNIT_TX: _wb_iface->poke16(B100_REG_GPIO_TX_DDR, value); return;      }  }  void b100_dboard_iface::_set_gpio_out(unit_t unit, boost::uint16_t value){      switch(unit){ -    case UNIT_RX: _iface->poke16(B100_REG_GPIO_RX_IO, value); return; -    case UNIT_TX: _iface->poke16(B100_REG_GPIO_TX_IO, value); return; +    case UNIT_RX: _wb_iface->poke16(B100_REG_GPIO_RX_IO, value); return; +    case UNIT_TX: _wb_iface->poke16(B100_REG_GPIO_TX_IO, value); return;      }  }  boost::uint16_t b100_dboard_iface::read_gpio(unit_t unit){      switch(unit){ -    case UNIT_RX: return _iface->peek16(B100_REG_GPIO_RX_IO); -    case UNIT_TX: return _iface->peek16(B100_REG_GPIO_TX_IO); +    case UNIT_RX: return _wb_iface->peek16(B100_REG_GPIO_RX_IO); +    case UNIT_TX: return _wb_iface->peek16(B100_REG_GPIO_TX_IO);      default: UHD_THROW_INVALID_CODE_PATH();      }  } @@ -196,7 +205,7 @@ void b100_dboard_iface::_set_atr_reg(unit_t unit, atr_reg_t atr, boost::uint16_t              (ATR_REG_FULL_DUPLEX, B100_REG_ATR_FULL_TXSIDE)          )      ; -    _iface->poke16(unit_to_atr_to_addr[unit][atr], value); +    _wb_iface->poke16(unit_to_atr_to_addr[unit][atr], value);  }  void b100_dboard_iface::set_gpio_debug(unit_t unit, int which){ @@ -211,13 +220,13 @@ void b100_dboard_iface::set_gpio_debug(unit_t unit, int which){      //set the debug on and which debug selection      switch(unit){      case UNIT_RX: -        _iface->poke16(B100_REG_GPIO_RX_DBG, 0xffff); -        _iface->poke16(B100_REG_GPIO_RX_SEL, dbg_sels); +        _wb_iface->poke16(B100_REG_GPIO_RX_DBG, 0xffff); +        _wb_iface->poke16(B100_REG_GPIO_RX_SEL, dbg_sels);          return;      case UNIT_TX: -        _iface->poke16(B100_REG_GPIO_TX_DBG, 0xffff); -        _iface->poke16(B100_REG_GPIO_TX_SEL, dbg_sels); +        _wb_iface->poke16(B100_REG_GPIO_TX_DBG, 0xffff); +        _wb_iface->poke16(B100_REG_GPIO_TX_SEL, dbg_sels);          return;      }  } @@ -244,7 +253,7 @@ void b100_dboard_iface::write_spi(      boost::uint32_t data,      size_t num_bits  ){ -    _iface->transact_spi(unit_to_otw_spi_dev(unit), config, data, num_bits, false /*no rb*/); +    _spi_iface->transact_spi(unit_to_otw_spi_dev(unit), config, data, num_bits, false /*no rb*/);  }  boost::uint32_t b100_dboard_iface::read_write_spi( @@ -253,18 +262,18 @@ boost::uint32_t b100_dboard_iface::read_write_spi(      boost::uint32_t data,      size_t num_bits  ){ -    return _iface->transact_spi(unit_to_otw_spi_dev(unit), config, data, num_bits, true /*rb*/); +    return _spi_iface->transact_spi(unit_to_otw_spi_dev(unit), config, data, num_bits, true /*rb*/);  }  /***********************************************************************   * I2C   **********************************************************************/  void b100_dboard_iface::write_i2c(boost::uint8_t addr, const byte_vector_t &bytes){ -    return _iface->write_i2c(addr, bytes); +    return _i2c_iface->write_i2c(addr, bytes);  }  byte_vector_t b100_dboard_iface::read_i2c(boost::uint8_t addr, size_t num_bytes){ -    return _iface->read_i2c(addr, num_bytes); +    return _i2c_iface->read_i2c(addr, num_bytes);  }  /*********************************************************************** diff --git a/host/lib/usrp/b100/io_impl.cpp b/host/lib/usrp/b100/io_impl.cpp index 5377c43d5..00993ab41 100644 --- a/host/lib/usrp/b100/io_impl.cpp +++ b/host/lib/usrp/b100/io_impl.cpp @@ -20,8 +20,6 @@  #include "usrp_commands.h"  #include "b100_impl.hpp"  #include "b100_regs.hpp" -#include <uhd/usrp/dsp_utils.hpp> -#include <uhd/usrp/dsp_props.hpp>  #include <uhd/utils/thread_priority.hpp>  #include <uhd/transport/bounded_buffer.hpp>  #include <boost/bind.hpp> @@ -31,7 +29,6 @@  #include <boost/thread.hpp>  #include <uhd/utils/msg.hpp>  #include <uhd/utils/log.hpp> -#include <iostream>  using namespace uhd;  using namespace uhd::usrp; @@ -42,10 +39,10 @@ namespace asio = boost::asio;   * IO Implementation Details   **********************************************************************/  struct b100_impl::io_impl{ -    io_impl(zero_copy_if::sptr data_transport): +    io_impl(zero_copy_if::sptr data_transport, const size_t recv_width):          data_transport(data_transport)      { -        for (size_t i = 0; i < B100_NUM_RX_DSPS; i++){ +        for (size_t i = 0; i < recv_width; i++){              typedef bounded_buffer<managed_recv_buffer::sptr> buffs_queue_type;              _buffs_queue.push_back(new buffs_queue_type(data_transport->get_num_recv_frames()));          } @@ -76,72 +73,125 @@ struct b100_impl::io_impl{              //check the stream id to know which channel              const boost::uint32_t *vrt_hdr = buff->cast<const boost::uint32_t *>(); -            const size_t rx_index = uhd::wtohx(vrt_hdr[1]) - B100_DSP_SID_BASE; +            const size_t rx_index = uhd::wtohx(vrt_hdr[1]) - B100_RX_SID_BASE;              if (rx_index == index) return buff; //got expected message              //otherwise queue and try again -            if (rx_index < B100_NUM_RX_DSPS) _buffs_queue[rx_index]->push_with_pop_on_full(buff); +            if (rx_index < _buffs_queue.size()) _buffs_queue[rx_index]->push_with_pop_on_full(buff);              else UHD_MSG(error) << "Got a data packet with known SID " << uhd::wtohx(vrt_hdr[1]) << std::endl;          }      }      sph::recv_packet_handler recv_handler;      sph::send_packet_handler send_handler; -    bool continuous_streaming;  };  /***********************************************************************   * Initialize internals within this file   **********************************************************************/  void b100_impl::io_init(void){ -    _iface->reset_gpif(6); -    _io_impl = UHD_PIMPL_MAKE(io_impl, (_data_transport)); +    //setup rx otw type +    _rx_otw_type.width = 16; +    _rx_otw_type.shift = 0; +    _rx_otw_type.byteorder = uhd::otw_type_t::BO_BIG_ENDIAN; + +    //setup tx otw type +    _tx_otw_type.width = 16; +    _tx_otw_type.shift = 0; +    _tx_otw_type.byteorder = uhd::otw_type_t::BO_BIG_ENDIAN;      //set the expected packet size in USB frames -    _iface->poke32(B100_REG_MISC_RX_LEN, 4); +    _fpga_ctrl->poke32(B100_REG_MISC_RX_LEN, 4); + +    //create new io impl +    _io_impl = UHD_PIMPL_MAKE(io_impl, (_data_transport, _rx_dsps.size())); -    update_xport_channel_mapping(); +    //init some handler stuff +    _io_impl->recv_handler.set_vrt_unpacker(&vrt::if_hdr_unpack_le); +    _io_impl->recv_handler.set_converter(_rx_otw_type); +    _io_impl->send_handler.set_vrt_packer(&vrt::if_hdr_pack_le); +    _io_impl->send_handler.set_converter(_tx_otw_type); +    _io_impl->send_handler.set_max_samples_per_packet(get_max_send_samps_per_packet());  } -void b100_impl::update_xport_channel_mapping(void){ -    if (_io_impl.get() == NULL) return; //not inited yet -    //set all of the relevant properties on the handler +void b100_impl::update_tick_rate(const double rate){      boost::mutex::scoped_lock recv_lock = _io_impl->recv_handler.get_scoped_lock(); -    _io_impl->recv_handler.resize(_rx_subdev_spec.size()); -    _io_impl->recv_handler.set_vrt_unpacker(&vrt::if_hdr_unpack_le); -    _io_impl->recv_handler.set_tick_rate(_clock_ctrl->get_fpga_clock_rate()); -    //FIXME assumes homogeneous rates across all dsp -    _io_impl->recv_handler.set_samp_rate(_rx_dsp_proxies[_rx_dsp_proxies.keys().at(0)]->get_link()[DSP_PROP_HOST_RATE].as<double>()); -    for (size_t chan = 0; chan < _io_impl->recv_handler.size(); chan++){ -        _io_impl->recv_handler.set_xport_chan_get_buff(chan, boost::bind( -            &b100_impl::io_impl::get_recv_buff, _io_impl.get(), chan, _1 -        )); -        _io_impl->recv_handler.set_overflow_handler(chan, boost::bind( -            &b100_impl::handle_overrun, this, chan +    _io_impl->recv_handler.set_tick_rate(rate); +    boost::mutex::scoped_lock send_lock = _io_impl->send_handler.get_scoped_lock(); +    _io_impl->send_handler.set_tick_rate(rate); +} + +void b100_impl::update_rx_samp_rate(const double rate){ +    boost::mutex::scoped_lock recv_lock = _io_impl->recv_handler.get_scoped_lock(); +    _io_impl->recv_handler.set_samp_rate(rate); +} + +void b100_impl::update_tx_samp_rate(const double rate){ +    boost::mutex::scoped_lock send_lock = _io_impl->send_handler.get_scoped_lock(); +    _io_impl->send_handler.set_samp_rate(rate); +} + +void b100_impl::update_rx_subdev_spec(const uhd::usrp::subdev_spec_t &spec){ +    boost::mutex::scoped_lock recv_lock = _io_impl->recv_handler.get_scoped_lock(); +    property_tree::path_type root = "/mboards/0/dboards"; + +    //sanity checking +    if (spec.size() == 0) throw uhd::value_error("rx subdev spec cant be empty"); +    if (spec.size() > _rx_dsps.size()) throw uhd::value_error("rx subdev spec too long"); + +    //setup mux for this spec +    for (size_t i = 0; i < spec.size(); i++){ +        //ASSUME that we dont swap the rx fe mux... +        const std::string conn = _tree->access<std::string>(root / spec[i].db_name / "rx_frontends" / spec[i].sd_name / "connection").get(); +        _rx_dsps[i]->set_mux(conn); +    } + +    //resize for the new occupancy +    _io_impl->recv_handler.resize(spec.size()); + +    //bind new callbacks for the handler +    for (size_t i = 0; i < _io_impl->recv_handler.size(); i++){ +        _rx_dsps[i]->set_nsamps_per_packet(get_max_recv_samps_per_packet()); //seems to be a good place to set this +        _io_impl->recv_handler.set_xport_chan_get_buff(i, boost::bind( +            &b100_impl::io_impl::get_recv_buff, _io_impl.get(), i, _1          )); +        _io_impl->recv_handler.set_overflow_handler(i, boost::bind(&rx_dsp_core_200::handle_overflow, _rx_dsps[i]));      } -    _io_impl->recv_handler.set_converter(_recv_otw_type); +} -    //set all of the relevant properties on the handler +void b100_impl::update_tx_subdev_spec(const uhd::usrp::subdev_spec_t &spec){      boost::mutex::scoped_lock send_lock = _io_impl->send_handler.get_scoped_lock(); -    _io_impl->send_handler.resize(_tx_subdev_spec.size()); -    _io_impl->send_handler.set_vrt_packer(&vrt::if_hdr_pack_le); -    _io_impl->send_handler.set_tick_rate(_clock_ctrl->get_fpga_clock_rate()); -    //FIXME assumes homogeneous rates across all dsp -    _io_impl->send_handler.set_samp_rate(_tx_dsp_proxies[_tx_dsp_proxies.keys().at(0)]->get_link()[DSP_PROP_HOST_RATE].as<double>()); -    for (size_t chan = 0; chan < _io_impl->send_handler.size(); chan++){ -        _io_impl->send_handler.set_xport_chan_get_buff(chan, boost::bind( -            &uhd::transport::zero_copy_if::get_send_buff, _io_impl->data_transport, _1 +    property_tree::path_type root = "/mboards/0/dboards"; + +    //sanity checking +    if (spec.size() != 1) throw uhd::value_error("tx subdev spec has to be size 1"); + +    //set the mux for this spec +    const std::string conn = _tree->access<std::string>(root / spec[0].db_name / "tx_frontends" / spec[0].sd_name / "connection").get(); +    _tx_fe->set_mux(conn); + +    //resize for the new occupancy +    _io_impl->send_handler.resize(spec.size()); + +    //bind new callbacks for the handler +    for (size_t i = 0; i < _io_impl->send_handler.size(); i++){ +        _io_impl->recv_handler.set_xport_chan_get_buff(i, boost::bind( +            &zero_copy_if::get_recv_buff, _data_transport, _1          ));      } -    _io_impl->send_handler.set_converter(_send_otw_type); -    _io_impl->send_handler.set_max_samples_per_packet(get_max_send_samps_per_packet());  }  /*********************************************************************** - * Data send + helper functions + * Async Data + **********************************************************************/ +bool b100_impl::recv_async_msg(uhd::async_metadata_t &md, double timeout){ +    return _fpga_ctrl->recv_async_msg(md, timeout); +} + +/*********************************************************************** + * Send Data   **********************************************************************/  size_t b100_impl::get_max_send_samps_per_packet(void) const {      static const size_t hdr_size = 0 @@ -149,7 +199,7 @@ size_t b100_impl::get_max_send_samps_per_packet(void) const {          - sizeof(vrt::if_packet_info_t().cid) //no class id ever used      ;      static const size_t bpp = 2048 - hdr_size; -    return bpp / _send_otw_type.get_sample_size(); +    return bpp / _tx_otw_type.get_sample_size();  }  size_t b100_impl::send( @@ -165,9 +215,8 @@ size_t b100_impl::send(  }  /*********************************************************************** - * Data recv + helper functions + * Receive Data   **********************************************************************/ -  size_t b100_impl::get_max_recv_samps_per_packet(void) const {      static const size_t hdr_size = 0          + vrt::max_if_hdr_words32*sizeof(boost::uint32_t) @@ -175,7 +224,7 @@ size_t b100_impl::get_max_recv_samps_per_packet(void) const {          - sizeof(vrt::if_packet_info_t().cid) //no class id ever used      ;      size_t bpp = 2048 - hdr_size; //limited by FPGA pkt buffer size -    return bpp/_recv_otw_type.get_sample_size(); +    return bpp/_rx_otw_type.get_sample_size();  }  size_t b100_impl::recv( @@ -189,23 +238,3 @@ size_t b100_impl::recv(          recv_mode, timeout      );  } - -void b100_impl::issue_ddc_stream_cmd(const stream_cmd_t &stream_cmd, size_t index) -{ -    _io_impl->continuous_streaming = (stream_cmd.stream_mode == stream_cmd_t::STREAM_MODE_START_CONTINUOUS); -    _iface->poke32(B100_REG_RX_CTRL_STREAM_CMD(index), dsp_type1::calc_stream_cmd_word(stream_cmd)); -    _iface->poke32(B100_REG_RX_CTRL_TIME_SECS(index),  boost::uint32_t(stream_cmd.time_spec.get_full_secs())); -    _iface->poke32(B100_REG_RX_CTRL_TIME_TICKS(index), stream_cmd.time_spec.get_tick_count(_clock_ctrl->get_fpga_clock_rate())); - -    if (stream_cmd.stream_mode == stream_cmd_t::STREAM_MODE_STOP_CONTINUOUS) { -        while(_io_impl->data_transport->get_recv_buff().get() != NULL){ -            /* NOP */ -        } -    } -} - -void b100_impl::handle_overrun(size_t index){ -    if (_io_impl->continuous_streaming){ -        this->issue_ddc_stream_cmd(stream_cmd_t::STREAM_MODE_START_CONTINUOUS, index); -    } -} diff --git a/host/lib/usrp/cores/time64_core_200.cpp b/host/lib/usrp/cores/time64_core_200.cpp index 772a2a2bb..1edfef8a1 100644 --- a/host/lib/usrp/cores/time64_core_200.cpp +++ b/host/lib/usrp/cores/time64_core_200.cpp @@ -64,9 +64,9 @@ public:      uhd::time_spec_t get_time_now(void){          for (size_t i = 0; i < 3; i++){ //special algorithm because we cant read 64 bits synchronously -            const boost::uint32_t secs = _iface->peek32(_readback_bases.rb_secs_imm); -            const boost::uint32_t ticks = _iface->peek32(_readback_bases.rb_ticks_imm); -            if (secs != _iface->peek32(_readback_bases.rb_secs_imm)) continue; +            const boost::uint32_t secs = _iface->peek32(_readback_bases.rb_secs_now); +            const boost::uint32_t ticks = _iface->peek32(_readback_bases.rb_ticks_now); +            if (secs != _iface->peek32(_readback_bases.rb_secs_now)) continue;              return time_spec_t(secs, ticks, _tick_rate);          }          throw uhd::runtime_error("time64_core_200: get time now timeout"); diff --git a/host/lib/usrp/cores/time64_core_200.hpp b/host/lib/usrp/cores/time64_core_200.hpp index 4145d1f93..ebd51a02f 100644 --- a/host/lib/usrp/cores/time64_core_200.hpp +++ b/host/lib/usrp/cores/time64_core_200.hpp @@ -31,7 +31,7 @@ public:      typedef boost::shared_ptr<time64_core_200> sptr;      struct readback_bases_type{ -        size_t rb_secs_imm, rb_ticks_imm; +        size_t rb_secs_now, rb_ticks_now;          size_t rb_secs_pps, rb_ticks_pps;      }; diff --git a/host/lib/usrp/cores/wb_iface.hpp b/host/lib/usrp/cores/wb_iface.hpp index 8a873e5dc..982594b21 100644 --- a/host/lib/usrp/cores/wb_iface.hpp +++ b/host/lib/usrp/cores/wb_iface.hpp @@ -20,10 +20,9 @@  #include <uhd/config.hpp>  #include <boost/cstdint.hpp> -#include <boost/utility.hpp>  #include <boost/shared_ptr.hpp> -class wb_iface : boost::noncopyable{ +class wb_iface{  public:      typedef boost::shared_ptr<wb_iface> sptr;      typedef boost::uint32_t wb_addr_type; diff --git a/host/lib/usrp/fx2/fx2_ctrl.cpp b/host/lib/usrp/fx2/fx2_ctrl.cpp index 06ca51c25..5b2f100c6 100644 --- a/host/lib/usrp/fx2/fx2_ctrl.cpp +++ b/host/lib/usrp/fx2/fx2_ctrl.cpp @@ -409,6 +409,42 @@ public:          return usrp_control_read(VRQ_I2C_READ, i2c_addr, 0, buf, len);      } +    static const bool iface_debug = false; +    static const size_t max_i2c_data_bytes = 64; + +    void write_i2c(boost::uint8_t addr, const byte_vector_t &bytes) +    { +        UHD_ASSERT_THROW(bytes.size() < max_i2c_data_bytes); + +        unsigned char buff[max_i2c_data_bytes]; +        std::copy(bytes.begin(), bytes.end(), buff); + +        int ret = this->usrp_i2c_write(addr & 0xff, +                                             buff, +                                             bytes.size()); + +        if (iface_debug && (ret < 0)) +            uhd::runtime_error("USRP: failed i2c write"); +    } + +    byte_vector_t read_i2c(boost::uint8_t addr, size_t num_bytes) +    { +      UHD_ASSERT_THROW(num_bytes < max_i2c_data_bytes); + +      unsigned char buff[max_i2c_data_bytes]; +      int ret = this->usrp_i2c_read(addr & 0xff, +                                            buff, +                                            num_bytes); + +      if (iface_debug && ((ret < 0) || (unsigned)ret < (num_bytes))) +          uhd::runtime_error("USRP: failed i2c read"); + +      byte_vector_t out_bytes; +      for (size_t i = 0; i < num_bytes; i++) +          out_bytes.push_back(buff[i]); + +      return out_bytes; +    }  private: diff --git a/host/lib/usrp/fx2/fx2_ctrl.hpp b/host/lib/usrp/fx2/fx2_ctrl.hpp index 37fa09605..eeff6287d 100644 --- a/host/lib/usrp/fx2/fx2_ctrl.hpp +++ b/host/lib/usrp/fx2/fx2_ctrl.hpp @@ -18,13 +18,14 @@  #ifndef INCLUDED_USRP_CTRL_HPP  #define INCLUDED_USRP_CTRL_HPP -#include <uhd/transport/usb_control.hpp>  +#include <uhd/transport/usb_control.hpp> +#include <uhd/types/serial.hpp> //i2c iface  #include <boost/shared_ptr.hpp>  #include <boost/utility.hpp>  namespace uhd{ namespace usrp{ -class fx2_ctrl : boost::noncopyable{ +class fx2_ctrl : boost::noncopyable, public uhd::i2c_iface{  public:      typedef boost::shared_ptr<fx2_ctrl> sptr; diff --git a/host/lib/usrp/usrp2/usrp2_impl.cpp b/host/lib/usrp/usrp2/usrp2_impl.cpp index e00924ebd..b2092f415 100644 --- a/host/lib/usrp/usrp2/usrp2_impl.cpp +++ b/host/lib/usrp/usrp2/usrp2_impl.cpp @@ -299,7 +299,7 @@ usrp2_impl::usrp2_impl(const device_addr_t &_device_addr){          const device_addr_t device_args_i = device_args[mbi];          const std::string mb = boost::lexical_cast<std::string>(mbi);          const std::string addr = device_args_i["addr"]; -        property_tree::path_type mb_path = "/mboards/" + mb; +        const property_tree::path_type mb_path = "/mboards/" + mb;          ////////////////////////////////////////////////////////////////          // construct transports for dsp and async errors @@ -348,8 +348,8 @@ usrp2_impl::usrp2_impl(const device_addr_t &_device_addr){          ////////////////////////////////////////////////////////////////          // create codec control objects          //////////////////////////////////////////////////////////////// -        property_tree::path_type rx_codec_path = mb_path / "rx_codecs/A"; -        property_tree::path_type tx_codec_path = mb_path / "tx_codecs/A"; +        const property_tree::path_type rx_codec_path = mb_path / "rx_codecs/A"; +        const property_tree::path_type tx_codec_path = mb_path / "tx_codecs/A";          _tree->create<int>(rx_codec_path / "gains"); //phony property so this dir exists          _tree->create<int>(tx_codec_path / "gains"); //phony property so this dir exists          _mbc[mb].codec = usrp2_codec_ctrl::make(_mbc[mb].iface); @@ -472,8 +472,8 @@ usrp2_impl::usrp2_impl(const device_addr_t &_device_addr){          // create time control objects          ////////////////////////////////////////////////////////////////          time64_core_200::readback_bases_type time64_rb_bases; -        time64_rb_bases.rb_secs_imm = U2_REG_TIME64_SECS_RB_IMM; -        time64_rb_bases.rb_ticks_imm = U2_REG_TIME64_TICKS_RB_IMM; +        time64_rb_bases.rb_secs_now = U2_REG_TIME64_SECS_RB_IMM; +        time64_rb_bases.rb_ticks_now = U2_REG_TIME64_TICKS_RB_IMM;          time64_rb_bases.rb_secs_pps = U2_REG_TIME64_SECS_RB_PPS;          time64_rb_bases.rb_ticks_pps = U2_REG_TIME64_TICKS_RB_PPS;          _mbc[mb].time64 = time64_core_200::make( | 
